From 7f616b4cc701e587eb7fe0193ef1fabf4a9c5781 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Juraj=20Or=C5=A1uli=C4=87?= Date: Mon, 7 Aug 2017 15:59:41 +0200 Subject: [PATCH] Use trajectory ID as namespace for trajectory marker (#473) Also simplifies marker IDs since they must only be unique within a unique namespace. --- cartographer_ros/cartographer_ros/map_builder_bridge.cc | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/cartographer_ros/cartographer_ros/map_builder_bridge.cc b/cartographer_ros/cartographer_ros/map_builder_bridge.cc index 71a87bc..6343430 100644 --- a/cartographer_ros/cartographer_ros/map_builder_bridge.cc +++ b/cartographer_ros/cartographer_ros/map_builder_bridge.cc @@ -169,13 +169,13 @@ visualization_msgs::MarkerArray MapBuilderBridge::GetTrajectoryNodeList() { visualization_msgs::MarkerArray trajectory_node_list; const auto all_trajectory_nodes = map_builder_.sparse_pose_graph()->GetTrajectoryNodes(); - int marker_id = 0; for (int trajectory_id = 0; trajectory_id < static_cast(all_trajectory_nodes.size()); ++trajectory_id) { const auto& single_trajectory_nodes = all_trajectory_nodes[trajectory_id]; visualization_msgs::Marker marker; - marker.id = marker_id++; + marker.ns = "Trajectory " + std::to_string(trajectory_id); + marker.id = 0; marker.type = visualization_msgs::Marker::LINE_STRIP; marker.header.stamp = ::ros::Time::now(); marker.header.frame_id = node_options_.map_frame; @@ -198,7 +198,7 @@ visualization_msgs::MarkerArray MapBuilderBridge::GetTrajectoryNodeList() { // trajectory into multiple markers. if (marker.points.size() == 16384) { trajectory_node_list.markers.push_back(marker); - marker.id = marker_id++; + ++marker.id; marker.points.clear(); // Push back the last point, so the two markers appear connected. marker.points.push_back(node_point);