Skip to content

Commit 5b7066e

Browse files
authored
Merge branch 'master' into fix/test_init
2 parents 0672ab6 + a2e56e4 commit 5b7066e

File tree

14 files changed

+976
-204
lines changed

14 files changed

+976
-204
lines changed

controller_manager/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -247,6 +247,7 @@ if(BUILD_TESTING)
247247
install(FILES test/test_ros2_control_node.yaml
248248
DESTINATION test)
249249
ament_add_pytest_test(test_ros2_control_node test/test_ros2_control_node_launch.py)
250+
ament_add_pytest_test(test_test_utils test/test_test_utils.py)
250251
endif()
251252

252253
install(

controller_manager/controller_manager/spawner.py

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -182,7 +182,10 @@ def main(args=None):
182182
ros_home = os.getenv("ROS_HOME", os.path.join(os.path.expanduser("~"), ".ros"))
183183
ros_control_lock_dir = os.path.join(ros_home, "locks")
184184
if not os.path.exists(ros_control_lock_dir):
185-
os.makedirs(ros_control_lock_dir)
185+
try:
186+
os.makedirs(ros_control_lock_dir)
187+
except FileExistsError:
188+
pass
186189
lock = FileLock(f"{ros_control_lock_dir}/ros2-control-controller-spawner.lock")
187190
max_retries = 5
188191
retry_delay = 3 # seconds

controller_manager/include/controller_manager/controller_manager.hpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -280,10 +280,11 @@ class ControllerManager : public rclcpp::Node
280280
*
281281
* \param[in] rt_controller_list controllers in the real-time list.
282282
* \param[in] controllers_to_activate names of the controller that have to be activated.
283+
* \param[in] strictness level of strictness for activation.
283284
*/
284285
void activate_controllers(
285286
const std::vector<ControllerSpec> & rt_controller_list,
286-
const std::vector<std::string> & controllers_to_activate);
287+
const std::vector<std::string> & controllers_to_activate, int strictness);
287288

