Skip to content

Commit

Permalink
Fix rviz trajectory rendering crash (cartographer-project#367)
Browse files Browse the repository at this point in the history
Rviz has a limit of 16384 points per marker. To get around this, each
trajectory is split into multiple markers, each up to 16384 points.
Fixes cartographer-project#366.
  • Loading branch information
ojura authored and wohe committed Jun 9, 2017
1 parent 51fe6fa commit 6658cff
Showing 1 changed file with 12 additions and 2 deletions.
14 changes: 12 additions & 2 deletions cartographer_ros/cartographer_ros/map_builder_bridge.cc
Original file line number Diff line number Diff line change
Expand Up @@ -217,8 +217,18 @@ visualization_msgs::MarkerArray MapBuilderBridge::GetTrajectoryNodesList() {
marker.scale.x = kTrajectoryLineStripMarkerScale;
marker.pose.orientation.w = 1.0;
for (const auto& node : single_trajectory) {
marker.points.push_back(ToGeometryMsgPoint(
(node.pose * node.constant_data->tracking_to_pose).translation()));
const ::geometry_msgs::Point node_point = ToGeometryMsgPoint(
(node.pose * node.constant_data->tracking_to_pose).translation());
marker.points.push_back(node_point);
// Work around the 16384 point limit in rviz by splitting the
// trajectory into multiple markers.
if (marker.points.size() == 16384) {
trajectory_nodes_list.markers.push_back(marker);
marker.id = marker_id++;
marker.points.clear();
// Push back the last point, so the two markers appear connected.
marker.points.push_back(node_point);
}
}
trajectory_nodes_list.markers.push_back(marker);
}
Expand Down

0 comments on commit 6658cff

Please sign in to comment.