Commit b903f7ee authored by oscar's avatar oscar

update

parent 57010ec4
......@@ -33,7 +33,10 @@ TrackingRos2::TrackingRos2(const rclcpp::NodeOptions& node_options)
std::placeholders::_1));
std::string pub_topic = "/perception/object_recognition/tracking/objects";
m_tracking_res = this->create_publisher<
wit_perception_msgs::msg::TrackedObjectsEx>(pub_topic, 10);
autoware_auto_perception_msgs::msg::TrackedObjects>(pub_topic, 10);
std::string pub_topic_ex = "/perception/object_recognition/tracking/objects_ex";
m_tracking_res_ex = this->create_publisher<
wit_perception_msgs::msg::TrackedObjectsEx>(pub_topic_ex, 10);
m_pubMarker = this->create_publisher<visualization_msgs::msg::MarkerArray>(
"output/sensors_fusion_obj_markers", 10);
m_pubMarkerText = this->create_publisher<visualization_msgs::msg::MarkerArray>(
......@@ -417,9 +420,9 @@ void TrackingRos2::TrackingPorcess(objTrackListPtr objsPtr) {
markerText.color.b = 0.0f;
markerText.color.a = 1.0;
char str[512] = {};
sprintf(str, "%lld:%.2f",iter.first,linear.x);
// sprintf(str, "%lld:%.2f",iter.first,linear.x);
// sprintf(str, "%.1f:%d:%d",cof,iter.first,obj.classification[0].label);
// sprintf(str, "%.2f:%d:%.2f:%.2f",cof,obj.classification[0].label,poss.x,linear.x);
sprintf(str, "%.2f:%d:%.2f:%.2f",cof,obj.classification[0].label,poss.y,poss.x);
markerText.text = str;
makerTextArray.markers.emplace_back(markerText);
RCLCPP_INFO(this->get_logger(),"tracking obj info id = %lld, label = %d,cof = %.2f,pos = [%.2f,%.2f,%.2f],linear = [%.2f,%.2f]",
......@@ -498,13 +501,14 @@ void TrackingRos2::TrackingPorcess(objTrackListPtr objsPtr) {
float(pt[5] - pt[4])/1000,float(pt[6] - pt[5])/1000,float(pt[7] - pt[6])/1000,float(pt[8] - pt[7])/1000,float(GetCurTime() - start_timestamp)/1000);
beginPrint = GetCurTime();
}
m_tracking_res->publish(sendObjs);
sendObjsEx.tracks = sendObjs;
sendObjsEx.pt = objsPtr->pt;
sendObjsEx.pt.push_back(GetCurTime());
//打印时间戳
//(top收到的时间戳,三个点云同步完成时间戳,点云拼接完的时间戳,点云检测完成时间,检测结果发送时间)
// (收到检测结果时间戳,与相机融合之后的时间戳,融合之后发送的时间戳,tracking收到消息时间戳,tracking发送的时间戳)
m_tracking_res->publish(sendObjsEx);
m_tracking_res_ex->publish(sendObjsEx);
m_pubMarker->publish(makerArray);
m_pubMarkerText->publish(makerTextArray);
// m_pubBoundingBoxes.publish(sendBoxes);
......
......@@ -35,7 +35,8 @@ class TrackingRos2 : public rclcpp::Node {
private:
rclcpp::Subscription<wit_perception_msgs::msg::DetectedObjectsWithFeatureEx>::SharedPtr m_fusion_res;
rclcpp::Publisher<wit_perception_msgs::msg::TrackedObjectsEx>::SharedPtr m_tracking_res;
rclcpp::Publisher<autoware_auto_perception_msgs::msg::TrackedObjects>::SharedPtr m_tracking_res;
rclcpp::Publisher<wit_perception_msgs::msg::TrackedObjectsEx>::SharedPtr m_tracking_res_ex;
rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr m_pubMarker;
rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr m_pubMarkerText;
......
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