Skip to content

Commit

Permalink
Avoid storing two maps in memory at once
Browse files Browse the repository at this point in the history
  • Loading branch information
rsoussan committed Jul 4, 2024
1 parent 339046b commit fd1d44c
Showing 1 changed file with 5 additions and 2 deletions.
7 changes: 5 additions & 2 deletions localization/localization_node/src/localization_nodelet.cc
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,9 @@ bool LocalizationNodelet::ResetMap(const std::string& map_file) {
while (processing_image_) {
usleep(100000);
}
map_.reset(new sparse_mapping::SparseMap(map_file, true));
// Reset map before creating new one to avoid storing two maps in memory at the same time
map_.reset();
map_ = std::make_shared<sparse_mapping::SparseMap>(map_file, true);
inst_.reset(new Localizer(map_.get()));
// Check to see if any params were changed when map was reset
ReadParams();
Expand All @@ -83,7 +85,8 @@ void LocalizationNodelet::Initialize(ros::NodeHandle* nh) {

// Reset all internal shared pointers
it_.reset(new image_transport::ImageTransport(*nh));
map_.reset(new sparse_mapping::SparseMap(map_file, true));
map_.reset();
map_ = std::make_shared<sparse_mapping::SparseMap>(map_file, true);
inst_.reset(new Localizer(map_.get()));

registration_publisher_ = nh->advertise<ff_msgs::CameraRegistration>(
Expand Down

0 comments on commit fd1d44c

Please sign in to comment.