@@ -849,6 +849,7 @@ controller_interface::return_type ControllerManager::configure_controller(
849849
850850void ControllerManager::clear_requests ()
851851{
852+ switch_params_.do_switch = false ;
852853 deactivate_request_.clear ();
853854 activate_request_.clear ();
854855 // Set these interfaces as unavailable when clearing requests to avoid leaving them in available
@@ -878,7 +879,8 @@ controller_interface::return_type ControllerManager::switch_controller(
878879 return controller_interface::return_type::ERROR;
879880 }
880881
881- switch_params_ = SwitchParams ();
882+ // reset the switch param internal variables
883+ switch_params_.reset ();
882884
883885 if (!deactivate_request_.empty () || !activate_request_.empty ())
884886 {
@@ -1299,19 +1301,27 @@ controller_interface::return_type ControllerManager::switch_controller(
12991301 // start the atomic controller switching
13001302 switch_params_.strictness = strictness;
13011303 switch_params_.activate_asap = activate_asap;
1302- switch_params_.init_time = rclcpp::Clock ().now ();
1303- switch_params_.timeout = timeout;
1304+ if (timeout == rclcpp::Duration{0 , 0 })
1305+ {
1306+ RCLCPP_INFO_ONCE (get_logger (), " Switch controller timeout is set to 0, using default 1s!" );
1307+ switch_params_.timeout = std::chrono::nanoseconds (1'000'000'000 );
1308+ }
1309+ else
1310+ {
1311+ switch_params_.timeout = timeout.to_chrono <std::chrono::nanoseconds>();
1312+ }
13041313 switch_params_.do_switch = true ;
1305-
13061314 // wait until switch is finished
13071315 RCLCPP_DEBUG (get_logger (), " Requested atomic controller switch from realtime loop" );
1308- while (rclcpp::ok () && switch_params_.do_switch )
1316+ std::unique_lock<std::mutex> switch_params_guard (switch_params_.mutex , std::defer_lock);
1317+ if (!switch_params_.cv .wait_for (
1318+ switch_params_guard, switch_params_.timeout , [this ] { return !switch_params_.do_switch ; }))
13091319 {
1310- if (! rclcpp::ok ())
1311- {
1312- return controller_interface::return_type::ERROR ;
1313- }
1314- std::this_thread::sleep_for ( std::chrono::microseconds ( 100 )) ;
1320+ RCLCPP_ERROR (
1321+ get_logger (), " Switch controller timed out after %f seconds! " ,
1322+ static_cast < double >(switch_params_. timeout . count ()) / 1e9 ) ;
1323+ clear_requests ();
1324+ return controller_interface::return_type::ERROR ;
13151325 }
13161326
13171327 // copy the controllers spec from the used to the unused list
@@ -2147,6 +2157,12 @@ void ControllerManager::read(const rclcpp::Time & time, const rclcpp::Duration &
21472157
21482158void ControllerManager::manage_switch ()
21492159{
2160+ std::unique_lock<std::mutex> guard (switch_params_.mutex , std::try_to_lock);
2161+ if (!guard.owns_lock ())
2162+ {
2163+ RCLCPP_DEBUG (get_logger (), " Unable to lock switch mutex. Retrying in next cycle." );
2164+ return ;
2165+ }
21502166 // Ask hardware interfaces to change mode
21512167 if (!resource_manager_->perform_command_mode_switch (
21522168 activate_command_interface_request_, deactivate_command_interface_request_))
@@ -2175,6 +2191,7 @@ void ControllerManager::manage_switch()
21752191
21762192 // All controllers switched --> switching done
21772193 switch_params_.do_switch = false ;
2194+ switch_params_.cv .notify_all ();
21782195}
21792196
21802197controller_interface::return_type ControllerManager::update (
0 commit comments