From d34a2e36b8e172a7bad2fd6ee70b81d15b73a85c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Sch=C3=BCtte?= Date: Fri, 5 Jan 2018 15:10:52 +0100 Subject: [PATCH] Make MapBuilderBridge::GetSubmapList() use GetAllSubmapPoses() (#647) --- .../cartographer_ros/map_builder_bridge.cc | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/cartographer_ros/cartographer_ros/map_builder_bridge.cc b/cartographer_ros/cartographer_ros/map_builder_bridge.cc index 932a40a..c175d1e 100644 --- a/cartographer_ros/cartographer_ros/map_builder_bridge.cc +++ b/cartographer_ros/cartographer_ros/map_builder_bridge.cc @@ -158,13 +158,13 @@ cartographer_ros_msgs::SubmapList MapBuilderBridge::GetSubmapList() { cartographer_ros_msgs::SubmapList submap_list; submap_list.header.stamp = ::ros::Time::now(); submap_list.header.frame_id = node_options_.map_frame; - for (const auto& submap_id_data : - map_builder_->pose_graph()->GetAllSubmapData()) { + for (const auto& submap_id_pose : + map_builder_->pose_graph()->GetAllSubmapPoses()) { cartographer_ros_msgs::SubmapEntry submap_entry; - submap_entry.trajectory_id = submap_id_data.id.trajectory_id; - submap_entry.submap_index = submap_id_data.id.submap_index; - submap_entry.submap_version = submap_id_data.data.submap->num_range_data(); - submap_entry.pose = ToGeometryMsgPose(submap_id_data.data.pose); + submap_entry.trajectory_id = submap_id_pose.id.trajectory_id; + submap_entry.submap_index = submap_id_pose.id.submap_index; + submap_entry.submap_version = submap_id_pose.data.version; + submap_entry.pose = ToGeometryMsgPose(submap_id_pose.data.pose); submap_list.submap.push_back(submap_entry); } return submap_list;