Commit e2e8c3ef authored by oscar's avatar oscar

提交发送

parent db98ee5d
......@@ -299,7 +299,7 @@ void TrackingRos::Init(ros::NodeHandle& nh)
m_pub = nh.advertise<jfx_common_msgs::det_tracking_array>("/tracking_res", 100);
m_pubCloud = nh.advertise<sensor_msgs::PointCloud2>("/tracking_cloud", 100);
m_pubBoundingBoxes = nh.advertise<jsk_recognition_msgs::BoundingBoxArray>("/tracking_bbox", 100);
m_pubMarker = nh.advertise<visualization_msgs::MarkerArray>("/tracking_loc", 100);
m_objsQueue.set_max_num_items(2);
......@@ -829,6 +829,7 @@ void TrackingRos::ThreadTrackingProcess()
m_pubBoundingBoxes.publish(sendBoxes);
objsPtr->cloud.header.frame_id = "/rslidar";
m_pubCloud.publish(objsPtr->cloud);
m_pubMarker.publish(markerArray);
#ifdef _USING_NSIGHT_
nvtxRangePop();
#endif
......
......@@ -50,6 +50,7 @@ public:
ros::Publisher m_pub;//发送所有物体信息的publisher
ros::Publisher m_pubCloud;//发送点云数据
ros::Publisher m_pubBoundingBoxes;//发送3D框信息
ros::Publisher m_pubMarker;//发送marker信息
std::vector<std::vector<double>> m_trans;
std::vector<std::vector<double>> m_kitti2origin;
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment