From 094e319d4ab384d86883edae974862c23966caf4 Mon Sep 17 00:00:00 2001 From: Wolfgang Hess Date: Wed, 26 Oct 2016 09:18:01 +0200 Subject: [PATCH] Cartographer API changes. (#146) --- cartographer_ros/cartographer_ros/assets_writer.cc | 4 ++-- cartographer_ros/cartographer_ros/assets_writer_main.cc | 2 +- cartographer_ros/cartographer_ros/node_main.cc | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/cartographer_ros/cartographer_ros/assets_writer.cc b/cartographer_ros/cartographer_ros/assets_writer.cc index 13f295a..d3ec13c 100644 --- a/cartographer_ros/cartographer_ros/assets_writer.cc +++ b/cartographer_ros/cartographer_ros/assets_writer.cc @@ -21,8 +21,8 @@ #include "cartographer/io/ply_writing_points_processor.h" #include "cartographer/io/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/proto/trajectory.pb.h" #include "cartographer_ros/map_writer.h" #include "cartographer_ros/occupancy_grid.h" #include "nav_msgs/OccupancyGrid.h" @@ -89,7 +89,7 @@ void WriteAssets(const std::vector<::cartographer::mapping::TrajectoryNode>& // Write the trajectory. std::ofstream proto_file(stem + ".pb", std::ios_base::out | std::ios_base::binary); - const carto::proto::Trajectory trajectory = + const carto::mapping::proto::Trajectory trajectory = carto::mapping::ToProto(trajectory_nodes); CHECK(trajectory.SerializeToOstream(&proto_file)) << "Could not serialize trajectory."; diff --git a/cartographer_ros/cartographer_ros/assets_writer_main.cc b/cartographer_ros/cartographer_ros/assets_writer_main.cc index 762ffa8..cc1e251 100644 --- a/cartographer_ros/cartographer_ros/assets_writer_main.cc +++ b/cartographer_ros/cartographer_ros/assets_writer_main.cc @@ -59,7 +59,7 @@ namespace carto = ::cartographer; std::unique_ptr ReadTrajectory( const std::string& trajectory_filename) { std::ifstream stream(trajectory_filename.c_str()); - carto::proto::Trajectory trajectory_proto; + carto::mapping::proto::Trajectory trajectory_proto; CHECK(trajectory_proto.ParseFromIstream(&stream)); return carto::transform::TransformInterpolationBuffer::FromTrajectory( trajectory_proto); diff --git a/cartographer_ros/cartographer_ros/node_main.cc b/cartographer_ros/cartographer_ros/node_main.cc index 805fce1..cb2a7ef 100644 --- a/cartographer_ros/cartographer_ros/node_main.cc +++ b/cartographer_ros/cartographer_ros/node_main.cc @@ -31,7 +31,7 @@ #include "cartographer/kalman_filter/pose_tracker.h" #include "cartographer/mapping/global_trajectory_builder_interface.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/local_trajectory_builder.h" #include "cartographer/mapping_2d/sparse_pose_graph.h"