|
@@ -2,6 +2,7 @@ package config
|
|
|
|
|
|
import (
|
|
|
"cicv-data-closedloop/pjisuv_msgs"
|
|
|
+ "cicv-data-closedloop/pjisuv_ticker"
|
|
|
"github.com/bluenviron/goroslib/v2/pkg/msgs/geometry_msgs"
|
|
|
"github.com/bluenviron/goroslib/v2/pkg/msgs/nav_msgs"
|
|
|
"github.com/bluenviron/goroslib/v2/pkg/msgs/sensor_msgs"
|
|
@@ -13,195 +14,197 @@ import (
|
|
|
var (
|
|
|
LabelMapTriggerId = new(sync.Map)
|
|
|
|
|
|
+
|
|
|
|
|
|
- RuleOfCicvTicker = make([]func(shareVars *sync.Map), 0) // tick代表定时任务间隔时间;对于长度为0的slice,无论是使用var还是make创建,它们在内存占用上的差异通常可以忽略不计
|
|
|
+ TopicOfCicvTicker = pjisuv_ticker.TickerTopic
|
|
|
+ RuleOfCicvTicker = make([]func(shareVars *sync.Map), 0) // tick代表定时任务间隔时间;对于长度为0的slice,无论是使用var还是make创建,它们在内存占用上的差异通常可以忽略不计
|
|
|
|
|
|
-
|
|
|
+
|
|
|
TopicOfAmrPose = "/amr_pose"
|
|
|
RuleOfAmrPose1 []func(data *visualization_msgs.MarkerArray) string
|
|
|
RuleOfAmrPose3 []func(shareVars *sync.Map, data *visualization_msgs.MarkerArray) string
|
|
|
|
|
|
-
|
|
|
+
|
|
|
TopicOfBoundingBoxesFast = "/bounding_boxes_fast"
|
|
|
RuleOfBoundingBoxesFast1 []func(data *pjisuv_msgs.BoundingBoxArray) string
|
|
|
RuleOfBoundingBoxesFast3 []func(shareVars *sync.Map, data *pjisuv_msgs.BoundingBoxArray) string
|
|
|
|
|
|
-
|
|
|
+
|
|
|
TopicOfCameraFault = "/camera_fault"
|
|
|
RuleOfCameraFault1 []func(data *pjisuv_msgs.FaultVec) string
|
|
|
RuleOfCameraFault3 []func(shareVars *sync.Map, data *pjisuv_msgs.FaultVec) string
|
|
|
|
|
|
-
|
|
|
+
|
|
|
TopicOfCanData = "/can_data"
|
|
|
RuleOfCanData1 []func(data *pjisuv_msgs.Frame) string
|
|
|
RuleOfCanData3 []func(shareVars *sync.Map, data *pjisuv_msgs.Frame) string
|
|
|
|
|
|
-
|
|
|
+
|
|
|
TopicOfCh128x1LslidarPointCloud = "/ch128x1/lslidar_point_cloud"
|
|
|
RuleOfCh128x1LslidarPointCloud1 []func(data *sensor_msgs.PointCloud2) string
|
|
|
RuleOfCh128x1LslidarPointCloud3 []func(shareVars *sync.Map, data *sensor_msgs.PointCloud2) string
|
|
|
|
|
|
-
|
|
|
+
|
|
|
TopicOfCh64wLLslidarPointCloud = "/ch64w_l/lslidar_point_cloud"
|
|
|
RuleOfCh64wLLslidarPointCloud1 []func(data *sensor_msgs.PointCloud2) string
|
|
|
RuleOfCh64wLLslidarPointCloud3 []func(shareVars *sync.Map, data *sensor_msgs.PointCloud2) string
|
|
|
|
|
|
-
|
|
|
+
|
|
|
TopicOfCh64wLScan = "/ch64w_l/scan"
|
|
|
RuleOfCh64wLScan1 []func(data *sensor_msgs.LaserScan) string
|
|
|
RuleOfCh64wLScan3 []func(shareVars *sync.Map, data *sensor_msgs.LaserScan) string
|
|
|
|
|
|
-
|
|
|
+
|
|
|
TopicOfCh64wRLslidarPointCloud = "/ch64w_r/lslidar_point_cloud"
|
|
|
RuleOfCh64wRLslidarPointCloud1 []func(data *sensor_msgs.PointCloud2) string
|
|
|
RuleOfCh64wRLslidarPointCloud3 []func(shareVars *sync.Map, data *sensor_msgs.PointCloud2) string
|
|
|
|
|
|
-
|
|
|
+
|
|
|
TopicOfCh64wRScan = "/ch64w_r/scan"
|
|
|
RuleOfCh64wRScan1 []func(data *sensor_msgs.LaserScan) string
|
|
|
RuleOfCh64wRScan3 []func(shareVars *sync.Map, data *sensor_msgs.LaserScan) string
|
|
|
|
|
|
-
|
|
|
+
|
|
|
TopicOfCicvLidarclusterMovingObjects = "/cicv/lidarcluster_moving_objects"
|
|
|
RuleOfCicvLidarclusterMovingObjects1 []func(data *pjisuv_msgs.PerceptionCicvMovingObjects) string
|
|
|
RuleOfCicvLidarclusterMovingObjects3 []func(shareVars *sync.Map, data *pjisuv_msgs.PerceptionCicvMovingObjects) string
|
|
|
|
|
|
-
|
|
|
+
|
|
|
TopicOfCicvAmrTrajectory = "/cicv_amr_trajectory"
|
|
|
RuleOfCicvAmrTrajectory1 []func(data *pjisuv_msgs.Trajectory) string
|
|
|
RuleOfCicvAmrTrajectory3 []func(shareVars *sync.Map, data *pjisuv_msgs.Trajectory) string
|
|
|
|
|
|
-
|
|
|
+
|
|
|
TopicOfCicvLocation = "/cicv_location"
|
|
|
RuleOfCicvLocation1 []func(data *pjisuv_msgs.PerceptionLocalization) string
|
|
|
RuleOfCicvLocation3 []func(shareVars *sync.Map, data *pjisuv_msgs.PerceptionLocalization) string
|
|
|
|
|
|
-
|
|
|
+
|
|
|
TopicOfCloudClusters = "/cloud_clusters"
|
|
|
RuleOfCloudClusters1 []func(data *pjisuv_msgs.AutowareCloudClusterArray) string
|
|
|
RuleOfCloudClusters3 []func(shareVars *sync.Map, data *pjisuv_msgs.AutowareCloudClusterArray) string
|
|
|
|
|
|
-
|
|
|
+
|
|
|
TopicOfHeartbeatInfo = "/heartbeat_info"
|
|
|
RuleOfHeartbeatInfo1 []func(data *pjisuv_msgs.HeartBeatInfo) string
|
|
|
RuleOfHeartbeatInfo3 []func(shareVars *sync.Map, data *pjisuv_msgs.HeartBeatInfo) string
|
|
|
|
|
|
-
|
|
|
+
|
|
|
TopicOfLidarPretreatmentCost = "/lidarPretreatment_Cost"
|
|
|
RuleOfLidarPretreatmentCost1 []func(data *geometry_msgs.Vector3Stamped) string
|
|
|
RuleOfLidarPretreatmentCost3 []func(shareVars *sync.Map, data *geometry_msgs.Vector3Stamped) string
|
|
|
|
|
|
-
|
|
|
+
|
|
|
TopicOfLidarPretreatmentOdometry = "/lidar_pretreatment/odometry"
|
|
|
RuleOfLidarPretreatmentOdometry1 []func(data *nav_msgs.Odometry) string
|
|
|
RuleOfLidarPretreatmentOdometry3 []func(shareVars *sync.Map, data *nav_msgs.Odometry) string
|
|
|
|
|
|
-
|
|
|
+
|
|
|
TopicOfLidarRoi = "/lidar_roi"
|
|
|
RuleOfLidarRoi1 []func(data *geometry_msgs.PolygonStamped) string
|
|
|
RuleOfLidarRoi3 []func(shareVars *sync.Map, data *geometry_msgs.PolygonStamped) string
|
|
|
|
|
|
-
|
|
|
+
|
|
|
TopicOfLine1 = "/line_1"
|
|
|
RuleOfLine11 []func(data *nav_msgs.Path) string
|
|
|
RuleOfLine13 []func(shareVars *sync.Map, data *nav_msgs.Path) string
|
|
|
|
|
|
-
|
|
|
+
|
|
|
TopicOfLine2 = "/line_2"
|
|
|
RuleOfLine21 []func(data *nav_msgs.Path) string
|
|
|
RuleOfLine23 []func(shareVars *sync.Map, data *nav_msgs.Path) string
|
|
|
|
|
|
-
|
|
|
+
|
|
|
TopicOfMapPolygon = "/map_polygon"
|
|
|
RuleOfMapPolygon1 []func(data *pjisuv_msgs.PolygonStamped) string
|
|
|
RuleOfMapPolygon3 []func(shareVars *sync.Map, data *pjisuv_msgs.PolygonStamped) string
|
|
|
|
|
|
-
|
|
|
+
|
|
|
TopicOfObstacleDisplay = "/obstacle_display"
|
|
|
RuleOfObstacleDisplay1 []func(data *visualization_msgs.MarkerArray) string
|
|
|
RuleOfObstacleDisplay3 []func(shareVars *sync.Map, data *visualization_msgs.MarkerArray) string
|
|
|
|
|
|
-
|
|
|
+
|
|
|
TopicOfPjControlPub = "/pj_control_pub"
|
|
|
RuleOfPjControlPub1 []func(data *pjisuv_msgs.CommonVehicleCmd) string
|
|
|
RuleOfPjControlPub3 []func(shareVars *sync.Map, data *pjisuv_msgs.CommonVehicleCmd) string
|
|
|
|
|
|
-
|
|
|
+
|
|
|
TopicOfPointsCluster = "/points_cluster"
|
|
|
RuleOfPointsCluster1 []func(data *sensor_msgs.PointCloud2) string
|
|
|
RuleOfPointsCluster3 []func(shareVars *sync.Map, data *sensor_msgs.PointCloud2) string
|
|
|
|
|
|
-
|
|
|
+
|
|
|
TopicOfPointsConcat = "/points_concat"
|
|
|
RuleOfPointsConcat1 []func(data *sensor_msgs.PointCloud2) string
|
|
|
RuleOfPointsConcat3 []func(shareVars *sync.Map, data *sensor_msgs.PointCloud2) string
|
|
|
|
|
|
-
|
|
|
+
|
|
|
TopicOfReferenceDisplay = "/reference_display"
|
|
|
RuleOfReferenceDisplay1 []func(data *nav_msgs.Path) string
|
|
|
RuleOfReferenceDisplay3 []func(shareVars *sync.Map, data *nav_msgs.Path) string
|
|
|
|
|
|
-
|
|
|
+
|
|
|
TopicOfReferenceTrajectory = "/reference_trajectory"
|
|
|
RuleOfReferenceTrajectory1 []func(data *pjisuv_msgs.Trajectory) string
|
|
|
RuleOfReferenceTrajectory3 []func(shareVars *sync.Map, data *pjisuv_msgs.Trajectory) string
|
|
|
|
|
|
-
|
|
|
+
|
|
|
TopicOfRoiPoints = "/roi/points"
|
|
|
RuleOfRoiPoints1 []func(data *sensor_msgs.PointCloud2) string
|
|
|
RuleOfRoiPoints3 []func(shareVars *sync.Map, data *sensor_msgs.PointCloud2) string
|
|
|
|
|
|
-
|
|
|
+
|
|
|
TopicOfRoiPolygon = "/roi/polygon"
|
|
|
RuleOfRoiPolygon1 []func(data *nav_msgs.Path) string
|
|
|
RuleOfRoiPolygon3 []func(shareVars *sync.Map, data *nav_msgs.Path) string
|
|
|
|
|
|
-
|
|
|
+
|
|
|
TopicOfTf = "/tf"
|
|
|
RuleOfTf1 []func(data *tf2_msgs.TFMessage) string
|
|
|
RuleOfTf3 []func(shareVars *sync.Map, data *tf2_msgs.TFMessage) string
|
|
|
|
|
|
-
|
|
|
+
|
|
|
TopicOfTpperception = "/tpperception"
|
|
|
RuleOfTpperception1 []func(data *pjisuv_msgs.PerceptionObjects) string
|
|
|
RuleOfTpperception3 []func(shareVars *sync.Map, data *pjisuv_msgs.PerceptionObjects) string
|
|
|
|
|
|
-
|
|
|
+
|
|
|
TopicOfTpperceptionVis = "/tpperception/vis"
|
|
|
RuleOfTpperceptionVis1 []func(data *visualization_msgs.MarkerArray) string
|
|
|
RuleOfTpperceptionVis3 []func(shareVars *sync.Map, data *visualization_msgs.MarkerArray) string
|
|
|
|
|
|
-
|
|
|
+
|
|
|
TopicOfTprouteplan = "/tprouteplan"
|
|
|
RuleOfTprouteplan1 []func(data *pjisuv_msgs.RoutePlan) string
|
|
|
RuleOfTprouteplan3 []func(shareVars *sync.Map, data *pjisuv_msgs.RoutePlan) string
|
|
|
|
|
|
-
|
|
|
+
|
|
|
TopicOfTrajectoryDisplay = "/trajectory_display"
|
|
|
RuleOfTrajectoryDisplay1 []func(data *nav_msgs.Path) string
|
|
|
RuleOfTrajectoryDisplay3 []func(shareVars *sync.Map, data *nav_msgs.Path) string
|
|
|
|
|
|
-
|
|
|
+
|
|
|
TopicOfUngroundCloudpoints = "/unground_cloudpoints"
|
|
|
RuleOfUngroundCloudpoints1 []func(data *sensor_msgs.PointCloud2) string
|
|
|
RuleOfUngroundCloudpoints3 []func(shareVars *sync.Map, data *sensor_msgs.PointCloud2) string
|
|
|
|
|
|
-
|
|
|
+
|
|
|
TopicOfCameraImage = "/camera_image"
|
|
|
RuleOfCameraImage1 []func(data *sensor_msgs.Image) string
|
|
|
RuleOfCameraImage3 []func(shareVars *sync.Map, data *sensor_msgs.Image) string
|
|
|
|
|
|
-
|
|
|
+
|
|
|
TopicOfDataRead = "/data_read"
|
|
|
RuleOfDataRead1 []func(data *pjisuv_msgs.Retrieval) string
|
|
|
RuleOfDataRead3 []func(shareVars *sync.Map, data *pjisuv_msgs.Retrieval) string
|
|
|
|
|
|
-
|
|
|
+
|
|
|
TopicOfPjiGps = "/pji_gps"
|
|
|
RuleOfPjiGps1 []func(data *pjisuv_msgs.PerceptionLocalization) string
|
|
|
RuleOfPjiGps3 []func(shareVars *sync.Map, data *pjisuv_msgs.PerceptionLocalization) string
|
|
|
|
|
|
-
|
|
|
+
|
|
|
TopicOfFaultInfo = "/fault_info"
|
|
|
RuleOfFaultInfo1 []func(data *pjisuv_msgs.FaultVec) string
|
|
|
RuleOfFaultInfo3 []func(shareVars *sync.Map, data *pjisuv_msgs.FaultVec) string
|
|
@@ -215,4 +218,51 @@ var (
|
|
|
TopicOfEndPointMessage = "/end_point_message"
|
|
|
RuleOfEndPointMessage1 []func(data *geometry_msgs.Point) string
|
|
|
RuleOfEndPointMessage3 []func(shareVars *sync.Map, data *geometry_msgs.Point) string
|
|
|
+
|
|
|
+
|
|
|
+ AllTopics = []string{
|
|
|
+ TopicOfCicvTicker,
|
|
|
+ TopicOfAmrPose,
|
|
|
+ TopicOfBoundingBoxesFast,
|
|
|
+ TopicOfCameraFault,
|
|
|
+ TopicOfCanData,
|
|
|
+ TopicOfCh128x1LslidarPointCloud,
|
|
|
+ TopicOfCh64wLLslidarPointCloud,
|
|
|
+ TopicOfCh64wLScan,
|
|
|
+ TopicOfCh64wRLslidarPointCloud,
|
|
|
+ TopicOfCh64wRScan,
|
|
|
+ TopicOfCicvLidarclusterMovingObjects,
|
|
|
+ TopicOfCicvAmrTrajectory,
|
|
|
+ TopicOfCicvLocation,
|
|
|
+ TopicOfCloudClusters,
|
|
|
+ TopicOfHeartbeatInfo,
|
|
|
+ TopicOfLidarPretreatmentCost,
|
|
|
+ TopicOfLidarPretreatmentOdometry,
|
|
|
+ TopicOfLidarRoi,
|
|
|
+ TopicOfLine1,
|
|
|
+ TopicOfLine2,
|
|
|
+ TopicOfMapPolygon,
|
|
|
+ TopicOfObstacleDisplay,
|
|
|
+ TopicOfPjControlPub,
|
|
|
+ TopicOfPointsCluster,
|
|
|
+ TopicOfPointsConcat,
|
|
|
+ TopicOfReferenceDisplay,
|
|
|
+ TopicOfReferenceTrajectory,
|
|
|
+ TopicOfRoiPoints,
|
|
|
+ TopicOfRoiPolygon,
|
|
|
+ TopicOfTf,
|
|
|
+ TopicOfTpperception,
|
|
|
+ TopicOfTpperceptionVis,
|
|
|
+ TopicOfTprouteplan,
|
|
|
+ TopicOfTrajectoryDisplay,
|
|
|
+ TopicOfUngroundCloudpoints,
|
|
|
+ TopicOfCameraImage,
|
|
|
+ TopicOfDataRead,
|
|
|
+ TopicOfPjiGps,
|
|
|
+ TopicOfFaultInfo,
|
|
|
+ TopicOfPjVehicleFdbPub,
|
|
|
+ TopicOfEndPointMessage,
|
|
|
+ }
|
|
|
+
|
|
|
+ AllTopicsNumber = len(AllTopics)
|
|
|
)
|