From 7a7b210c94aa02dcafe7aa9a3b64bc2e32b6f333 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Sch=C3=BCtte?= Date: Mon, 8 Jan 2018 18:52:27 +0100 Subject: [PATCH] Fix bug in MapBuilderBridge::GetTrajectoryStates() (#652) --- cartographer_ros/cartographer_ros/map_builder_bridge.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cartographer_ros/cartographer_ros/map_builder_bridge.cc b/cartographer_ros/cartographer_ros/map_builder_bridge.cc index bb114e5..7968065 100644 --- a/cartographer_ros/cartographer_ros/map_builder_bridge.cc +++ b/cartographer_ros/cartographer_ros/map_builder_bridge.cc @@ -207,7 +207,7 @@ visualization_msgs::MarkerArray MapBuilderBridge::GetTrajectoryNodeList() { CreateTrajectoryMarker(trajectory_id, node_options_.map_frame); for (const auto& node_id_data : node_poses.trajectory(trajectory_id)) { - if (node_id_data.data.has_constant_data) { + if (!node_id_data.data.has_constant_data) { PushAndResetLineMarker(&marker, &trajectory_node_list.markers); continue; }