Skip to content

Commit a1ad523

Browse files
authored
refactor SwitchParams to fix the incosistencies in the spawner tests (#1638)
1 parent 32e471a commit a1ad523

File tree

3 files changed

+74
-17
lines changed

3 files changed

+74
-17
lines changed

controller_manager/include/controller_manager/controller_manager.hpp

Lines changed: 17 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -583,14 +583,25 @@ class ControllerManager : public rclcpp::Node
583583

584584
struct SwitchParams
585585
{
586-
bool do_switch = {false};
587-
bool started = {false};
588-
rclcpp::Time init_time = {rclcpp::Time::max()};
586+
void reset()
587+
{
588+
do_switch = false;
589+
started = false;
590+
strictness = 0;
591+
activate_asap = false;
592+
}
593+
594+
bool do_switch;
595+
bool started;
589596

590597
// Switch options
591-
int strictness = {0};
592-
bool activate_asap = {false};
593-
rclcpp::Duration timeout = rclcpp::Duration{0, 0};
598+
int strictness;
599+
bool activate_asap;
600+
std::chrono::nanoseconds timeout;
601+
602+
// conditional variable and mutex to wait for the switch to complete
603+
std::condition_variable cv;
604+
std::mutex mutex;
594605
};
595606

596607
SwitchParams switch_params_;

controller_manager/src/controller_manager.cpp

Lines changed: 27 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -849,6 +849,7 @@ controller_interface::return_type ControllerManager::configure_controller(
849849

850850
void 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

21482158
void 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

21802197
controller_interface::return_type ControllerManager::update(

controller_manager/test/test_controller_manager_srvs.cpp

Lines changed: 30 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -168,9 +168,38 @@ TEST_F(TestControllerManagerSrvs, list_controllers_srv)
168168
"joint1/velocity", "joint2/acceleration", "joint2/position", "joint2/velocity",
169169
"joint3/acceleration", "joint3/position", "joint3/velocity", "sensor1/velocity"));
170170

171+
// Switch with a very low timeout 1 ns and it should fail as there is no enough time to switch
172+
ASSERT_EQ(
173+
controller_interface::return_type::ERROR,
174+
cm_->switch_controller(
175+
{}, {test_controller::TEST_CONTROLLER_NAME},
176+
controller_manager_msgs::srv::SwitchController::Request::STRICT, true,
177+
rclcpp::Duration(0, 1)));
178+
179+
result = call_service_and_wait(*client, request, srv_executor);
180+
ASSERT_EQ(1u, result->controller.size());
181+
ASSERT_EQ("active", result->controller[0].state);
182+
ASSERT_THAT(
183+
result->controller[0].claimed_interfaces,
184+
UnorderedElementsAre(
185+
"joint2/velocity", "joint3/velocity", "joint2/max_acceleration", "configuration/max_tcp_jerk",
186+
"joint1/position", "joint1/max_velocity"));
187+
ASSERT_THAT(
188+
result->controller[0].required_command_interfaces,
189+
UnorderedElementsAre(
190+
"configuration/max_tcp_jerk", "joint1/max_velocity", "joint1/position",
191+
"joint2/max_acceleration", "joint2/velocity", "joint3/velocity"));
192+
ASSERT_THAT(
193+
result->controller[0].required_state_interfaces,
194+
UnorderedElementsAre(
195+
"configuration/max_tcp_jerk", "joint1/position", "joint1/some_unlisted_interface",
196+
"joint1/velocity", "joint2/acceleration", "joint2/position", "joint2/velocity",
197+
"joint3/acceleration", "joint3/position", "joint3/velocity", "sensor1/velocity"));
198+
199+
// Try again with higher timeout
171200
cm_->switch_controller(
172201
{}, {test_controller::TEST_CONTROLLER_NAME},
173-
controller_manager_msgs::srv::SwitchController::Request::STRICT, true, rclcpp::Duration(0, 0));
202+
controller_manager_msgs::srv::SwitchController::Request::STRICT, true, rclcpp::Duration(3, 0));
174203

175204
result = call_service_and_wait(*client, request, srv_executor);
176205
ASSERT_EQ(1u, result->controller.size());

0 commit comments

Comments
 (0)