Cartographer API changes. (#146)

master
Wolfgang Hess 2016-10-26 09:18:01 +02:00 committed by Damon Kohler
parent 26e956678f
commit 094e319d4a
3 changed files with 4 additions and 4 deletions

View File

@ -21,8 +21,8 @@
#include "cartographer/io/ply_writing_points_processor.h" #include "cartographer/io/ply_writing_points_processor.h"
#include "cartographer/io/points_processor.h" #include "cartographer/io/points_processor.h"
#include "cartographer/io/xray_points_processor.h" #include "cartographer/io/xray_points_processor.h"
#include "cartographer/mapping/proto/trajectory.pb.h"
#include "cartographer/mapping_2d/proto/laser_fan_inserter_options.pb.h" #include "cartographer/mapping_2d/proto/laser_fan_inserter_options.pb.h"
#include "cartographer/proto/trajectory.pb.h"
#include "cartographer_ros/map_writer.h" #include "cartographer_ros/map_writer.h"
#include "cartographer_ros/occupancy_grid.h" #include "cartographer_ros/occupancy_grid.h"
#include "nav_msgs/OccupancyGrid.h" #include "nav_msgs/OccupancyGrid.h"
@ -89,7 +89,7 @@ void WriteAssets(const std::vector<::cartographer::mapping::TrajectoryNode>&
// Write the trajectory. // Write the trajectory.
std::ofstream proto_file(stem + ".pb", std::ofstream proto_file(stem + ".pb",
std::ios_base::out | std::ios_base::binary); std::ios_base::out | std::ios_base::binary);
const carto::proto::Trajectory trajectory = const carto::mapping::proto::Trajectory trajectory =
carto::mapping::ToProto(trajectory_nodes); carto::mapping::ToProto(trajectory_nodes);
CHECK(trajectory.SerializeToOstream(&proto_file)) CHECK(trajectory.SerializeToOstream(&proto_file))
<< "Could not serialize trajectory."; << "Could not serialize trajectory.";

View File

@ -59,7 +59,7 @@ namespace carto = ::cartographer;
std::unique_ptr<carto::transform::TransformInterpolationBuffer> ReadTrajectory( std::unique_ptr<carto::transform::TransformInterpolationBuffer> ReadTrajectory(
const std::string& trajectory_filename) { const std::string& trajectory_filename) {
std::ifstream stream(trajectory_filename.c_str()); std::ifstream stream(trajectory_filename.c_str());
carto::proto::Trajectory trajectory_proto; carto::mapping::proto::Trajectory trajectory_proto;
CHECK(trajectory_proto.ParseFromIstream(&stream)); CHECK(trajectory_proto.ParseFromIstream(&stream));
return carto::transform::TransformInterpolationBuffer::FromTrajectory( return carto::transform::TransformInterpolationBuffer::FromTrajectory(
trajectory_proto); trajectory_proto);

View File

@ -31,7 +31,7 @@
#include "cartographer/kalman_filter/pose_tracker.h" #include "cartographer/kalman_filter/pose_tracker.h"
#include "cartographer/mapping/global_trajectory_builder_interface.h" #include "cartographer/mapping/global_trajectory_builder_interface.h"
#include "cartographer/mapping/map_builder.h" #include "cartographer/mapping/map_builder.h"
#include "cartographer/mapping/proto/submaps.pb.h" #include "cartographer/mapping/proto/submap_visualization.pb.h"
#include "cartographer/mapping_2d/global_trajectory_builder.h" #include "cartographer/mapping_2d/global_trajectory_builder.h"
#include "cartographer/mapping_2d/local_trajectory_builder.h" #include "cartographer/mapping_2d/local_trajectory_builder.h"
#include "cartographer/mapping_2d/sparse_pose_graph.h" #include "cartographer/mapping_2d/sparse_pose_graph.h"