Move conversion table to LoadOccupancyGridMap. (#941)

master
Kevin Daun 2018-07-14 10:20:22 +02:00 committed by Wally B. Feed
parent 0572ebb592
commit a90e9952d8
1 changed files with 5 additions and 6 deletions

View File

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