Skip to content

Commit

Permalink
add try to lock mutex and print to not to obsruct RT thread
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor committed Jul 23, 2024
1 parent c2336ae commit 22e6ca1
Showing 1 changed file with 7 additions and 3 deletions.
10 changes: 7 additions & 3 deletions controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1297,7 +1297,6 @@ controller_interface::return_type ControllerManager::switch_controller(
}

// start the atomic controller switching
std::unique_lock<std::mutex> switch_params_guard(switch_params_.mutex);
switch_params_.strictness = strictness;
switch_params_.activate_asap = activate_asap;
if (timeout == rclcpp::Duration{0, 0})
Expand All @@ -1310,9 +1309,9 @@ controller_interface::return_type ControllerManager::switch_controller(
switch_params_.timeout = timeout.to_chrono<std::chrono::nanoseconds>();
}
switch_params_.do_switch = true;

// wait until switch is finished
RCLCPP_DEBUG(get_logger(), "Requested atomic controller switch from realtime loop");
std::unique_lock<std::mutex> switch_params_guard(switch_params_.mutex, std::defer_lock);
if (!switch_params_.cv.wait_for(
switch_params_guard, switch_params_.timeout, [this] { return !switch_params_.do_switch; }))
{
Expand Down Expand Up @@ -2156,7 +2155,12 @@ void ControllerManager::read(const rclcpp::Time & time, const rclcpp::Duration &

void ControllerManager::manage_switch()
{
std::lock_guard<std::mutex> guard(switch_params_.mutex);
std::unique_lock<std::mutex> guard(switch_params_.mutex, std::try_to_lock);
if (!guard.owns_lock())
{
RCLCPP_DEBUG(get_logger(), "Unable to lock switch mutex. Retrying in next cycle.");
return;
}
// Ask hardware interfaces to change mode
if (!resource_manager_->perform_command_mode_switch(
activate_command_interface_request_, deactivate_command_interface_request_))
Expand Down

0 comments on commit 22e6ca1

Please sign in to comment.