diff --git a/mapping_plugin/slam_toolbox_rviz_plugin.cpp b/mapping_plugin/slam_toolbox_rviz_plugin.cpp index 6d2a0a391..9990bb90d 100644 --- a/mapping_plugin/slam_toolbox_rviz_plugin.cpp +++ b/mapping_plugin/slam_toolbox_rviz_plugin.cpp @@ -219,7 +219,6 @@ void SlamToolboxPlugin::PauseMeasurementsCb(int state) /*****************************************************************************/ void SlamToolboxPlugin::updateCheckStateIfExternalChange() /*****************************************************************************/ - { ros::Rate r(1); //1 hz ros::NodeHandle nh; diff --git a/src/slam_toolbox.cpp b/src/slam_toolbox.cpp index ee7912770..94466f0cf 100644 --- a/src/slam_toolbox.cpp +++ b/src/slam_toolbox.cpp @@ -986,7 +986,7 @@ bool SlamToolbox::PauseNewMeasurementsCallback( \ { boost::mutex::scoped_lock lock(pause_mutex_); pause_new_measurements_ = !pause_new_measurements_; - nh_.setParam("paused_measurements", pause_new_measurements_); + nh_.setParam("paused_new_measurements", pause_new_measurements_); ROS_INFO("SlamToolbox: Toggled to %s", \ pause_new_measurements_ ? "pause taking new measurements." : "actively taking new measurements.");