diff --git a/cartographer_ros/cartographer_ros/pbstream_map_publisher_main.cc b/cartographer_ros/cartographer_ros/pbstream_map_publisher_main.cc index 34b3f20..3da3ca7 100644 --- a/cartographer_ros/cartographer_ros/pbstream_map_publisher_main.cc +++ b/cartographer_ros/cartographer_ros/pbstream_map_publisher_main.cc @@ -50,8 +50,7 @@ namespace cartographer_ros { namespace { std::unique_ptr LoadOccupancyGridMsg( - const std::string& pbstream_filename, const double resolution, - ::cartographer::mapping::ValueConversionTables* conversion_lookup_tables) { + const std::string& pbstream_filename, const double resolution) { ::cartographer::io::ProtoStreamReader reader(pbstream_filename); ::cartographer::io::ProtoStreamDeserializer deserializer(&reader); @@ -59,6 +58,7 @@ std::unique_ptr LoadOccupancyGridMsg( std::map<::cartographer::mapping::SubmapId, ::cartographer::io::SubmapSlice> submap_slices; ::cartographer::mapping::proto::SerializedData proto; + ::cartographer::mapping::ValueConversionTables conversion_lookup_tables; while (deserializer.ReadNextSerializedData(&proto)) { if (proto.has_submap()) { const auto& submap = proto.submap(); @@ -71,7 +71,7 @@ std::unique_ptr LoadOccupancyGridMsg( .submap(id.submap_index) .pose()); FillSubmapSlice(global_submap_pose, submap, &submap_slices[id], - conversion_lookup_tables); + &conversion_lookup_tables); } } CHECK(reader.eof()); @@ -85,9 +85,8 @@ std::unique_ptr LoadOccupancyGridMsg( void Run(const std::string& pbstream_filename, const std::string& map_topic, const std::string& map_frame_id, const double resolution) { - ::cartographer::mapping::ValueConversionTables conversion_lookup_tables; - std::unique_ptr msg_ptr = LoadOccupancyGridMsg( - pbstream_filename, resolution, &conversion_lookup_tables); + std::unique_ptr msg_ptr = + LoadOccupancyGridMsg(pbstream_filename, resolution); ::ros::NodeHandle node_handle(""); ::ros::Publisher pub = node_handle.advertise(