Discard proto data in pbstream_map_publisher via RAII. (#912)
We don't need it after the occupancy grid is drawn. Reduces the memory consumption especially for large maps.master
parent
8bbec6bff7
commit
0e65aa55b9
|
@ -48,8 +48,8 @@ DEFINE_double(resolution, 0.05, "Resolution of a grid cell in the drawn map.");
|
||||||
namespace cartographer_ros {
|
namespace cartographer_ros {
|
||||||
namespace {
|
namespace {
|
||||||
|
|
||||||
void Run(const std::string& pbstream_filename, const std::string& map_topic,
|
std::unique_ptr<nav_msgs::OccupancyGrid> LoadOccupancyGridMsg(
|
||||||
const std::string& map_frame_id, const double resolution) {
|
const std::string& pbstream_filename, const double resolution) {
|
||||||
::cartographer::io::ProtoStreamReader reader(pbstream_filename);
|
::cartographer::io::ProtoStreamReader reader(pbstream_filename);
|
||||||
::cartographer::io::ProtoStreamDeserializer deserializer(&reader);
|
::cartographer::io::ProtoStreamDeserializer deserializer(&reader);
|
||||||
|
|
||||||
|
@ -73,15 +73,21 @@ void Run(const std::string& pbstream_filename, const std::string& map_topic,
|
||||||
}
|
}
|
||||||
CHECK(reader.eof());
|
CHECK(reader.eof());
|
||||||
|
|
||||||
::ros::NodeHandle node_handle("");
|
|
||||||
::ros::Publisher pub = node_handle.advertise<nav_msgs::OccupancyGrid>(
|
|
||||||
map_topic, kLatestOnlyPublisherQueueSize, true /*latched */);
|
|
||||||
|
|
||||||
LOG(INFO) << "Generating combined map image from submap slices.";
|
LOG(INFO) << "Generating combined map image from submap slices.";
|
||||||
const auto painted_slices =
|
const auto painted_slices =
|
||||||
::cartographer::io::PaintSubmapSlices(submap_slices, resolution);
|
::cartographer::io::PaintSubmapSlices(submap_slices, resolution);
|
||||||
std::unique_ptr<nav_msgs::OccupancyGrid> msg_ptr = CreateOccupancyGridMsg(
|
return CreateOccupancyGridMsg(painted_slices, resolution, FLAGS_map_frame_id,
|
||||||
painted_slices, resolution, FLAGS_map_frame_id, ros::Time::now());
|
ros::Time::now());
|
||||||
|
}
|
||||||
|
|
||||||
|
void Run(const std::string& pbstream_filename, const std::string& map_topic,
|
||||||
|
const std::string& map_frame_id, const double resolution) {
|
||||||
|
std::unique_ptr<nav_msgs::OccupancyGrid> msg_ptr =
|
||||||
|
LoadOccupancyGridMsg(pbstream_filename, resolution);
|
||||||
|
|
||||||
|
::ros::NodeHandle node_handle("");
|
||||||
|
::ros::Publisher pub = node_handle.advertise<nav_msgs::OccupancyGrid>(
|
||||||
|
map_topic, kLatestOnlyPublisherQueueSize, true /*latched */);
|
||||||
|
|
||||||
LOG(INFO) << "Publishing occupancy grid topic " << map_topic
|
LOG(INFO) << "Publishing occupancy grid topic " << map_topic
|
||||||
<< " (frame_id: " << map_frame_id
|
<< " (frame_id: " << map_frame_id
|
||||||
|
|
Loading…
Reference in New Issue