@@ -490,6 +490,17 @@ TEST_P(TestControllerManagerWithStrictness, async_controller_lifecycle)
490490 testing::AllOf (testing::Gt (0.6 * exp_period), testing::Lt ((1.4 * exp_period))));
491491 size_t last_internal_counter = test_controller->internal_counter ;
492492
493+ {
494+ ControllerManagerRunner cm_runner (this );
495+ std::this_thread::sleep_for (std::chrono::milliseconds (1000 ));
496+ }
497+ ASSERT_THAT (
498+ test_controller->internal_counter ,
499+ testing::AllOf (
500+ testing::Ge (last_internal_counter + 18 ), testing::Le (last_internal_counter + 21 )))
501+ << " As the sleep is 1 sec and the controller rate is 20Hz, we should have approx. 20 updates" ;
502+
503+ last_internal_counter = test_controller->internal_counter ;
493504 // Stop controller, will take effect at the end of the update function
494505 start_controllers = {};
495506 stop_controllers = {test_controller::TEST_CONTROLLER_NAME};
@@ -533,6 +544,215 @@ TEST_P(TestControllerManagerWithStrictness, async_controller_lifecycle)
533544 EXPECT_EQ (1 , test_controller.use_count ());
534545}
535546
547+ TEST_P (TestControllerManagerWithStrictness, async_controller_lifecycle_at_cm_rate)
548+ {
549+ const auto test_param = GetParam ();
550+ auto test_controller = std::make_shared<test_controller::TestController>();
551+ auto test_controller2 = std::make_shared<test_controller::TestController>();
552+ constexpr char TEST_CONTROLLER2_NAME[] = " test_controller2_name" ;
553+ cm_->add_controller (
554+ test_controller, test_controller::TEST_CONTROLLER_NAME,
555+ test_controller::TEST_CONTROLLER_CLASS_NAME);
556+ cm_->add_controller (
557+ test_controller2, TEST_CONTROLLER2_NAME, test_controller::TEST_CONTROLLER_CLASS_NAME);
558+ EXPECT_EQ (2u , cm_->get_loaded_controllers ().size ());
559+ EXPECT_EQ (2 , test_controller.use_count ());
560+
561+ // setup interface to claim from controllers
562+ controller_interface::InterfaceConfiguration cmd_itfs_cfg;
563+ cmd_itfs_cfg.type = controller_interface::interface_configuration_type::INDIVIDUAL;
564+ for (const auto & interface : ros2_control_test_assets::TEST_ACTUATOR_HARDWARE_COMMAND_INTERFACES)
565+ {
566+ cmd_itfs_cfg.names .push_back (interface);
567+ }
568+ test_controller->set_command_interface_configuration (cmd_itfs_cfg);
569+
570+ controller_interface::InterfaceConfiguration state_itfs_cfg;
571+ state_itfs_cfg.type = controller_interface::interface_configuration_type::INDIVIDUAL;
572+ for (const auto & interface : ros2_control_test_assets::TEST_ACTUATOR_HARDWARE_STATE_INTERFACES)
573+ {
574+ state_itfs_cfg.names .push_back (interface);
575+ }
576+ for (const auto & interface : ros2_control_test_assets::TEST_SENSOR_HARDWARE_STATE_INTERFACES)
577+ {
578+ state_itfs_cfg.names .push_back (interface);
579+ }
580+ test_controller->set_state_interface_configuration (state_itfs_cfg);
581+
582+ controller_interface::InterfaceConfiguration cmd_itfs_cfg2;
583+ cmd_itfs_cfg2.type = controller_interface::interface_configuration_type::INDIVIDUAL;
584+ for (const auto & interface : ros2_control_test_assets::TEST_SYSTEM_HARDWARE_COMMAND_INTERFACES)
585+ {
586+ cmd_itfs_cfg2.names .push_back (interface);
587+ }
588+ test_controller2->set_command_interface_configuration (cmd_itfs_cfg2);
589+
590+ controller_interface::InterfaceConfiguration state_itfs_cfg2;
591+ state_itfs_cfg2.type = controller_interface::interface_configuration_type::ALL;
592+ test_controller2->set_state_interface_configuration (state_itfs_cfg2);
593+
594+ // Check if namespace is set correctly
595+ RCLCPP_INFO (
596+ rclcpp::get_logger (" test_controller_manager" ), " Controller Manager namespace is '%s'" ,
597+ cm_->get_namespace ());
598+ EXPECT_STREQ (cm_->get_namespace (), " /" );
599+ RCLCPP_INFO (
600+ rclcpp::get_logger (" test_controller_manager" ), " Controller 1 namespace is '%s'" ,
601+ test_controller->get_node ()->get_namespace ());
602+ EXPECT_STREQ (test_controller->get_node ()->get_namespace (), " /" );
603+ RCLCPP_INFO (
604+ rclcpp::get_logger (" test_controller_manager" ), " Controller 2 namespace is '%s'" ,
605+ test_controller2->get_node ()->get_namespace ());
606+ EXPECT_STREQ (test_controller2->get_node ()->get_namespace (), " /" );
607+
608+ EXPECT_EQ (
609+ controller_interface::return_type::OK,
610+ cm_->update (time_, rclcpp::Duration::from_seconds (0.01 )));
611+ EXPECT_EQ (0u , test_controller->internal_counter )
612+ << " Update should not reach an unconfigured controller" ;
613+
614+ EXPECT_EQ (
615+ lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
616+ test_controller->get_lifecycle_state ().id ());
617+
618+ // configure controller
619+ rclcpp::Parameter is_async_parameter (" is_async" , rclcpp::ParameterValue (true ));
620+ test_controller->get_node ()->set_parameter (is_async_parameter);
621+ {
622+ ControllerManagerRunner cm_runner (this );
623+ cm_->configure_controller (test_controller::TEST_CONTROLLER_NAME);
624+ cm_->configure_controller (TEST_CONTROLLER2_NAME);
625+ }
626+ EXPECT_EQ (
627+ controller_interface::return_type::OK,
628+ cm_->update (time_, rclcpp::Duration::from_seconds (0.01 )));
629+ EXPECT_EQ (0u , test_controller->internal_counter ) << " Controller is not started" ;
630+ EXPECT_EQ (0u , test_controller2->internal_counter ) << " Controller is not started" ;
631+
632+ EXPECT_EQ (
633+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
634+ test_controller->get_lifecycle_state ().id ());
635+
636+ // Start controller, will take effect at the end of the update function
637+ std::vector<std::string> start_controllers = {" fake_controller" , TEST_CONTROLLER2_NAME};
638+ std::vector<std::string> stop_controllers = {};
639+ auto switch_future = std::async (
640+ std::launch::async, &controller_manager::ControllerManager::switch_controller, cm_,
641+ start_controllers, stop_controllers, test_param.strictness , true , rclcpp::Duration (0 , 0 ));
642+
643+ EXPECT_EQ (
644+ controller_interface::return_type::OK,
645+ cm_->update (time_, rclcpp::Duration::from_seconds (0.01 )));
646+ EXPECT_EQ (0u , test_controller2->internal_counter ) << " Controller is started at the end of update" ;
647+ {
648+ ControllerManagerRunner cm_runner (this );
649+ EXPECT_EQ (test_param.expected_return , switch_future.get ());
650+ }
651+
652+ EXPECT_EQ (
653+ controller_interface::return_type::OK,
654+ cm_->update (time_, rclcpp::Duration::from_seconds (0.01 )));
655+ EXPECT_GE (test_controller2->internal_counter , test_param.expected_counter );
656+
657+ // Start the real test controller, will take effect at the end of the update function
658+ start_controllers = {test_controller::TEST_CONTROLLER_NAME};
659+ stop_controllers = {};
660+ switch_future = std::async (
661+ std::launch::async, &controller_manager::ControllerManager::switch_controller, cm_,
662+ start_controllers, stop_controllers, test_param.strictness , true , rclcpp::Duration (0 , 0 ));
663+
664+ ASSERT_EQ (std::future_status::timeout, switch_future.wait_for (std::chrono::milliseconds (100 )))
665+ << " switch_controller should be blocking until next update cycle" ;
666+
667+ EXPECT_EQ (
668+ controller_interface::return_type::OK,
669+ cm_->update (time_, rclcpp::Duration::from_seconds (0.01 )));
670+ EXPECT_EQ (0u , test_controller->internal_counter ) << " Controller is started at the end of update" ;
671+ {
672+ ControllerManagerRunner cm_runner (this );
673+ EXPECT_EQ (controller_interface::return_type::OK, switch_future.get ());
674+ }
675+ EXPECT_EQ (
676+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, test_controller->get_lifecycle_state ().id ());
677+
678+ time_ = cm_->get_clock ()->now ();
679+ EXPECT_EQ (
680+ controller_interface::return_type::OK,
681+ cm_->update (time_, rclcpp::Duration::from_seconds (0.01 )));
682+ EXPECT_GE (test_controller->internal_counter , 1u );
683+ auto current_counter = test_controller->internal_counter ;
684+ std::this_thread::sleep_for (
685+ std::chrono::milliseconds (1000 / (test_controller->get_update_rate ())));
686+ EXPECT_EQ (test_controller->internal_counter , current_counter + 1u );
687+ EXPECT_NEAR (test_controller->update_period_ .seconds (), 0.01 , 0.008 );
688+
689+ const double exp_period = (cm_->get_clock ()->now () - time_).seconds ();
690+ time_ = cm_->get_clock ()->now ();
691+ EXPECT_EQ (
692+ controller_interface::return_type::OK,
693+ cm_->update (time_, rclcpp::Duration::from_seconds (0.01 )));
694+ EXPECT_EQ (test_controller->internal_counter , current_counter + 1u );
695+ std::this_thread::sleep_for (
696+ std::chrono::milliseconds (1000 / (test_controller->get_update_rate ())));
697+ EXPECT_EQ (test_controller->internal_counter , current_counter + 2u );
698+ EXPECT_THAT (
699+ test_controller->update_period_ .seconds (),
700+ testing::AllOf (testing::Gt (0.6 * exp_period), testing::Lt ((1.4 * exp_period))));
701+ size_t last_internal_counter = test_controller->internal_counter ;
702+
703+ {
704+ ControllerManagerRunner cm_runner (this );
705+ std::this_thread::sleep_for (std::chrono::milliseconds (1000 ));
706+ }
707+ ASSERT_THAT (
708+ test_controller->internal_counter ,
709+ testing::AllOf (
710+ testing::Ge (last_internal_counter + cm_->get_update_rate () - 3 ),
711+ testing::Le (last_internal_counter + cm_->get_update_rate () + 1 )))
712+ << " As the sleep is 1 sec and the controller rate is 100Hz, we should have approx. 100 updates" ;
713+
714+ // Sleep for 2 cycles to allow for any changes
715+ std::this_thread::sleep_for (std::chrono::milliseconds (20 ));
716+ last_internal_counter = test_controller->internal_counter ;
717+ {
718+ ControllerManagerRunner cm_runner (this );
719+ // Stop controller, will take effect at the end of the update function
720+ start_controllers = {};
721+ stop_controllers = {test_controller::TEST_CONTROLLER_NAME};
722+ switch_future = std::async (
723+ std::launch::async, &controller_manager::ControllerManager::switch_controller, cm_,
724+ start_controllers, stop_controllers, test_param.strictness , true , rclcpp::Duration (0 , 0 ));
725+
726+ ASSERT_EQ (std::future_status::ready, switch_future.wait_for (std::chrono::milliseconds (100 )))
727+ << " switch_controller should be blocking until next update cycle" ;
728+
729+ std::this_thread::sleep_for (std::chrono::milliseconds (20 ));
730+ EXPECT_EQ (controller_interface::return_type::OK, switch_future.get ());
731+ EXPECT_EQ (last_internal_counter + 1 , test_controller->internal_counter )
732+ << " Controller is stopped at the end of update, it should finish it's active cycle" ;
733+ }
734+
735+ EXPECT_EQ (
736+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
737+ test_controller->get_lifecycle_state ().id ());
738+ auto unload_future = std::async (
739+ std::launch::async, &controller_manager::ControllerManager::unload_controller, cm_,
740+ test_controller::TEST_CONTROLLER_NAME);
741+
742+ ASSERT_EQ (std::future_status::timeout, unload_future.wait_for (std::chrono::milliseconds (100 )))
743+ << " unload_controller should be blocking until next update cycle" ;
744+
745+ EXPECT_EQ (
746+ controller_interface::return_type::OK,
747+ cm_->update (time_, rclcpp::Duration::from_seconds (0.01 )));
748+ EXPECT_EQ (controller_interface::return_type::OK, unload_future.get ());
749+
750+ EXPECT_EQ (
751+ lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED,
752+ test_controller->get_lifecycle_state ().id ());
753+ EXPECT_EQ (1 , test_controller.use_count ());
754+ }
755+
536756TEST_P (TestControllerManagerWithStrictness, per_controller_update_rate)
537757{
538758 auto strictness = GetParam ().strictness ;
0 commit comments