Skip to content

Commit

Permalink
disable map saver in localization mode as unnecessary and increases m…
Browse files Browse the repository at this point in the history
…emory
  • Loading branch information
SteveMacenski committed Sep 23, 2019
1 parent bf05617 commit 8cc2ab2
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 1 deletion.
2 changes: 1 addition & 1 deletion solvers/ceres_solver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -402,7 +402,7 @@ void CeresSolver::ModifyNode(const int& unique_id, Eigen::Vector3d pose)
{
double yaw_init = it->second(2);
it->second = pose;
it->second(2)+= yaw_init;
it->second(2) += yaw_init;
}
}

Expand Down
3 changes: 3 additions & 0 deletions src/slam_toolbox_localization.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,9 @@ LocalizationSlamToolbox::LocalizationSlamToolbox(ros::NodeHandle& nh)

// in localization mode, we cannot allow for interactive mode
enable_interactive_mode_ = false;

// in localization mode, disable map saver
map_saver_.reset();
return;
}

Expand Down

0 comments on commit 8cc2ab2

Please sign in to comment.