diff --git a/cartographer_ros/cartographer_ros/assets_writer_main.cc b/cartographer_ros/cartographer_ros/assets_writer_main.cc index b4c356f..4cc09f7 100644 --- a/cartographer_ros/cartographer_ros/assets_writer_main.cc +++ b/cartographer_ros/cartographer_ros/assets_writer_main.cc @@ -28,6 +28,7 @@ #include "cartographer/io/points_processor_pipeline_builder.h" #include "cartographer/io/proto_stream.h" #include "cartographer/mapping/proto/pose_graph.pb.h" +#include "cartographer/mapping/proto/trajectory_builder_options.pb.h" #include "cartographer/sensor/point_cloud.h" #include "cartographer/sensor/range_data.h" #include "cartographer/transform/transform_interpolation_buffer.h" @@ -135,6 +136,9 @@ void Run(const std::string& pose_graph_filename, carto::io::ProtoStreamReader reader(pose_graph_filename); carto::mapping::proto::PoseGraph pose_graph_proto; CHECK(reader.ReadProto(&pose_graph_proto)); + ::cartographer::mapping::proto::AllTrajectoryBuilderOptions + all_trajectory_builder_options; + CHECK(reader.ReadProto(&all_trajectory_builder_options)); CHECK_EQ(pose_graph_proto.trajectory_size(), bag_filenames.size()) << "Pose graphs contains " << pose_graph_proto.trajectory_size() << " trajectories while " << bag_filenames.size() diff --git a/cartographer_ros/cartographer_ros/pbstream_to_ros_map_main.cc b/cartographer_ros/cartographer_ros/pbstream_to_ros_map_main.cc index be0ca42..0ab2025 100644 --- a/cartographer_ros/cartographer_ros/pbstream_to_ros_map_main.cc +++ b/cartographer_ros/cartographer_ros/pbstream_to_ros_map_main.cc @@ -22,7 +22,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/mapping_2d/probability_grid.h" #include "cartographer/mapping_2d/submaps.h" #include "cartographer/mapping_3d/submaps.h" @@ -45,6 +45,9 @@ void Run(const std::string& pbstream_filename, const std::string& map_filestem, ::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>