Follow googlecartographer/cartographer#859 (#712)

master
Christoph Schütte 2018-02-07 16:24:20 +01:00 committed by Wally B. Feed
parent 512a9cc358
commit 5cd81be61e
2 changed files with 8 additions and 1 deletions

View File

@ -28,6 +28,7 @@
#include "cartographer/io/points_processor_pipeline_builder.h" #include "cartographer/io/points_processor_pipeline_builder.h"
#include "cartographer/io/proto_stream.h" #include "cartographer/io/proto_stream.h"
#include "cartographer/mapping/proto/pose_graph.pb.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/point_cloud.h"
#include "cartographer/sensor/range_data.h" #include "cartographer/sensor/range_data.h"
#include "cartographer/transform/transform_interpolation_buffer.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::io::ProtoStreamReader reader(pose_graph_filename);
carto::mapping::proto::PoseGraph pose_graph_proto; carto::mapping::proto::PoseGraph pose_graph_proto;
CHECK(reader.ReadProto(&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()) CHECK_EQ(pose_graph_proto.trajectory_size(), bag_filenames.size())
<< "Pose graphs contains " << pose_graph_proto.trajectory_size() << "Pose graphs contains " << pose_graph_proto.trajectory_size()
<< " trajectories while " << bag_filenames.size() << " trajectories while " << bag_filenames.size()

View File

@ -22,7 +22,7 @@
#include "cartographer/mapping/proto/pose_graph.pb.h" #include "cartographer/mapping/proto/pose_graph.pb.h"
#include "cartographer/mapping/proto/serialization.pb.h" #include "cartographer/mapping/proto/serialization.pb.h"
#include "cartographer/mapping/proto/submap.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/probability_grid.h"
#include "cartographer/mapping_2d/submaps.h" #include "cartographer/mapping_2d/submaps.h"
#include "cartographer/mapping_3d/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; ::cartographer::mapping::proto::PoseGraph pose_graph;
CHECK(reader.ReadProto(&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."; LOG(INFO) << "Loading submap slices from serialized data.";
std::map<::cartographer::mapping::SubmapId, ::cartographer::io::SubmapSlice> std::map<::cartographer::mapping::SubmapId, ::cartographer::io::SubmapSlice>