288289
void list_controllers_srv_cb(
289290
const std::shared_ptr<controller_manager_msgs::srv::ListControllers::Request> request,

controller_manager/src/controller_manager.cpp

Lines changed: 42 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -1307,6 +1307,10 @@ controller_interface::return_type ControllerManager::configure_controller(
13071307
resource_manager_->import_controller_reference_interfaces(controller_name, ref_interfaces);
13081308
resource_manager_->import_controller_exported_state_interfaces(
13091309
controller_name, state_interfaces);
1310+
// make all the exported interfaces of the controller unavailable
1311+
controller->set_chained_mode(false);
1312+
resource_manager_->make_controller_exported_state_interfaces_unavailable(controller_name);
1313+
resource_manager_->make_controller_reference_interfaces_unavailable(controller_name);
13101314
}
13111315

13121316
// let's update the list of following and preceding controllers
@@ -2226,9 +2230,10 @@ void ControllerManager::switch_chained_mode(
22262230

22272231
void ControllerManager::activate_controllers(
22282232
const std::vector<ControllerSpec> & rt_controller_list,
2229-
const std::vector<std::string> & controllers_to_activate)
2233+
const std::vector<std::string> & controllers_to_activate, int strictness)
22302234
{
22312235
std::vector<std::string> failed_controllers_command_interfaces;
2236+
bool is_successful = true;
22322237
for (const auto & controller_name : controllers_to_activate)
22332238
{
22342239
auto found_it = std::find_if(
@@ -2295,6 +2300,7 @@ void ControllerManager::activate_controllers(
22952300
// something went wrong during command interfaces, go skip the controller
22962301
if (!assignment_successful)
22972302
{
2303+
is_successful = false;
22982304
continue;
22992305
}
23002306

@@ -2333,6 +2339,7 @@ void ControllerManager::activate_controllers(
23332339
// something went wrong during state interfaces, go skip the controller
23342340
if (!assignment_successful)
23352341
{
2342+
is_successful = false;
23362343
continue;
23372344
}
23382345
controller->assign_interfaces(std::move(command_loans), std::move(state_loans));
@@ -2365,10 +2372,15 @@ void ControllerManager::activate_controllers(
23652372
controller->get_node()->get_name(), new_state.label().c_str(), new_state.id(),
23662373
hardware_interface::lifecycle_state_names::ACTIVE,
23672374
lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE);
2375+
is_successful = false;
23682376
controller->release_interfaces();
2369-
failed_controllers_command_interfaces.insert(
2370-
failed_controllers_command_interfaces.end(), command_interface_names.begin(),
2371-
command_interface_names.end());
2377+
ros2_control::add_items(failed_controllers_command_interfaces, command_interface_names);
2378+
if (controller->is_chainable())
2379+
{
2380+
// make all the exported interfaces of the controller unavailable
2381+
resource_manager_->make_controller_exported_state_interfaces_unavailable(controller_name);
2382+
resource_manager_->make_controller_reference_interfaces_unavailable(controller_name);
2383+
}
23722384
continue;
23732385
}
23742386

@@ -2380,6 +2392,27 @@ void ControllerManager::activate_controllers(
23802392
resource_manager_->make_controller_reference_interfaces_available(controller_name);
23812393
}
23822394
}
2395+
if (
2396+
!is_successful && strictness == controller_manager_msgs::srv::SwitchController::Request::STRICT)
2397+
{
2398+
RCLCPP_ERROR(
2399+
get_logger(),
2400+
"At least one controller failed to be activated. Releasing all interfaces and stopping all "
2401+
"activated controllers because the switch strictness is set to STRICT.");
2402+
// deactivate all controllers that were activated in this switch
2403+
deactivate_controllers(rt_controller_list, controllers_to_activate);
2404+
if (
2405+
!resource_manager_->prepare_command_mode_switch(
2406+
{}, switch_params_.activate_command_interface_request) ||
2407+
!resource_manager_->perform_command_mode_switch(
2408+
{}, switch_params_.activate_command_interface_request))
2409+
{
2410+
RCLCPP_ERROR(
2411+
get_logger(),
2412+
"Error switching back the interfaces in the hardware when the controller activation "
2413+
"failed.");
2414+
}
2415+
}
23832416
// Now prepare and perform the stop interface switching as this is needed for exclusive
23842417
// interfaces
23852418
if (
@@ -2916,7 +2949,8 @@ void ControllerManager::manage_switch()
29162949

29172950
// activate controllers once the switch is fully complete
29182951
const auto act_start_time = std::chrono::steady_clock::now();
2919-
activate_controllers(rt_controller_list, switch_params_.activate_request);
2952+
activate_controllers(
2953+
rt_controller_list, switch_params_.activate_request, switch_params_.strictness);
29202954
execution_time_.activation_time =
29212955
std::chrono::duration<double, std::micro>(std::chrono::steady_clock::now() - act_start_time)
29222956
.count();
@@ -3116,7 +3150,9 @@ controller_interface::return_type ControllerManager::update(
31163150
deactivate_controllers(rt_controller_list, rt_buffer_.deactivate_controllers_list);
31173151
if (!rt_buffer_.fallback_controllers_list.empty())
31183152
{
3119-
activate_controllers(rt_controller_list, rt_buffer_.fallback_controllers_list);
3153+
activate_controllers(
3154+
rt_controller_list, rt_buffer_.fallback_controllers_list,
3155+
controller_manager_msgs::srv::SwitchController::Request::STRICT);
31203156
}
31213157
// To publish the activity of the failing controllers and the fallback controllers
31223158
publish_activity();

controller_manager/test/test_controller_manager.cpp

Lines changed: 177 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2280,3 +2280,180 @@ TEST_F(
22802280
test_chainable_controller->get_lifecycle_state().id());
22812281
}
22822282
}
2283+
2284+
TEST_F(
2285+
TestControllerManagerChainableControllerFailedActivation,
2286+
test_chainable_controllers_failed_activation_stops_all_list)
2287+
{
2288+
const std::string test_chainable_controller_2_name = "test_chainable_controller_2";
2289+
2290+
const auto strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT;
2291+
controller_interface::InterfaceConfiguration cmd_itfs_cfg;
2292+
controller_interface::InterfaceConfiguration itfs_cfg;
2293+
cmd_itfs_cfg.type = controller_interface::interface_configuration_type::INDIVIDUAL;
2294+
itfs_cfg.type = controller_interface::interface_configuration_type::INDIVIDUAL;
2295+
2296+
// controller 1
2297+
auto test_chainable_controller =
2298+
std::make_shared<test_chainable_controller::TestChainableController>();
2299+
cmd_itfs_cfg.names = {"joint1/position"};
2300+
itfs_cfg.names = {"joint2/velocity"};
2301+
test_chainable_controller->set_command_interface_configuration(cmd_itfs_cfg);
2302+
test_chainable_controller->set_state_interface_configuration(itfs_cfg);
2303+
test_chainable_controller->set_reference_interface_names({"modified_joint1/position"});
2304+
test_chainable_controller->set_exported_state_interface_names({"modified_joint2/velocity"});
2305+
test_chainable_controller->fail_on_activate = false;
2306+
2307+
auto test_chainable_controller_2 =
2308+
std::make_shared<test_chainable_controller::TestChainableController>();
2309+
cmd_itfs_cfg.names = {"joint2/velocity"};
2310+
itfs_cfg.names = {"joint2/velocity"};
2311+
test_chainable_controller_2->set_command_interface_configuration(cmd_itfs_cfg);
2312+
test_chainable_controller_2->set_state_interface_configuration(itfs_cfg);
2313+
test_chainable_controller_2->set_reference_interface_names({"modified_joint2/position"});
2314+
test_chainable_controller_2->set_exported_state_interface_names({"modified_joint2/velocity"});
2315+
test_chainable_controller_2->fail_on_activate = false;
2316+
2317+
auto test_controller = std::make_shared<test_controller::TestController>();
2318+
cmd_itfs_cfg.names = {
2319+
std::string(test_chainable_controller::TEST_CONTROLLER_NAME) + "/modified_joint1/position"};
2320+
test_controller->set_command_interface_configuration(cmd_itfs_cfg);
2321+
test_controller->set_state_interface_configuration(itfs_cfg);
2322+
2323+
cm_->add_controller(
2324+
test_chainable_controller, test_chainable_controller::TEST_CONTROLLER_NAME,
2325+
test_chainable_controller::TEST_CONTROLLER_CLASS_NAME);
2326+
cm_->add_controller(
2327+
test_chainable_controller_2, test_chainable_controller_2_name,
2328+
test_chainable_controller::TEST_CONTROLLER_CLASS_NAME);
2329+
cm_->add_controller(
2330+
test_controller, test_controller::TEST_CONTROLLER_NAME,
2331+
test_controller::TEST_CONTROLLER_CLASS_NAME);
2332+
2333+
EXPECT_EQ(3u, cm_->get_loaded_controllers().size());
2334+
EXPECT_EQ(2, test_chainable_controller.use_count());
2335+
EXPECT_EQ(2, test_chainable_controller_2.use_count());
2336+
EXPECT_EQ(2, test_controller.use_count());
2337+
EXPECT_EQ(
2338+
controller_interface::return_type::OK,
2339+
cm_->update(time_, rclcpp::Duration::from_seconds(0.01)));
2340+
2341+
EXPECT_EQ(
2342+
lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
2343+
test_chainable_controller->get_lifecycle_state().id());
2344+
EXPECT_EQ(
2345+
lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
2346+
test_chainable_controller_2->get_lifecycle_state().id());
2347+
EXPECT_EQ(
2348+
lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
2349+
test_controller->get_lifecycle_state().id());
2350+
2351+
// configure controllers
2352+
{
2353+
ControllerManagerRunner cm_runner(this);
2354+
EXPECT_EQ(
2355+
controller_interface::return_type::OK,
2356+
cm_->configure_controller(test_chainable_controller::TEST_CONTROLLER_NAME));
2357+
EXPECT_EQ(
2358+
controller_interface::return_type::OK,
2359+
cm_->configure_controller(test_chainable_controller_2_name));
2360+
EXPECT_EQ(
2361+
controller_interface::return_type::OK,
2362+
cm_->configure_controller(test_controller::TEST_CONTROLLER_NAME));
2363+
}
2364+
2365+
std::vector<std::string> start_controllers = {
2366+
test_chainable_controller::TEST_CONTROLLER_NAME, test_chainable_controller_2_name,
2367+
test_controller::TEST_CONTROLLER_NAME};
2368+
std::vector<std::string> stop_controllers = {};
2369+
{
2370+
ControllerManagerRunner cm_runner(this);
2371+
2372+
auto switch_future = std::async(
2373+
std::launch::async, &controller_manager::ControllerManager::switch_controller, cm_,
2374+
start_controllers, stop_controllers, strictness, true, rclcpp::Duration(0, 0));
2375+
ASSERT_EQ(std::future_status::ready, switch_future.wait_for(std::chrono::milliseconds(100)))
2376+
<< "switch_controller should be blocking until next update cycle";
2377+
EXPECT_EQ(controller_interface::return_type::OK, switch_future.get());
2378+
EXPECT_EQ(
2379+
lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
2380+
test_chainable_controller->get_lifecycle_state().id());
2381+
EXPECT_EQ(
2382+
lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
2383+
test_chainable_controller_2->get_lifecycle_state().id());
2384+
EXPECT_EQ(
2385+
lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
2386+
test_controller->get_lifecycle_state().id());
2387+
2388+
// Now deactivate all the controllers
2389+
auto switch_future_2 = std::async(
2390+
std::launch::async, &controller_manager::ControllerManager::switch_controller, cm_,
2391+
stop_controllers, start_controllers, strictness, true, rclcpp::Duration(0, 0));
2392+
ASSERT_EQ(std::future_status::ready, switch_future_2.wait_for(std::chrono::milliseconds(100)))
2393+
<< "switch_controller should be blocking until next update cycle";
2394+
EXPECT_EQ(controller_interface::return_type::OK, switch_future_2.get());
2395+
EXPECT_EQ(
2396+
lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
2397+
test_chainable_controller->get_lifecycle_state().id());
2398+
EXPECT_EQ(
2399+
lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
2400+
test_chainable_controller_2->get_lifecycle_state().id());
2401+
EXPECT_EQ(
2402+
lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
2403+
test_controller->get_lifecycle_state().id());
2404+
}
2405+
2406+
// Now, let's make the first controller fail on activation and see that all the controllers are
2407+
// set to inactive in strict mode
2408+
test_chainable_controller->fail_on_activate = true;
2409+
{
2410+
ControllerManagerRunner cm_runner(this);
2411+
2412+
auto switch_future = std::async(
2413+
std::launch::async, &controller_manager::ControllerManager::switch_controller, cm_,
2414+
start_controllers, stop_controllers, strictness, true, rclcpp::Duration(0, 0));
2415+
ASSERT_EQ(std::future_status::ready, switch_future.wait_for(std::chrono::milliseconds(100)))
2416+
<< "switch_controller should be blocking until next update cycle";
2417+
EXPECT_EQ(controller_interface::return_type::ERROR, switch_future.get());
2418+
EXPECT_EQ(
2419+
lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
2420+
test_chainable_controller->get_lifecycle_state().id());
2421+
EXPECT_EQ(
2422+
lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
2423+
test_chainable_controller_2->get_lifecycle_state().id());
2424+
EXPECT_EQ(
2425+
lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
2426+
test_controller->get_lifecycle_state().id());
2427+
}
2428+
2429+
// Now, reconfigure and test with BEST_EFFORT strictness and see that the other two controllers
2430+
// are active
2431+
{
2432+
ControllerManagerRunner cm_runner(this);
2433+
EXPECT_EQ(
2434+
controller_interface::return_type::OK,
2435+
cm_->configure_controller(test_chainable_controller::TEST_CONTROLLER_NAME));
2436+
EXPECT_EQ(
2437+
lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
2438+
test_chainable_controller->get_lifecycle_state().id());
2439+
2440+
const auto best_effort_strictness =
2441+
controller_manager_msgs::srv::SwitchController::Request::BEST_EFFORT;
2442+
auto switch_future = std::async(
2443+
std::launch::async, &controller_manager::ControllerManager::switch_controller, cm_,
2444+
start_controllers, stop_controllers, best_effort_strictness, true, rclcpp::Duration(0, 0));
2445+
ASSERT_EQ(std::future_status::ready, switch_future.wait_for(std::chrono::milliseconds(100)))
2446+
<< "switch_controller should be blocking until next update cycle";
2447+
EXPECT_EQ(controller_interface::return_type::ERROR, switch_future.get());
2448+
EXPECT_EQ(
2449+
lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
2450+
test_chainable_controller->get_lifecycle_state().id());
2451+
EXPECT_EQ(
2452+
lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
2453+
test_chainable_controller_2->get_lifecycle_state().id());
2454+
// test controller needs to be inactive as it depends on the failed controller's interface
2455+
EXPECT_EQ(
2456+
lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
2457+
test_controller->get_lifecycle_state().id());
2458+
}
2459+
}

controller_manager/test/test_release_interfaces.cpp

Lines changed: 22 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -176,7 +176,7 @@ TEST_F(TestReleaseInterfaces, switch_controllers_same_interface)
176176
abstract_test_controller2.c->get_lifecycle_state().id());
177177
}
178178

179-
{ // Test starting both controllers at the same time
179+
{ // Test starting both controllers at the same time, with STRICT both should fail
180180
RCLCPP_INFO(
181181
cm_->get_logger(),
182182
"Starting both controllers at the same time (should notify about resource conflict)");
@@ -189,6 +189,27 @@ TEST_F(TestReleaseInterfaces, switch_controllers_same_interface)
189189
<< "switch_controller should be blocking until next update cycle";
190190
ControllerManagerRunner cm_runner(this);
191191
EXPECT_EQ(controller_interface::return_type::ERROR, switch_future.get());
192+
ASSERT_EQ(
193+
lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
194+
abstract_test_controller1.c->get_lifecycle_state().id());
195+
ASSERT_EQ(
196+
lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
197+
abstract_test_controller2.c->get_lifecycle_state().id());
198+
}
199+
200+
{ // Test starting both controllers at the same time, with BEST_EFFORT one should activate
201+
RCLCPP_INFO(
202+
cm_->get_logger(),
203+
"Starting both controllers at the same time (should notify about resource conflict)");
204+
std::vector<std::string> start_controllers = {controller_name1, controller_name2};
205+
std::vector<std::string> stop_controllers = {};
206+
auto switch_future = std::async(
207+
std::launch::async, &controller_manager::ControllerManager::switch_controller, cm_,
208+
start_controllers, stop_controllers, BEST_EFFORT, true, rclcpp::Duration(0, 0));
209+
ASSERT_EQ(std::future_status::timeout, switch_future.wait_for(std::chrono::milliseconds(100)))
210+
<< "switch_controller should be blocking until next update cycle";
211+
ControllerManagerRunner cm_runner(this);
212+
EXPECT_EQ(controller_interface::return_type::ERROR, switch_future.get());
192213
ASSERT_EQ(
193214
lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
194215
abstract_test_controller1.c->get_lifecycle_state().id());

0 commit comments

Comments
 (0)