From a6095979aa5a4747d2e37e9691f4d5b55c9de51d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Sch=C3=BCtte?= Date: Mon, 8 Jan 2018 11:10:14 +0100 Subject: [PATCH] Make MapBuilderBridge use GetAllTrajectoryNodePoses() (#649) --- cartographer_ros/cartographer_ros/map_builder_bridge.cc | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/cartographer_ros/cartographer_ros/map_builder_bridge.cc b/cartographer_ros/cartographer_ros/map_builder_bridge.cc index c175d1e..e42b10d 100644 --- a/cartographer_ros/cartographer_ros/map_builder_bridge.cc +++ b/cartographer_ros/cartographer_ros/map_builder_bridge.cc @@ -201,13 +201,13 @@ MapBuilderBridge::GetTrajectoryStates() { visualization_msgs::MarkerArray MapBuilderBridge::GetTrajectoryNodeList() { visualization_msgs::MarkerArray trajectory_node_list; - const auto nodes = map_builder_->pose_graph()->GetTrajectoryNodes(); - for (const int trajectory_id : nodes.trajectory_ids()) { + const auto node_poses = map_builder_->pose_graph()->GetTrajectoryNodePoses(); + for (const int trajectory_id : node_poses.trajectory_ids()) { visualization_msgs::Marker marker = CreateTrajectoryMarker(trajectory_id, node_options_.map_frame); - for (const auto& node_id_data : nodes.trajectory(trajectory_id)) { - if (node_id_data.data.constant_data == nullptr) { + for (const auto& node_id_data : node_poses.trajectory(trajectory_id)) { + if (node_id_data.data.has_constant_data) { PushAndResetLineMarker(&marker, &trajectory_node_list.markers); continue; }