From 289e4314bec3bc9b7340a3e297cd0b538a10abb9 Mon Sep 17 00:00:00 2001 From: Michael Grupp Date: Wed, 28 Feb 2018 16:36:50 +0100 Subject: [PATCH] Fix pbstream_map_publisher (follow #712) (#745) Applies the proto deserialization changes that were introduced in PR #712. --- .../cartographer_ros/pbstream_map_publisher_main.cc | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/cartographer_ros/cartographer_ros/pbstream_map_publisher_main.cc b/cartographer_ros/cartographer_ros/pbstream_map_publisher_main.cc index a9be180..5841b4c 100644 --- a/cartographer_ros/cartographer_ros/pbstream_map_publisher_main.cc +++ b/cartographer_ros/cartographer_ros/pbstream_map_publisher_main.cc @@ -27,7 +27,7 @@ #include "cartographer/mapping/proto/pose_graph.pb.h" #include "cartographer/mapping/proto/serialization.pb.h" #include "cartographer/mapping/proto/submap.pb.h" -#include "cartographer/mapping/submaps.h" +#include "cartographer/mapping/proto/trajectory_builder_options.pb.h" #include "cartographer_ros/msg_conversion.h" #include "cartographer_ros/node_constants.h" #include "cartographer_ros/ros_log_sink.h" @@ -53,6 +53,9 @@ void Run(const std::string& pbstream_filename, const std::string& map_topic, ::cartographer::mapping::proto::PoseGraph pose_graph; CHECK(reader.ReadProto(&pose_graph)); + ::cartographer::mapping::proto::AllTrajectoryBuilderOptions + all_trajectory_builder_options; + CHECK(reader.ReadProto(&all_trajectory_builder_options)); LOG(INFO) << "Loading submap slices from serialized data."; std::map<::cartographer::mapping::SubmapId, ::cartographer::io::SubmapSlice>