From dd8441417cb36a880f947feac43d9ee1eb200dfa Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Sun, 1 Dec 2024 11:10:20 +0100 Subject: [PATCH 1/6] Bump version of pre-commit hooks (#1902) Co-authored-by: christophfroehlich <3367244+christophfroehlich@users.noreply.github.com> --- .pre-commit-config.yaml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 205e0f63ab..75c5402ffe 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -63,7 +63,7 @@ repos: # CPP hooks - repo: https://github.com/pre-commit/mirrors-clang-format - rev: v19.1.3 + rev: v19.1.4 hooks: - id: clang-format args: ['-fallback-style=none', '-i'] @@ -133,7 +133,7 @@ repos: exclude: CHANGELOG\.rst|\.(svg|pyc|drawio)$ - repo: https://github.com/python-jsonschema/check-jsonschema - rev: 0.29.4 + rev: 0.30.0 hooks: - id: check-github-workflows args: ["--verbose"] From 89fd4ef05e1fc107c9d1b2b122292665ccca6f36 Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Tue, 3 Dec 2024 16:28:40 +0100 Subject: [PATCH 2/6] [Diagnostics] Add diagnostics of execution time and periodicity of the controllers and controller_manager (#1871) --- .../controller_interface_base.hpp | 27 +- .../src/controller_interface_base.cpp | 24 +- controller_manager/CMakeLists.txt | 11 +- .../doc/parameters_context.yaml | 21 ++ controller_manager/doc/userdoc.rst | 36 +-- .../controller_manager/controller_manager.hpp | 10 +- .../controller_manager/controller_spec.hpp | 13 + controller_manager/package.xml | 2 + controller_manager/src/controller_manager.cpp | 286 ++++++++++++++---- .../src/controller_manager_parameters.yaml | 136 +++++++++ controller_manager/src/ros2_control_node.cpp | 2 +- .../test/test_controller_manager.cpp | 242 ++++++++++++++- .../test/test_hardware_management_srvs.cpp | 4 +- 13 files changed, 703 insertions(+), 111 deletions(-) create mode 100644 controller_manager/doc/parameters_context.yaml create mode 100644 controller_manager/src/controller_manager_parameters.yaml diff --git a/controller_interface/include/controller_interface/controller_interface_base.hpp b/controller_interface/include/controller_interface/controller_interface_base.hpp index ae3804919c..e41779cf7b 100644 --- a/controller_interface/include/controller_interface/controller_interface_base.hpp +++ b/controller_interface/include/controller_interface/controller_interface_base.hpp @@ -71,6 +71,25 @@ struct ControllerUpdateStats unsigned int total_triggers; unsigned int failed_triggers; }; + +/** + * Struct to store the status of the controller update method. + * The status contains information if the update was triggered successfully, the result of the + * update method and the execution duration of the update method. The status is used to provide + * feedback to the controller_manager. + * @var successful: true if the update was triggered successfully, false if not. + * @var result: return_type::OK if update is successfully, otherwise return_type::ERROR. + * @var execution_time: duration of the execution of the update method. + * @var period: period of the update method. + */ +struct ControllerUpdateStatus +{ + bool successful = true; + return_type result = return_type::OK; + std::optional execution_time = std::nullopt; + std::optional period = std::nullopt; +}; + /** * Base interface class for an controller. The interface may not be used to implement a controller. * The class provides definitions for `ControllerInterface` and `ChainableControllerInterface` @@ -175,13 +194,11 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy * * \param[in] time The time at the start of this control loop iteration * \param[in] period The measured time taken by the last control loop iteration - * \returns A pair with the first element being a boolean indicating if the async callback method - * was triggered and the second element being the last return value of the async function. For - * more details check the AsyncFunctionHandler implementation in `realtime_tools` package. + * \returns ControllerUpdateStatus. The status contains information if the update was triggered + * successfully, the result of the update method and the execution duration of the update method. */ CONTROLLER_INTERFACE_PUBLIC - std::pair trigger_update( - const rclcpp::Time & time, const rclcpp::Duration & period); + ControllerUpdateStatus trigger_update(const rclcpp::Time & time, const rclcpp::Duration & period); CONTROLLER_INTERFACE_PUBLIC std::shared_ptr get_node(); diff --git a/controller_interface/src/controller_interface_base.cpp b/controller_interface/src/controller_interface_base.cpp index 0713ec3c25..065fe77061 100644 --- a/controller_interface/src/controller_interface_base.cpp +++ b/controller_interface/src/controller_interface_base.cpp @@ -159,12 +159,14 @@ const rclcpp_lifecycle::State & ControllerInterfaceBase::get_lifecycle_state() c return node_->get_current_state(); } -std::pair ControllerInterfaceBase::trigger_update( +ControllerUpdateStatus ControllerInterfaceBase::trigger_update( const rclcpp::Time & time, const rclcpp::Duration & period) { + ControllerUpdateStatus status; trigger_stats_.total_triggers++; if (is_async()) { + const rclcpp::Time last_trigger_time = async_handler_->get_current_callback_time(); const auto result = async_handler_->trigger_async_callback(time, period); if (!result.first) { @@ -174,12 +176,28 @@ std::pair ControllerInterfaceBase::trigger_update( "The controller missed %u update cycles out of %u total triggers.", trigger_stats_.failed_triggers, trigger_stats_.total_triggers); } - return result; + status.successful = result.first; + status.result = result.second; + const auto execution_time = async_handler_->get_last_execution_time(); + if (execution_time.count() > 0) + { + status.execution_time = execution_time; + } + if (last_trigger_time.get_clock_type() != RCL_CLOCK_UNINITIALIZED) + { + status.period = time - last_trigger_time; + } } else { - return std::make_pair(true, update(time, period)); + const auto start_time = std::chrono::steady_clock::now(); + status.successful = true; + status.result = update(time, period); + status.execution_time = std::chrono::duration_cast( + std::chrono::steady_clock::now() - start_time); + status.period = period; } + return status; } std::shared_ptr ControllerInterfaceBase::get_node() diff --git a/controller_manager/CMakeLists.txt b/controller_manager/CMakeLists.txt index ea5fc176cd..dba9531e45 100644 --- a/controller_manager/CMakeLists.txt +++ b/controller_manager/CMakeLists.txt @@ -16,6 +16,8 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS rclcpp realtime_tools std_msgs + libstatistics_collector + generate_parameter_library ) find_package(ament_cmake REQUIRED) @@ -27,6 +29,10 @@ foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS}) find_package(${Dependency} REQUIRED) endforeach() +generate_parameter_library(controller_manager_parameters + src/controller_manager_parameters.yaml +) + add_library(controller_manager SHARED src/controller_manager.cpp ) @@ -35,6 +41,9 @@ target_include_directories(controller_manager PUBLIC $ $ ) +target_link_libraries(controller_manager PUBLIC + controller_manager_parameters +) ament_target_dependencies(controller_manager PUBLIC ${THIS_PACKAGE_INCLUDE_DEPENDS}) # Causes the visibility macros to use dllexport rather than dllimport, @@ -236,7 +245,7 @@ install( DESTINATION include/controller_manager ) install( - TARGETS controller_manager + TARGETS controller_manager controller_manager_parameters EXPORT export_controller_manager RUNTIME DESTINATION bin LIBRARY DESTINATION lib diff --git a/controller_manager/doc/parameters_context.yaml b/controller_manager/doc/parameters_context.yaml new file mode 100644 index 0000000000..a015765c79 --- /dev/null +++ b/controller_manager/doc/parameters_context.yaml @@ -0,0 +1,21 @@ +hardware_components_initial_state: | + Map of parameters for controlled lifecycle management of hardware components. + The names of the components are defined as attribute of ````-tag in ``robot_description``. + Hardware components found in ``robot_description``, but without explicit state definition will be immediately activated. + Detailed explanation of each parameter is given below. + The full structure of the map is given in the following example: + + .. code-block:: yaml + + hardware_components_initial_state: + unconfigured: + - "arm1" + - "arm2" + inactive: + - "base3" + +diagnostics.threshold.controllers.periodicity: | + The ``periodicity`` diagnostics will be published only for the asynchronous controllers, because any affect to the synchronous controllers will be reflected directly in the controller manager's periodicity. + +diagnostics.threshold.controllers.execution_time: | + The ``execution_time`` diagnostics will be published for all controllers. The ``mean_error`` for a synchronous controller will be computed against zero, as it should be as low as possible. However, the ``mean_error`` for an asynchronous controller will be computed against the controller's desired update period, as the controller can take a maximum of the desired period cycle to execute it's update cycle. diff --git a/controller_manager/doc/userdoc.rst b/controller_manager/doc/userdoc.rst index 5a86c3373b..872a695d0f 100644 --- a/controller_manager/doc/userdoc.rst +++ b/controller_manager/doc/userdoc.rst @@ -57,32 +57,6 @@ robot_description [std_msgs::msg::String] Parameters ----------- -hardware_components_initial_state - Map of parameters for controlled lifecycle management of hardware components. - The names of the components are defined as attribute of ````-tag in ``robot_description``. - Hardware components found in ``robot_description``, but without explicit state definition will be immediately activated. - Detailed explanation of each parameter is given below. - The full structure of the map is given in the following example: - -.. code-block:: yaml - - hardware_components_initial_state: - unconfigured: - - "arm1" - - "arm2" - inactive: - - "base3" - -hardware_components_initial_state.unconfigured (optional; list; default: empty) - Defines which hardware components will be only loaded immediately when controller manager is started. - -hardware_components_initial_state.inactive (optional; list; default: empty) - Defines which hardware components will be configured immediately when controller manager is started. - -update_rate (mandatory; integer) - The frequency of controller manager's real-time update loop. - This loop reads states from hardware, updates controller and writes commands to hardware. - .type Name of a plugin exported using ``pluginlib`` for a controller. This is a class from which controller's instance with name "``controller_name``" is created. @@ -99,6 +73,16 @@ update_rate (mandatory; integer) The fallback controllers activation is subject to the availability of the state and command interfaces at the time of activation. It is recommended to test the fallback strategy in simulation before deploying it on the real robot. +.. generate_parameter_library_details:: + ../src/controller_manager_parameters.yaml + parameters_context.yaml + +**An example parameter file:** + +.. generate_parameter_library_default:: + ../src/controller_manager_parameters.yaml + + Handling Multiple Controller Managers ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ diff --git a/controller_manager/include/controller_manager/controller_manager.hpp b/controller_manager/include/controller_manager/controller_manager.hpp index 068eefc1f9..332d565238 100644 --- a/controller_manager/include/controller_manager/controller_manager.hpp +++ b/controller_manager/include/controller_manager/controller_manager.hpp @@ -50,6 +50,8 @@ namespace controller_manager { +class ParamListener; +class Params; using ControllersListIterator = std::vector::const_iterator; CONTROLLER_MANAGER_PUBLIC rclcpp::NodeOptions get_cm_node_options(); @@ -346,7 +348,7 @@ class ControllerManager : public rclcpp::Node // Per controller update rate support unsigned int update_loop_counter_ = 0; - unsigned int update_rate_ = 100; + unsigned int update_rate_; std::vector> chained_controllers_configuration_; std::unique_ptr resource_manager_; @@ -357,6 +359,8 @@ class ControllerManager : public rclcpp::Node const std::string & command_interface); void init_controller_manager(); + void initialize_parameters(); + /** * Clear request lists used when switching controllers. The lists are shared between "callback" * and "control loop" threads. @@ -473,6 +477,8 @@ class ControllerManager : public rclcpp::Node */ rclcpp::NodeOptions determine_controller_node_options(const ControllerSpec & controller) const; + std::shared_ptr cm_param_listener_; + std::shared_ptr params_; diagnostic_updater::Updater diagnostics_updater_; std::shared_ptr executor_; @@ -603,6 +609,8 @@ class ControllerManager : public rclcpp::Node rclcpp::Subscription::SharedPtr robot_description_subscription_; rclcpp::TimerBase::SharedPtr robot_description_notification_timer_; + controller_manager::MovingAverageStatistics periodicity_stats_; + struct SwitchParams { void reset() diff --git a/controller_manager/include/controller_manager/controller_spec.hpp b/controller_manager/include/controller_manager/controller_spec.hpp index 0f44867814..9cc508772d 100644 --- a/controller_manager/include/controller_manager/controller_spec.hpp +++ b/controller_manager/include/controller_manager/controller_spec.hpp @@ -24,9 +24,13 @@ #include #include "controller_interface/controller_interface_base.hpp" #include "hardware_interface/controller_info.hpp" +#include "libstatistics_collector/moving_average_statistics/moving_average.hpp" namespace controller_manager { + +using MovingAverageStatistics = + libstatistics_collector::moving_average_statistics::MovingAverageStatistics; /// Controller Specification /** * This struct contains both a pointer to a given controller, \ref c, as well @@ -35,9 +39,18 @@ namespace controller_manager */ struct ControllerSpec { + ControllerSpec() + { + last_update_cycle_time = std::make_shared(0, 0, RCL_CLOCK_UNINITIALIZED); + execution_time_statistics = std::make_shared(); + periodicity_statistics = std::make_shared(); + } + hardware_interface::ControllerInfo info; controller_interface::ControllerInterfaceBaseSharedPtr c; std::shared_ptr last_update_cycle_time; + std::shared_ptr execution_time_statistics; + std::shared_ptr periodicity_statistics; }; struct ControllerChainSpec diff --git a/controller_manager/package.xml b/controller_manager/package.xml index 18189d5d16..42211e4e40 100644 --- a/controller_manager/package.xml +++ b/controller_manager/package.xml @@ -28,6 +28,8 @@ ros2param ros2run std_msgs + libstatistics_collector + generate_parameter_library ament_cmake_gmock ament_cmake_pytest diff --git a/controller_manager/src/controller_manager.cpp b/controller_manager/src/controller_manager.cpp index 82546aaeda..56e95c9f7b 100644 --- a/controller_manager/src/controller_manager.cpp +++ b/controller_manager/src/controller_manager.cpp @@ -28,6 +28,8 @@ #include "rclcpp/version.h" #include "rclcpp_lifecycle/state.hpp" +#include "controller_manager_parameters.hpp" + namespace // utility { static constexpr const char * kControllerInterfaceNamespace = "controller_interface"; @@ -237,6 +239,7 @@ ControllerManager::ControllerManager( kControllerInterfaceNamespace, kChainableControllerInterfaceClassName)), cm_node_options_(options) { + initialize_parameters(); init_controller_manager(); } @@ -245,10 +248,6 @@ ControllerManager::ControllerManager( bool activate_all_hw_components, const std::string & manager_node_name, const std::string & node_namespace, const rclcpp::NodeOptions & options) : rclcpp::Node(manager_node_name, node_namespace, options), - update_rate_(get_parameter_or("update_rate", 100)), - resource_manager_(std::make_unique( - urdf, this->get_node_clock_interface(), this->get_node_logging_interface(), - activate_all_hw_components, update_rate_)), diagnostics_updater_(this), executor_(executor), loader_(std::make_shared>( @@ -258,6 +257,10 @@ ControllerManager::ControllerManager( kControllerInterfaceNamespace, kChainableControllerInterfaceClassName)), cm_node_options_(options) { + initialize_parameters(); + resource_manager_ = std::make_unique( + urdf, this->get_node_clock_interface(), this->get_node_logging_interface(), + activate_all_hw_components, params_->update_rate); init_controller_manager(); } @@ -276,18 +279,13 @@ ControllerManager::ControllerManager( kControllerInterfaceNamespace, kChainableControllerInterfaceClassName)), cm_node_options_(options) { + initialize_parameters(); init_controller_manager(); } void ControllerManager::init_controller_manager() { // Get parameters needed for RT "update" loop to work - if (!get_parameter("update_rate", update_rate_)) - { - RCLCPP_WARN( - get_logger(), "'update_rate' parameter not set, using default value of %d Hz.", update_rate_); - } - if (is_resource_manager_initialized()) { init_services(); @@ -313,6 +311,7 @@ void ControllerManager::init_controller_manager() robot_description_subscription_->get_topic_name()); // Setup diagnostics + periodicity_stats_.Reset(); diagnostics_updater_.setHardwareID("ros2_control"); diagnostics_updater_.add( "Controllers Activity", this, &ControllerManager::controller_activity_diagnostic_callback); @@ -324,6 +323,25 @@ void ControllerManager::init_controller_manager() &ControllerManager::controller_manager_diagnostic_callback); } +void ControllerManager::initialize_parameters() +{ + // Initialize parameters + try + { + cm_param_listener_ = std::make_shared( + this->get_node_parameters_interface(), this->get_logger()); + params_ = std::make_shared(cm_param_listener_->get_params()); + update_rate_ = static_cast(params_->update_rate); + } + catch (const std::exception & e) + { + RCLCPP_ERROR( + this->get_logger(), + "Exception thrown while initializing controller manager parameters: %s \n", e.what()); + throw e; + } +} + void ControllerManager::robot_description_callback(const std_msgs::msg::String & robot_description) { RCLCPP_INFO(get_logger(), "Received robot description from topic."); @@ -365,51 +383,52 @@ void ControllerManager::init_resource_manager(const std::string & robot_descript using lifecycle_msgs::msg::State; auto set_components_to_state = - [&](const std::string & parameter_name, rclcpp_lifecycle::State state) + [&](const std::vector & components_to_set, rclcpp_lifecycle::State state) { - std::vector components_to_set = std::vector({}); - if (get_parameter(parameter_name, components_to_set)) + for (const auto & component : components_to_set) { - for (const auto & component : components_to_set) + if (component.empty()) { - if (component.empty()) - { - continue; - } - if (components_to_activate.find(component) == components_to_activate.end()) - { - RCLCPP_WARN( - get_logger(), "Hardware component '%s' is unknown, therefore not set in '%s' state.", - component.c_str(), state.label().c_str()); - } - else + continue; + } + if (components_to_activate.find(component) == components_to_activate.end()) + { + RCLCPP_WARN( + get_logger(), "Hardware component '%s' is unknown, therefore not set in '%s' state.", + component.c_str(), state.label().c_str()); + } + else + { + RCLCPP_INFO( + get_logger(), "Setting component '%s' to '%s' state.", component.c_str(), + state.label().c_str()); + if ( + resource_manager_->set_component_state(component, state) == + hardware_interface::return_type::ERROR) { - RCLCPP_INFO( - get_logger(), "Setting component '%s' to '%s' state.", component.c_str(), - state.label().c_str()); - if ( - resource_manager_->set_component_state(component, state) == - hardware_interface::return_type::ERROR) - { - throw std::runtime_error( - "Failed to set the initial state of the component : " + component + " to " + - state.label()); - } - components_to_activate.erase(component); + throw std::runtime_error( + "Failed to set the initial state of the component : " + component + " to " + + state.label()); } + components_to_activate.erase(component); } } }; + if (cm_param_listener_->is_old(*params_)) + { + *params_ = cm_param_listener_->get_params(); + } + // unconfigured (loaded only) set_components_to_state( - "hardware_components_initial_state.unconfigured", + params_->hardware_components_initial_state.unconfigured, rclcpp_lifecycle::State( State::PRIMARY_STATE_UNCONFIGURED, hardware_interface::lifecycle_state_names::UNCONFIGURED)); // inactive (configured) set_components_to_state( - "hardware_components_initial_state.inactive", + params_->hardware_components_initial_state.inactive, rclcpp_lifecycle::State( State::PRIMARY_STATE_INACTIVE, hardware_interface::lifecycle_state_names::INACTIVE)); @@ -545,6 +564,8 @@ controller_interface::ControllerInterfaceBaseSharedPtr ControllerManager::load_c controller_spec.info.type = controller_type; controller_spec.last_update_cycle_time = std::make_shared( 0, 0, this->get_node_clock_interface()->get_clock()->get_clock_type()); + controller_spec.execution_time_statistics = std::make_shared(); + controller_spec.periodicity_statistics = std::make_shared(); // We have to fetch the parameters_file at the time of loading the controller, because this way we // can load them at the creation of the LifeCycleNode and this helps in using the features such as @@ -1774,6 +1795,8 @@ void ControllerManager::activate_controllers( try { + found_it->periodicity_statistics->Reset(); + found_it->execution_time_statistics->Reset(); const auto new_state = controller->get_node()->activate(); if (new_state.id() != lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) { @@ -2255,6 +2278,7 @@ std::vector ControllerManager::get_controller_names() void ControllerManager::read(const rclcpp::Time & time, const rclcpp::Duration & period) { + periodicity_stats_.AddMeasurement(1.0 / period.seconds()); auto [ok, failed_hardware_names] = resource_manager_->read(time, period); if (!ok) @@ -2367,12 +2391,14 @@ controller_interface::return_type ControllerManager::update( : rclcpp::Duration::from_seconds((1.0 / controller_update_rate)); const rclcpp::Time current_time = get_clock()->now(); + bool first_update_cycle = false; if ( *loaded_controller.last_update_cycle_time == rclcpp::Time(0, 0, this->get_node_clock_interface()->get_clock()->get_clock_type())) { + first_update_cycle = true; // it is zero after activation - *loaded_controller.last_update_cycle_time = current_time - controller_period; + *loaded_controller.last_update_cycle_time = current_time; RCLCPP_DEBUG( get_logger(), "Setting last_update_cycle_time to %fs for the controller : %s", loaded_controller.last_update_cycle_time->seconds(), loaded_controller.info.name.c_str()); @@ -2390,7 +2416,7 @@ controller_interface::return_type ControllerManager::update( run_controller_at_cm_rate || (time == rclcpp::Time(0, 0, this->get_node_clock_interface()->get_clock()->get_clock_type())) || - (controller_actual_period.seconds() * controller_update_rate >= 0.99); + (controller_actual_period.seconds() * controller_update_rate >= 0.99) || first_update_cycle; RCLCPP_DEBUG( get_logger(), "update_loop_counter: '%d ' controller_go: '%s ' controller_name: '%s '", @@ -2404,8 +2430,20 @@ controller_interface::return_type ControllerManager::update( // Catch exceptions thrown by the controller update function try { - std::tie(trigger_status, controller_ret) = - loaded_controller.c->trigger_update(time, controller_actual_period); + const auto trigger_result = + loaded_controller.c->trigger_update(current_time, controller_actual_period); + trigger_status = trigger_result.successful; + controller_ret = trigger_result.result; + if (trigger_status && trigger_result.execution_time.has_value()) + { + loaded_controller.execution_time_statistics->AddMeasurement( + static_cast(trigger_result.execution_time.value().count()) / 1.e3); + } + if (!first_update_cycle && trigger_status && trigger_result.period.has_value()) + { + loaded_controller.periodicity_statistics->AddMeasurement( + 1.0 / trigger_result.period.value().seconds()); + } } catch (const std::exception & e) { @@ -3062,34 +3100,140 @@ void ControllerManager::controller_activity_diagnostic_callback( std::lock_guard guard(rt_controllers_wrapper_.controllers_lock_); const std::vector & controllers = rt_controllers_wrapper_.get_updated_list(guard); bool all_active = true; + const std::string periodicity_suffix = ".periodicity"; + const std::string exec_time_suffix = ".execution_time"; + const std::string state_suffix = ".state"; + + if (cm_param_listener_->is_old(*params_)) + { + *params_ = cm_param_listener_->get_params(); + } + + auto make_stats_string = + [](const auto & statistics_data, const std::string & measurement_unit) -> std::string + { + std::ostringstream oss; + oss << std::fixed << std::setprecision(2); + oss << "Avg: " << statistics_data.average << " [" << statistics_data.min << " - " + << statistics_data.max << "] " << measurement_unit + << ", StdDev: " << statistics_data.standard_deviation; + return oss.str(); + }; + + // Variable to define the overall status of the controller diagnostics + auto level = diagnostic_msgs::msg::DiagnosticStatus::OK; + + std::vector high_exec_time_controllers; + std::vector bad_periodicity_async_controllers; for (size_t i = 0; i < controllers.size(); ++i) { + const bool is_async = controllers[i].c->is_async(); if (!is_controller_active(controllers[i].c)) { all_active = false; } - stat.add(controllers[i].info.name, controllers[i].c->get_lifecycle_state().label()); + stat.add( + controllers[i].info.name + state_suffix, controllers[i].c->get_lifecycle_state().label()); + if (is_controller_active(controllers[i].c)) + { + const auto periodicity_stats = controllers[i].periodicity_statistics->GetStatistics(); + const auto exec_time_stats = controllers[i].execution_time_statistics->GetStatistics(); + stat.add( + controllers[i].info.name + exec_time_suffix, make_stats_string(exec_time_stats, "us")); + if (is_async) + { + stat.add( + controllers[i].info.name + periodicity_suffix, + make_stats_string(periodicity_stats, "Hz") + + " -> Desired : " + std::to_string(controllers[i].c->get_update_rate()) + " Hz"); + const double periodicity_error = std::abs( + periodicity_stats.average - static_cast(controllers[i].c->get_update_rate())); + if ( + periodicity_error > + params_->diagnostics.threshold.controllers.periodicity.mean_error.error || + periodicity_stats.standard_deviation > + params_->diagnostics.threshold.controllers.periodicity.standard_deviation.error) + { + level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; + add_element_to_list(bad_periodicity_async_controllers, controllers[i].info.name); + } + else if ( + periodicity_error > + params_->diagnostics.threshold.controllers.periodicity.mean_error.warn || + periodicity_stats.standard_deviation > + params_->diagnostics.threshold.controllers.periodicity.standard_deviation.warn) + { + if (level != diagnostic_msgs::msg::DiagnosticStatus::ERROR) + { + level = diagnostic_msgs::msg::DiagnosticStatus::WARN; + } + add_element_to_list(bad_periodicity_async_controllers, controllers[i].info.name); + } + } + const double max_exp_exec_time = is_async ? 1.e6 / controllers[i].c->get_update_rate() : 0.0; + if ( + (exec_time_stats.average - max_exp_exec_time) > + params_->diagnostics.threshold.controllers.execution_time.mean_error.error || + exec_time_stats.standard_deviation > + params_->diagnostics.threshold.controllers.execution_time.standard_deviation.error) + { + level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; + high_exec_time_controllers.push_back(controllers[i].info.name); + } + else if ( + (exec_time_stats.average - max_exp_exec_time) > + params_->diagnostics.threshold.controllers.execution_time.mean_error.warn || + exec_time_stats.standard_deviation > + params_->diagnostics.threshold.controllers.execution_time.standard_deviation.warn) + { + if (level != diagnostic_msgs::msg::DiagnosticStatus::ERROR) + { + level = diagnostic_msgs::msg::DiagnosticStatus::WARN; + } + high_exec_time_controllers.push_back(controllers[i].info.name); + } + } + } + + stat.summary( + diagnostic_msgs::msg::DiagnosticStatus::OK, + all_active ? "All controllers are active" : "Not all controllers are active"); + + if (!high_exec_time_controllers.empty()) + { + std::string high_exec_time_controllers_string; + for (const auto & controller : high_exec_time_controllers) + { + high_exec_time_controllers_string.append(controller); + high_exec_time_controllers_string.append(" "); + } + stat.mergeSummary( + level, + "\nControllers with high execution time : [ " + high_exec_time_controllers_string + "]"); + } + if (!bad_periodicity_async_controllers.empty()) + { + std::string bad_periodicity_async_controllers_string; + for (const auto & controller : bad_periodicity_async_controllers) + { + bad_periodicity_async_controllers_string.append(controller); + bad_periodicity_async_controllers_string.append(" "); + } + stat.mergeSummary( + level, + "\nControllers with bad periodicity : [ " + bad_periodicity_async_controllers_string + "]"); } if (!atleast_one_hw_active) { - stat.summary( + stat.mergeSummary( diagnostic_msgs::msg::DiagnosticStatus::ERROR, "No hardware components are currently active to activate controllers"); } - else + else if (controllers.empty()) { - if (controllers.empty()) - { - stat.summary( - diagnostic_msgs::msg::DiagnosticStatus::WARN, "No controllers are currently loaded"); - } - else - { - stat.summary( - diagnostic_msgs::msg::DiagnosticStatus::OK, - all_active ? "All controllers are active" : "Not all controllers are active"); - } + stat.mergeSummary( + diagnostic_msgs::msg::DiagnosticStatus::WARN, "No controllers are currently loaded"); } } @@ -3142,7 +3286,14 @@ void ControllerManager::hardware_components_diagnostic_callback( void ControllerManager::controller_manager_diagnostic_callback( diagnostic_updater::DiagnosticStatusWrapper & stat) { + const std::string periodicity_stat_name = "periodicity"; + const auto cm_stats = periodicity_stats_.GetStatistics(); stat.add("update_rate", std::to_string(get_update_rate())); + stat.add(periodicity_stat_name + ".average", std::to_string(cm_stats.average)); + stat.add( + periodicity_stat_name + ".standard_deviation", std::to_string(cm_stats.standard_deviation)); + stat.add(periodicity_stat_name + ".min", std::to_string(cm_stats.min)); + stat.add(periodicity_stat_name + ".max", std::to_string(cm_stats.max)); if (is_resource_manager_initialized()) { stat.summary(diagnostic_msgs::msg::DiagnosticStatus::OK, "Controller Manager is running"); @@ -3161,6 +3312,27 @@ void ControllerManager::controller_manager_diagnostic_callback( "Resource Manager is not initialized properly!"); } } + + const double periodicity_error = std::abs(cm_stats.average - get_update_rate()); + const std::string diag_summary = + "Controller Manager has bad periodicity : " + std::to_string(cm_stats.average) + + " Hz. Expected consistent " + std::to_string(get_update_rate()) + " Hz"; + if ( + periodicity_error > + params_->diagnostics.threshold.controller_manager.periodicity.mean_error.error || + cm_stats.standard_deviation > + params_->diagnostics.threshold.controller_manager.periodicity.standard_deviation.error) + { + stat.mergeSummary(diagnostic_msgs::msg::DiagnosticStatus::ERROR, diag_summary); + } + else if ( + periodicity_error > + params_->diagnostics.threshold.controller_manager.periodicity.mean_error.warn || + cm_stats.standard_deviation > + params_->diagnostics.threshold.controller_manager.periodicity.standard_deviation.warn) + { + stat.mergeSummary(diagnostic_msgs::msg::DiagnosticStatus::WARN, diag_summary); + } } void ControllerManager::update_list_with_controller_chain( diff --git a/controller_manager/src/controller_manager_parameters.yaml b/controller_manager/src/controller_manager_parameters.yaml new file mode 100644 index 0000000000..1bb9b152b1 --- /dev/null +++ b/controller_manager/src/controller_manager_parameters.yaml @@ -0,0 +1,136 @@ +controller_manager: + update_rate: { + type: int, + default_value: 100, + read_only: true, + description: "The frequency of controller manager's real-time update loop. This loop reads states from hardware, updates controllers and writes commands to hardware." + } + + hardware_components_initial_state: + unconfigured: { + type: string_array, + default_value: [], + description: "Defines which hardware components will be only loaded when controller manager is started. These hardware components will need to be configured and activated manually or via a hardware spawner.", + validation: { + unique<>: null, + } + } + + inactive: { + type: string_array, + default_value: [], + description: "Defines which hardware components will be configured when controller manager is started. These hardware components will need to be activated manually or via a hardware spawner.", + validation: { + unique<>: null, + } + } + + diagnostics: + threshold: + controller_manager: + periodicity: + mean_error: + warn: { + type: double, + default_value: 5.0, + description: "The warning threshold for the mean error of the controller manager's periodicity. If the mean error exceeds this threshold, a warning diagnostic will be published.", + validation: { + gt<>: 0.0, + } + } + error: { + type: double, + default_value: 10.0, + description: "The error threshold for the mean error of the controller manager's periodicity. If the mean error exceeds this threshold, an error diagnostic will be published.", + validation: { + gt<>: 0.0, + } + } + standard_deviation: + warn: { + type: double, + default_value: 5.0, + description: "The warning threshold for the standard deviation of the controller manager's periodicity. If the standard deviation exceeds this threshold, a warning diagnostic will be published.", + validation: { + gt<>: 0.0, + } + } + error: { + type: double, + default_value: 10.0, + description: "The error threshold for the standard deviation of the controller manager's periodicity. If the standard deviation exceeds this threshold, an error diagnostic will be published.", + validation: { + gt<>: 0.0, + } + } + controllers: + periodicity: + mean_error: + warn: { + type: double, + default_value: 5.0, + description: "The warning threshold for the mean error of the controller update loop. If the mean error exceeds this threshold, a warning diagnostic will be published. This diagnostics will be published only for the asynchronous controllers, because any affect to the synchronous controllers will be reflected directly in the controller manager's periodicity.", + validation: { + gt<>: 0.0, + } + } + error: { + type: double, + default_value: 10.0, + description: "The error threshold for the mean error of the controller update loop. If the mean error exceeds this threshold, an error diagnostic will be published. This diagnostics will be published only for the asynchronous controllers, because any affect to the synchronous controllers will be reflected directly in the controller manager's periodicity.", + validation: { + gt<>: 0.0, + } + } + standard_deviation: + warn: { + type: double, + default_value: 5.0, + description: "The warning threshold for the standard deviation of the controller update loop. If the standard deviation exceeds this threshold, a warning diagnostic will be published. This diagnostics will be published only for the asynchronous controllers, because any affect to the synchronous controllers will be reflected directly in the controller manager's periodicity.", + validation: { + gt<>: 0.0, + } + } + error: { + type: double, + default_value: 10.0, + description: "The error threshold for the standard deviation of the controller update loop. If the standard deviation exceeds this threshold, an error diagnostic will be published. This diagnostics will be published only for the asynchronous controllers, because any affect to the synchronous controllers will be reflected directly in the controller manager's periodicity.", + validation: { + gt<>: 0.0, + } + } + execution_time: + mean_error: + warn: { + type: double, + default_value: 1000.0, + description: "The warning threshold for the mean error of the controller's update cycle execution time in microseconds. If the mean error exceeds this threshold, a warning diagnostic will be published. The ``mean_error`` for a synchronous controller will be computed against zero, as it should be as low as possible. However, the ``mean_error`` for an asynchronous controller will be computed against the controller's desired update period, as the controller can take a maximum of the desired period cycle to execute it's update cycle", + validation: { + gt<>: 0.0, + } + } + error: { + type: double, + default_value: 2000.0, + description: "The error threshold for the mean error of the controller's update cycle execution time in microseconds. If the mean error exceeds this threshold, an error diagnostic will be published. The ``mean_error`` for a synchronous controller will be computed against zero, as it should be as low as possible. However, the ``mean_error`` for an asynchronous controller will be computed against the controller's desired update period, as the controller can take a maximum of the desired period cycle to execute it's update cycle", + validation: { + gt<>: 0.0, + } + } + standard_deviation: + warn: { + type: double, + default_value: 100.0, + description: "The warning threshold for the standard deviation of the controller's update cycle execution time. If the standard deviation exceeds this threshold, a warning diagnostic will be published.", + validation: { + gt<>: 0.0, + } + } + error: { + type: double, + default_value: 200.0, + description: "The error threshold for the standard deviation of the controller's update cycle execution time. If the standard deviation exceeds this threshold, an error diagnostic will be published.", + validation: { + gt<>: 0.0, + } + } diff --git a/controller_manager/src/ros2_control_node.cpp b/controller_manager/src/ros2_control_node.cpp index 5dace36d34..da79de76a3 100644 --- a/controller_manager/src/ros2_control_node.cpp +++ b/controller_manager/src/ros2_control_node.cpp @@ -109,7 +109,7 @@ int main(int argc, char ** argv) next_iteration_time{cm_now}; // for calculating the measured period of the loop - rclcpp::Time previous_time = cm->now(); + rclcpp::Time previous_time = cm->now() - period; while (rclcpp::ok()) { diff --git a/controller_manager/test/test_controller_manager.cpp b/controller_manager/test/test_controller_manager.cpp index 0c4e51985f..b715bc23dc 100644 --- a/controller_manager/test/test_controller_manager.cpp +++ b/controller_manager/test/test_controller_manager.cpp @@ -366,6 +366,7 @@ TEST_P(TestControllerManagerWithStrictness, async_controller_lifecycle) EXPECT_EQ( lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, test_controller->get_lifecycle_state().id()); + time_ = cm_->get_clock()->now(); EXPECT_EQ( controller_interface::return_type::OK, cm_->update(time_, rclcpp::Duration::from_seconds(0.01))); @@ -373,6 +374,21 @@ TEST_P(TestControllerManagerWithStrictness, async_controller_lifecycle) std::this_thread::sleep_for( std::chrono::milliseconds(1000 / (test_controller->get_update_rate()))); EXPECT_EQ(test_controller->internal_counter, 1u); + EXPECT_EQ(test_controller->update_period_.seconds(), 0.0) + << "The first trigger cycle should have zero period"; + + const double exp_period = (cm_->get_clock()->now() - time_).seconds(); + time_ = cm_->get_clock()->now(); + EXPECT_EQ( + controller_interface::return_type::OK, + cm_->update(time_, rclcpp::Duration::from_seconds(0.01))); + EXPECT_EQ(test_controller->internal_counter, 1u); + std::this_thread::sleep_for( + std::chrono::milliseconds(1000 / (test_controller->get_update_rate()))); + EXPECT_EQ(test_controller->internal_counter, 2u); + EXPECT_THAT( + test_controller->update_period_.seconds(), + testing::AllOf(testing::Gt(0.6 * exp_period), testing::Lt((1.4 * exp_period)))); size_t last_internal_counter = test_controller->internal_counter; // Stop controller, will take effect at the end of the update function @@ -576,7 +592,26 @@ TEST_P(TestControllerManagerWithUpdateRates, per_controller_equal_and_higher_upd // [cm_update_rate, 2*cm_update_rate) EXPECT_THAT( test_controller->update_period_.seconds(), - testing::AllOf(testing::Ge(0.9 / cm_update_rate), testing::Lt((1.1 / cm_update_rate)))); + testing::AllOf(testing::Ge(0.85 / cm_update_rate), testing::Lt((1.15 / cm_update_rate)))); + ASSERT_EQ( + test_controller->internal_counter, + cm_->get_loaded_controllers()[0].execution_time_statistics->GetCount()); + ASSERT_EQ( + test_controller->internal_counter - 1, + cm_->get_loaded_controllers()[0].periodicity_statistics->GetCount()) + << "The first update is not counted in periodicity statistics"; + EXPECT_THAT( + cm_->get_loaded_controllers()[0].periodicity_statistics->Average(), + testing::AllOf( + testing::Ge(0.95 * cm_->get_update_rate()), testing::Lt((1.05 * cm_->get_update_rate())))); + EXPECT_THAT( + cm_->get_loaded_controllers()[0].periodicity_statistics->Min(), + testing::AllOf( + testing::Ge(0.85 * cm_->get_update_rate()), testing::Lt((1.2 * cm_->get_update_rate())))); + EXPECT_THAT( + cm_->get_loaded_controllers()[0].periodicity_statistics->Max(), + testing::AllOf( + testing::Ge(0.85 * cm_->get_update_rate()), testing::Lt((1.2 * cm_->get_update_rate())))); loop_rate.sleep(); } // if we do 2 times of the controller_manager update rate, the internal counter should be @@ -683,6 +718,8 @@ TEST_P(TestControllerUpdateRates, check_the_controller_update_rate) const auto initial_counter = test_controller->internal_counter; // don't start with zero to check if the period is correct if controller is activated anytime rclcpp::Time time = time_; + const auto exp_periodicity = + cm_update_rate / std::ceil(static_cast(cm_update_rate) / controller_update_rate); for (size_t update_counter = 0; update_counter <= 10 * cm_update_rate; ++update_counter) { rclcpp::Time old_time = time; @@ -691,19 +728,36 @@ TEST_P(TestControllerUpdateRates, check_the_controller_update_rate) EXPECT_EQ( controller_interface::return_type::OK, cm_->update(time, rclcpp::Duration::from_seconds(0.01))); - // In case of a non perfect divisor, the update period should respect the rule - // [controller_update_rate, 2*controller_update_rate) - EXPECT_THAT( - test_controller->update_period_.seconds(), - testing::AllOf( - testing::Gt(0.99 * controller_period), - testing::Lt((1.05 * controller_period) + PERIOD.seconds()))) - << "update_counter: " << update_counter << " desired controller period: " << controller_period - << " actual controller period: " << test_controller->update_period_.seconds(); - if (update_counter % cm_update_rate == 0) + if (test_controller->internal_counter - initial_counter > 0) + { + // In case of a non perfect divisor, the update period should respect the rule + // [controller_update_rate, 2*controller_update_rate) + EXPECT_THAT( + test_controller->update_period_.seconds(), + testing::AllOf( + testing::Gt(0.99 * controller_period), + testing::Lt((1.05 * controller_period) + PERIOD.seconds()))) + << "update_counter: " << update_counter + << " desired controller period: " << controller_period + << " actual controller period: " << test_controller->update_period_.seconds(); + } + else + { + // Check that the first cycle update period is zero + EXPECT_EQ(test_controller->update_period_.seconds(), 0.0); + } + + if (update_counter > 0 && update_counter % cm_update_rate == 0) { const double no_of_secs_passed = static_cast(update_counter) / cm_update_rate; + const auto actual_counter = test_controller->internal_counter - initial_counter; + const unsigned int exp_counter = + static_cast(exp_periodicity * no_of_secs_passed); + SCOPED_TRACE( + "The internal counter is : " + std::to_string(actual_counter) + " [" + + std::to_string(exp_counter - 1) + ", " + std::to_string(exp_counter + 1) + + "] and number of seconds passed : " + std::to_string(no_of_secs_passed)); // NOTE: here EXPECT_NEAR is used because it is observed that in the first iteration of whole // cycle of cm_update_rate counts, there is one count missing, but in rest of the 9 cycles it // is clearly tracking, so adding 1 here won't affect the final count. @@ -711,10 +765,26 @@ TEST_P(TestControllerUpdateRates, check_the_controller_update_rate) // cycle and then on accumulating 37 on every other update cycle so at the end of the 10 // cycles it will have 369 instead of 370. EXPECT_THAT( - test_controller->internal_counter - initial_counter, - testing::AnyOf( - testing::Ge((controller_update_rate - 1) * no_of_secs_passed), - testing::Lt((controller_update_rate * no_of_secs_passed)))); + actual_counter, testing::AnyOf(testing::Ge(exp_counter - 1), testing::Le(exp_counter + 1))); + ASSERT_EQ( + test_controller->internal_counter, + cm_->get_loaded_controllers()[0].execution_time_statistics->GetCount()); + ASSERT_EQ( + test_controller->internal_counter - 1, + cm_->get_loaded_controllers()[0].periodicity_statistics->GetCount()) + << "The first update is not counted in periodicity statistics"; + EXPECT_THAT( + cm_->get_loaded_controllers()[0].periodicity_statistics->Average(), + testing::AllOf(testing::Ge(0.95 * exp_periodicity), testing::Lt((1.05 * exp_periodicity)))); + EXPECT_THAT( + cm_->get_loaded_controllers()[0].periodicity_statistics->Min(), + testing::AllOf(testing::Ge(0.85 * exp_periodicity), testing::Lt((1.2 * exp_periodicity)))); + EXPECT_THAT( + cm_->get_loaded_controllers()[0].periodicity_statistics->Max(), + testing::AllOf(testing::Ge(0.85 * exp_periodicity), testing::Lt((1.2 * exp_periodicity)))); + EXPECT_LT( + cm_->get_loaded_controllers()[0].execution_time_statistics->Average(), + 50.0); // 50 microseconds } } } @@ -723,6 +793,148 @@ INSTANTIATE_TEST_SUITE_P( per_controller_update_rate_check, TestControllerUpdateRates, testing::Values(10, 12, 16, 23, 37, 40, 50, 63, 71, 85, 90)); +class TestAsyncControllerUpdateRates +: public ControllerManagerFixture +{ +}; + +TEST_F(TestAsyncControllerUpdateRates, check_the_async_controller_update_rate_and_stats) +{ + const unsigned int ctrl_update_rate = cm_->get_update_rate() / 2; + auto test_controller = std::make_shared(); + cm_->add_controller( + test_controller, test_controller::TEST_CONTROLLER_NAME, + test_controller::TEST_CONTROLLER_CLASS_NAME); + EXPECT_EQ(1u, cm_->get_loaded_controllers().size()); + EXPECT_EQ(2, test_controller.use_count()); + + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, + test_controller->get_lifecycle_state().id()); + + test_controller->get_node()->set_parameter({"update_rate", static_cast(ctrl_update_rate)}); + test_controller->get_node()->set_parameter({"is_async", true}); + // configure controller + { + ControllerManagerRunner cm_runner(this); + cm_->configure_controller(test_controller::TEST_CONTROLLER_NAME); + } + ASSERT_TRUE(test_controller->is_async()); + time_ = test_controller->get_node()->now(); // set to something nonzero + cm_->get_clock()->sleep_until(time_ + PERIOD); + time_ = cm_->get_clock()->now(); + EXPECT_EQ( + controller_interface::return_type::OK, + cm_->update(time_, rclcpp::Duration::from_seconds(0.01))); + EXPECT_EQ(0u, test_controller->internal_counter) << "Controller is not started"; + + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, + test_controller->get_lifecycle_state().id()); + + // Start controller, will take effect at the end of the update function + const auto strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT; + std::vector start_controllers = {test_controller::TEST_CONTROLLER_NAME}; + std::vector stop_controllers = {}; + auto switch_future = std::async( + std::launch::async, &controller_manager::ControllerManager::switch_controller, cm_, + start_controllers, stop_controllers, strictness, true, rclcpp::Duration(0, 0)); + + ASSERT_EQ(std::future_status::timeout, switch_future.wait_for(std::chrono::milliseconds(100))) + << "switch_controller should be blocking until next update cycle"; + + cm_->get_clock()->sleep_until(time_ + PERIOD); + time_ = cm_->get_clock()->now(); + EXPECT_EQ( + controller_interface::return_type::OK, + cm_->update(time_, rclcpp::Duration::from_seconds(0.01))); + EXPECT_EQ(0u, test_controller->internal_counter) << "Controller is started at the end of update"; + { + ControllerManagerRunner cm_runner(this); + EXPECT_EQ(controller_interface::return_type::OK, switch_future.get()); + } + + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, test_controller->get_lifecycle_state().id()); + + EXPECT_EQ(test_controller->get_update_rate(), ctrl_update_rate); + const auto cm_update_rate = cm_->get_update_rate(); + const auto controller_update_rate = test_controller->get_update_rate(); + const double controller_period = 1.0 / controller_update_rate; + + const auto initial_counter = test_controller->internal_counter; + // don't start with zero to check if the period is correct if controller is activated anytime + rclcpp::Time time = time_; + const auto exp_periodicity = + cm_update_rate / std::ceil(static_cast(cm_update_rate) / controller_update_rate); + for (size_t update_counter = 0; update_counter <= 10 * cm_update_rate; ++update_counter) + { + rclcpp::Time old_time = time; + cm_->get_clock()->sleep_until(old_time + PERIOD); + time = cm_->get_clock()->now(); + EXPECT_EQ( + controller_interface::return_type::OK, + cm_->update(time, rclcpp::Duration::from_seconds(0.01))); + + // the async controllers will have to wait for one cycle to have the correct update period in + // the controller + if (test_controller->internal_counter - initial_counter > 1) + { + EXPECT_THAT( + test_controller->update_period_.seconds(), + testing::AllOf( + testing::Gt(0.99 * controller_period), + testing::Lt((1.05 * controller_period) + PERIOD.seconds()))) + << "update_counter: " << update_counter + << " desired controller period: " << controller_period + << " actual controller period: " << test_controller->update_period_.seconds(); + } + // else + // { + // // Check that the first cycle update period is zero + // EXPECT_EQ(test_controller->update_period_.seconds(), 0.0); + // } + + if (update_counter > 0 && update_counter % cm_update_rate == 0) + { + const double no_of_secs_passed = static_cast(update_counter) / cm_update_rate; + const auto actual_counter = test_controller->internal_counter - initial_counter; + const unsigned int exp_counter = + static_cast(exp_periodicity * no_of_secs_passed); + SCOPED_TRACE( + "The internal counter is : " + std::to_string(actual_counter) + " [" + + std::to_string(exp_counter - 1) + ", " + std::to_string(exp_counter + 1) + + "] and number of seconds passed : " + std::to_string(no_of_secs_passed)); + // NOTE: here EXPECT_THAT is used because it is observed that in the first iteration of whole + // cycle of cm_update_rate counts, there is one count missing, but in rest of the 9 cycles it + // is clearly tracking, so adding 1 here won't affect the final count. + // For instance, a controller with update rate 37 Hz, seems to have 36 in the first update + // cycle and then on accumulating 37 on every other update cycle so at the end of the 10 + // cycles it will have 369 instead of 370. + EXPECT_THAT( + actual_counter, testing::AnyOf(testing::Ge(exp_counter - 1), testing::Le(exp_counter + 1))); + EXPECT_THAT( + cm_->get_loaded_controllers()[0].execution_time_statistics->GetCount(), + testing::AnyOf(testing::Ge(exp_counter - 1), testing::Le(exp_counter))); + EXPECT_THAT( + cm_->get_loaded_controllers()[0].periodicity_statistics->GetCount(), + testing::AnyOf(testing::Ge(exp_counter - 1), testing::Le(exp_counter))); + EXPECT_THAT( + cm_->get_loaded_controllers()[0].periodicity_statistics->Average(), + testing::AllOf(testing::Ge(0.95 * exp_periodicity), testing::Lt((1.05 * exp_periodicity)))); + EXPECT_THAT( + cm_->get_loaded_controllers()[0].periodicity_statistics->Min(), + testing::AllOf(testing::Ge(0.85 * exp_periodicity), testing::Lt((1.2 * exp_periodicity)))); + EXPECT_THAT( + cm_->get_loaded_controllers()[0].periodicity_statistics->Max(), + testing::AllOf(testing::Ge(0.85 * exp_periodicity), testing::Lt((1.2 * exp_periodicity)))); + EXPECT_LT( + cm_->get_loaded_controllers()[0].execution_time_statistics->Average(), + 12000); // more or less 12 milliseconds considering the waittime in the controller + } + } +} + class TestControllerManagerFallbackControllers : public ControllerManagerFixture, public testing::WithParamInterface diff --git a/controller_manager/test/test_hardware_management_srvs.cpp b/controller_manager/test/test_hardware_management_srvs.cpp index c7b67e0cfe..bdd48f15ae 100644 --- a/controller_manager/test/test_hardware_management_srvs.cpp +++ b/controller_manager/test/test_hardware_management_srvs.cpp @@ -65,6 +65,7 @@ class TestControllerManagerHWManagementSrvs : public TestControllerManagerSrvs cm_ = std::make_shared(executor_, TEST_CM_NAME); run_updater_ = false; + SetUpSrvsCMExecutor(); cm_->set_parameter(rclcpp::Parameter( "hardware_components_initial_state.unconfigured", std::vector({TEST_SYSTEM_HARDWARE_NAME}))); @@ -72,11 +73,10 @@ class TestControllerManagerHWManagementSrvs : public TestControllerManagerSrvs "hardware_components_initial_state.inactive", std::vector({TEST_SENSOR_HARDWARE_NAME}))); + std::this_thread::sleep_for(std::chrono::milliseconds(100)); auto msg = std_msgs::msg::String(); msg.data = ros2_control_test_assets::minimal_robot_urdf; cm_->robot_description_callback(msg); - - SetUpSrvsCMExecutor(); } void check_component_fileds( From 3052b58bd089f9c0210cb3a2dd87bd12e9435b30 Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Wed, 4 Dec 2024 08:23:37 +0100 Subject: [PATCH 3/6] Fix the launch_utils regression (#1909) --- controller_manager/controller_manager/launch_utils.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/controller_manager/controller_manager/launch_utils.py b/controller_manager/controller_manager/launch_utils.py index e10096b675..9c8f5a9d24 100644 --- a/controller_manager/controller_manager/launch_utils.py +++ b/controller_manager/controller_manager/launch_utils.py @@ -145,6 +145,6 @@ def generate_load_controller_launch_description( controller_params_files = [controller_params_file] if controller_params_file else None return generate_controllers_spawner_launch_description( controller_names=[controller_name], - controller_params_file=controller_params_files, + controller_params_files=controller_params_files, extra_spawner_args=extra_spawner_args, ) From dbee650c461b85e7927286afea1ce8e8c36b3bfc Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Wed, 4 Dec 2024 08:24:17 +0100 Subject: [PATCH 4/6] Lock memory by default on a realtime system setup (#1896) --- controller_manager/doc/userdoc.rst | 2 +- controller_manager/src/ros2_control_node.cpp | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/controller_manager/doc/userdoc.rst b/controller_manager/doc/userdoc.rst index 872a695d0f..fb69753ee2 100644 --- a/controller_manager/doc/userdoc.rst +++ b/controller_manager/doc/userdoc.rst @@ -325,7 +325,7 @@ The controller_manager can be launched with the ros2_control_node executable. Th The ros2_control_node executable uses the following parameters from the ``controller_manager`` node: -lock_memory (optional; bool; default: false) +lock_memory (optional; bool; default: false for a non-realtime kernel, true for a realtime kernel) Locks the memory of the ``controller_manager`` node at startup to physical RAM in order to avoid page faults and to prevent the node from being swapped out to disk. Find more information about the setup for memory locking in the following link : `How to set ulimit values `_ diff --git a/controller_manager/src/ros2_control_node.cpp b/controller_manager/src/ros2_control_node.cpp index da79de76a3..af8d26d8b1 100644 --- a/controller_manager/src/ros2_control_node.cpp +++ b/controller_manager/src/ros2_control_node.cpp @@ -59,7 +59,8 @@ int main(int argc, char ** argv) const bool use_sim_time = cm->get_parameter_or("use_sim_time", false); - const bool lock_memory = cm->get_parameter_or("lock_memory", false); + const bool has_realtime = realtime_tools::has_realtime_kernel(); + const bool lock_memory = cm->get_parameter_or("lock_memory", has_realtime); std::string message; if (lock_memory && !realtime_tools::lock_memory(message)) { From 3d57fc81572558b2ce5962bd59de66e20a8213d5 Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Wed, 4 Dec 2024 13:02:40 +0100 Subject: [PATCH 5/6] [Feature] Choose different read and write rate for the hardware components (#1570) --- doc/release_notes.rst | 38 +++ .../doc/different_update_rates_userdoc.rst | 241 ++++++------------ .../include/hardware_interface/actuator.hpp | 13 + .../hardware_component_info.hpp | 4 + .../hardware_interface/hardware_info.hpp | 2 + .../include/hardware_interface/sensor.hpp | 8 + .../include/hardware_interface/system.hpp | 13 + hardware_interface/src/actuator.cpp | 29 +-- hardware_interface/src/component_parser.cpp | 38 +++ hardware_interface/src/resource_manager.cpp | 58 ++++- hardware_interface/src/sensor.cpp | 15 +- hardware_interface/src/system.cpp | 29 +-- .../test/test_component_interfaces.cpp | 93 ++++--- ...est_component_interfaces_custom_export.cpp | 23 +- .../test/test_component_parser.cpp | 30 +++ .../test/test_components/test_system.cpp | 6 + .../test/test_resource_manager.cpp | 227 ++++++++++++++++- .../ros2_control_test_assets/descriptions.hpp | 97 +++++++ 18 files changed, 721 insertions(+), 243 deletions(-) diff --git a/doc/release_notes.rst b/doc/release_notes.rst index b7c4b934c4..a20099a20a 100644 --- a/doc/release_notes.rst +++ b/doc/release_notes.rst @@ -113,6 +113,44 @@ hardware_interface * Soft limits are also parsed from the URDF into the ``HardwareInfo`` structure for the defined joints (`#1488 `_) * Access to logger and clock through ``get_logger`` and ``get_clock`` methods in ResourceManager and HardwareComponents ``Actuator``, ``Sensor`` and ``System`` (`#1585 `_) +* The ``ros2_control`` tag now supports parsing read/write rate ``rw_rate`` for the each hardware component parsed through the URDF (`#1570 `_) + + .. code:: xml + + + + ros2_control_demo_hardware/RRBotSystemPositionOnlyHardware + 2.0 + 3.0 + 2.0 + + + + + + + + + + + + + + ros2_control_demo_hardware/MultimodalGripper + + + + 0 + 100 + + + + + + + + + * Added ``get_hardware_info`` method to the hardware components interface to access the ``HardwareInfo`` instead of accessing the variable ``info_`` directly (`#1643 `_) * With (`#1683 `_) the ``rclcpp_lifecycle::State & get_state()`` and ``void set_state(const rclcpp_lifecycle::State & new_state)`` are replaced by ``rclcpp_lifecycle::State & get_lifecycle_state()`` and ``void set_lifecycle_state(const rclcpp_lifecycle::State & new_state)``. This change affects controllers and hardware. This is related to (`#1240 `_) as variant support introduces ``get_state`` and ``set_state`` methods for setting/getting state of handles. * With (`#1421 `_) a key-value storage is added to InterfaceInfo. This allows to define extra params with per Command-/StateInterface in the ``.ros2_control.xacro`` file. diff --git a/hardware_interface/doc/different_update_rates_userdoc.rst b/hardware_interface/doc/different_update_rates_userdoc.rst index 23f5e3564a..5a71587d44 100644 --- a/hardware_interface/doc/different_update_rates_userdoc.rst +++ b/hardware_interface/doc/different_update_rates_userdoc.rst @@ -5,165 +5,86 @@ Different update rates for Hardware Components =============================================================================== -In the following sections you can find some advice which will help you to implement Hardware -Components with update rates different from the main control loop. - -By counting loops -------------------------------------------------------------------------------- - -Current implementation of -`ros2_control main node `_ -has one update rate that controls the rate of the -`read(...) `_ -and `write(...) `_ -calls in `hardware_interface(s) `_. -To achieve different update rates for your hardware component you can use the following steps: - -.. _step-1: - -1. Add parameters of main control loop update rate and desired update rate for your hardware component - - .. code:: xml - - - - - - - - - my_system_interface/MySystemHardware - ${main_loop_update_rate} - ${desired_hw_update_rate} - - ... - - - - - - -.. _step-2: - -2. In you ``on_init()`` specific implementation fetch the desired parameters - - .. code:: cpp - - namespace my_system_interface - { - hardware_interface::CallbackReturn MySystemHardware::on_init( - const hardware_interface::HardwareInfo & info) - { - if ( - hardware_interface::SystemInterface::on_init(info) != - hardware_interface::CallbackReturn::SUCCESS) - { - return hardware_interface::CallbackReturn::ERROR; - } - - // declaration in *.hpp file --> unsigned int main_loop_update_rate_, desired_hw_update_rate_ = 100 ; - main_loop_update_rate_ = stoi(info_.hardware_parameters["main_loop_update_rate"]); - desired_hw_update_rate_ = stoi(info_.hardware_parameters["desired_hw_update_rate"]); - - ... - } - ... - } // my_system_interface - -3. In your ``on_activate`` specific implementation reset internal loop counter - - .. code:: cpp - - hardware_interface::CallbackReturn MySystemHardware::on_activate( - const rclcpp_lifecycle::State & /*previous_state*/) - { - // declaration in *.hpp file --> unsigned int update_loop_counter_ ; - update_loop_counter_ = 0; - ... - } - -4. In your ``read(const rclcpp::Time & time, const rclcpp::Duration & period)`` - and/or ``write(const rclcpp::Time & time, const rclcpp::Duration & period)`` - specific implementations decide if you should interfere with your hardware - - .. code:: cpp - - hardware_interface::return_type MySystemHardware::read(const rclcpp::Time & time, const rclcpp::Duration & period) - { - - bool hardware_go = main_loop_update_rate_ == 0 || - desired_hw_update_rate_ == 0 || - ((update_loop_counter_ % desired_hw_update_rate_) == 0); - - if (hardware_go){ - // hardware comms and operations - ... - } - ... - - // update counter - ++update_loop_counter_; - update_loop_counter_ %= main_loop_update_rate_; - } - -By measuring elapsed time -------------------------------------------------------------------------------- - -Another way to decide if hardware communication should be executed in the -``read(const rclcpp::Time & time, const rclcpp::Duration & period)`` and/or -``write(const rclcpp::Time & time, const rclcpp::Duration & period)`` -implementations is to measure elapsed time since last pass: - -1. In your ``on_activate`` specific implementation reset the flags that indicate - that this is the first pass of the ``read`` and ``write`` methods - - .. code:: cpp - - hardware_interface::CallbackReturn MySystemHardware::on_activate( - const rclcpp_lifecycle::State & /*previous_state*/) - { - // declaration in *.hpp file --> bool first_read_pass_, first_write_pass_ = true ; - first_read_pass_ = first_write_pass_ = true; - ... - } - -2. In your ``read(const rclcpp::Time & time, const rclcpp::Duration & period)`` - and/or ``write(const rclcpp::Time & time, const rclcpp::Duration & period)`` - specific implementations decide if you should interfere with your hardware - - .. code:: cpp - - hardware_interface::return_type MySystemHardware::read(const rclcpp::Time & time, const rclcpp::Duration & period) - { - if (first_read_pass_ || (time - last_read_time_ ) > desired_hw_update_period_) - { - first_read_pass_ = false; - // declaration in *.hpp file --> rclcpp::Time last_read_time_ ; - last_read_time_ = time; - // hardware comms and operations - ... - } - ... - } - - hardware_interface::return_type MySystemHardware::write(const rclcpp::Time & time, const rclcpp::Duration & period) - { - if (first_write_pass_ || (time - last_write_time_ ) > desired_hw_update_period_) - { - first_write_pass_ = false; - // declaration in *.hpp file --> rclcpp::Time last_write_time_ ; - last_write_time_ = time; - // hardware comms and operations - ... - } - ... - } +The ``ros2_control`` framework allows to run different hardware components at different update rates. This is useful when some of the hardware components needs to run at a different frequency than the traditional control loop frequency which is same as the one of the ``controller_manager``. It is very typical to have different components with different frequencies in a robotic system with different sensors or different components using different communication protocols. +This is useful when you have a hardware component that needs to run at a higher rate than the rest of the components. For example, you might have a sensor that needs to be read at 1000Hz, while the rest of the components can run at 500Hz, given that the control loop frequency of the ``controller_manager`` is higher than 1000Hz. The read/write rate can be defined easily by adding the parameter ``rw_rate`` to the ``ros2_control`` tag of the hardware component. + +Examples +***************************** +The following examples show how to use the different hardware interface types with different update frequencies in a ``ros2_control`` URDF. +They can be combined together within the different hardware component types (system, actuator, sensor) (:ref:`see detailed documentation `) as follows + +For a RRBot with Multimodal gripper and external sensor running at different rates: + +.. code-block:: xml + + + + ros2_control_demo_hardware/RRBotSystemPositionOnlyHardware + 2.0 + 3.0 + 2.0 + + + + -1 + 1 + + + + + + -1 + 1 + + + + + + + + + + + + + + + ros2_control_demo_hardware/MultimodalGripper + + + + 0 + 100 + + + + + + + + + + + ros2_control_demo_hardware/ForceTorqueSensor2DHardware + 0.43 + + + + + kuka_tcp + 100 + 100 + + + + + + + + + + +In the above example, the system hardware component that controls the joints of the RRBot is running at 500 Hz, the multimodal gripper is running at 200 Hz and the force torque sensor is running at 250 Hz. .. note:: - - The approach to get the desired update period value from the URDF and assign it to the variable - ``desired_hw_update_period_`` is the same as in the previous section (|step-1|_ and |step-2|_) but - with a different parameter name. - -.. |step-1| replace:: step 1 -.. |step-2| replace:: step 2 + In the above example, the ``rw_rate`` parameter is set to 500 Hz, 200 Hz and 250 Hz for the system, actuator and sensor hardware components respectively. This parameter is optional and if not set, the default value of 0 will be used which means that the hardware component will run at the same rate as the ``controller_manager``. However, if the specified rate is higher than the ``controller_manager`` rate, the hardware component will then run at the rate of the ``controller_manager``. diff --git a/hardware_interface/include/hardware_interface/actuator.hpp b/hardware_interface/include/hardware_interface/actuator.hpp index 3b16a65261..bfeb5d969d 100644 --- a/hardware_interface/include/hardware_interface/actuator.hpp +++ b/hardware_interface/include/hardware_interface/actuator.hpp @@ -95,15 +95,28 @@ class Actuator final HARDWARE_INTERFACE_PUBLIC const rclcpp_lifecycle::State & get_lifecycle_state() const; + HARDWARE_INTERFACE_PUBLIC + const rclcpp::Time & get_last_read_time() const; + + HARDWARE_INTERFACE_PUBLIC + const rclcpp::Time & get_last_write_time() const; + HARDWARE_INTERFACE_PUBLIC return_type read(const rclcpp::Time & time, const rclcpp::Duration & period); HARDWARE_INTERFACE_PUBLIC return_type write(const rclcpp::Time & time, const rclcpp::Duration & period); + HARDWARE_INTERFACE_PUBLIC + std::recursive_mutex & get_mutex(); + private: std::unique_ptr impl_; mutable std::recursive_mutex actuators_mutex_; + // Last read cycle time + rclcpp::Time last_read_cycle_time_; + // Last write cycle time + rclcpp::Time last_write_cycle_time_; }; } // namespace hardware_interface diff --git a/hardware_interface/include/hardware_interface/hardware_component_info.hpp b/hardware_interface/include/hardware_interface/hardware_component_info.hpp index 092ed21000..70a0482811 100644 --- a/hardware_interface/include/hardware_interface/hardware_component_info.hpp +++ b/hardware_interface/include/hardware_interface/hardware_component_info.hpp @@ -22,6 +22,7 @@ #include #include +#include #include "rclcpp_lifecycle/state.hpp" namespace hardware_interface @@ -47,6 +48,9 @@ struct HardwareComponentInfo /// Component is async bool is_async; + //// read/write rate + unsigned int rw_rate; + /// Component current state. rclcpp_lifecycle::State state; diff --git a/hardware_interface/include/hardware_interface/hardware_info.hpp b/hardware_interface/include/hardware_interface/hardware_info.hpp index eea8b6ca8a..f62329ee62 100644 --- a/hardware_interface/include/hardware_interface/hardware_info.hpp +++ b/hardware_interface/include/hardware_interface/hardware_info.hpp @@ -174,6 +174,8 @@ struct HardwareInfo std::string type; /// Hardware group to which the hardware belongs. std::string group; + /// Component's read and write rates in Hz. + unsigned int rw_rate; /// Component is async bool is_async; /// Name of the pluginlib plugin of the hardware that will be loaded. diff --git a/hardware_interface/include/hardware_interface/sensor.hpp b/hardware_interface/include/hardware_interface/sensor.hpp index ca570b78aa..ac7f3f6f6a 100644 --- a/hardware_interface/include/hardware_interface/sensor.hpp +++ b/hardware_interface/include/hardware_interface/sensor.hpp @@ -82,15 +82,23 @@ class Sensor final HARDWARE_INTERFACE_PUBLIC const rclcpp_lifecycle::State & get_lifecycle_state() const; + HARDWARE_INTERFACE_PUBLIC + const rclcpp::Time & get_last_read_time() const; + HARDWARE_INTERFACE_PUBLIC return_type read(const rclcpp::Time & time, const rclcpp::Duration & period); HARDWARE_INTERFACE_PUBLIC return_type write(const rclcpp::Time &, const rclcpp::Duration &) { return return_type::OK; } + HARDWARE_INTERFACE_PUBLIC + std::recursive_mutex & get_mutex(); + private: std::unique_ptr impl_; mutable std::recursive_mutex sensors_mutex_; + // Last read cycle time + rclcpp::Time last_read_cycle_time_; }; } // namespace hardware_interface diff --git a/hardware_interface/include/hardware_interface/system.hpp b/hardware_interface/include/hardware_interface/system.hpp index 09adaa7190..749e10d5e4 100644 --- a/hardware_interface/include/hardware_interface/system.hpp +++ b/hardware_interface/include/hardware_interface/system.hpp @@ -95,15 +95,28 @@ class System final HARDWARE_INTERFACE_PUBLIC const rclcpp_lifecycle::State & get_lifecycle_state() const; + HARDWARE_INTERFACE_PUBLIC + const rclcpp::Time & get_last_read_time() const; + + HARDWARE_INTERFACE_PUBLIC + const rclcpp::Time & get_last_write_time() const; + HARDWARE_INTERFACE_PUBLIC return_type read(const rclcpp::Time & time, const rclcpp::Duration & period); HARDWARE_INTERFACE_PUBLIC return_type write(const rclcpp::Time & time, const rclcpp::Duration & period); + HARDWARE_INTERFACE_PUBLIC + std::recursive_mutex & get_mutex(); + private: std::unique_ptr impl_; mutable std::recursive_mutex system_mutex_; + // Last read cycle time + rclcpp::Time last_read_cycle_time_; + // Last write cycle time + rclcpp::Time last_write_cycle_time_; }; } // namespace hardware_interface diff --git a/hardware_interface/src/actuator.cpp b/hardware_interface/src/actuator.cpp index b0ed1f7c80..0e4ae95ca9 100644 --- a/hardware_interface/src/actuator.cpp +++ b/hardware_interface/src/actuator.cpp @@ -41,6 +41,8 @@ Actuator::Actuator(Actuator && other) noexcept { std::lock_guard lock(other.actuators_mutex_); impl_ = std::move(other.impl_); + last_read_cycle_time_ = other.last_read_cycle_time_; + last_write_cycle_time_ = other.last_write_cycle_time_; } const rclcpp_lifecycle::State & Actuator::initialize( @@ -53,6 +55,8 @@ const rclcpp_lifecycle::State & Actuator::initialize( switch (impl_->init(actuator_info, logger, clock_interface)) { case CallbackReturn::SUCCESS: + last_read_cycle_time_ = clock_interface->get_clock()->now(); + last_write_cycle_time_ = clock_interface->get_clock()->now(); impl_->set_lifecycle_state(rclcpp_lifecycle::State( lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, lifecycle_state_names::UNCONFIGURED)); @@ -282,18 +286,15 @@ const rclcpp_lifecycle::State & Actuator::get_lifecycle_state() const return impl_->get_lifecycle_state(); } +const rclcpp::Time & Actuator::get_last_read_time() const { return last_read_cycle_time_; } + +const rclcpp::Time & Actuator::get_last_write_time() const { return last_write_cycle_time_; } + return_type Actuator::read(const rclcpp::Time & time, const rclcpp::Duration & period) { - std::unique_lock lock(actuators_mutex_, std::try_to_lock); - if (!lock.owns_lock()) - { - RCLCPP_DEBUG( - impl_->get_logger(), "Skipping read() call for actuator '%s' since it is locked", - impl_->get_name().c_str()); - return return_type::OK; - } if (lifecycleStateThatRequiresNoAction(impl_->get_lifecycle_state().id())) { + last_read_cycle_time_ = time; return return_type::OK; } return_type result = return_type::ERROR; @@ -306,22 +307,16 @@ return_type Actuator::read(const rclcpp::Time & time, const rclcpp::Duration & p { error(); } + last_read_cycle_time_ = time; } return result; } return_type Actuator::write(const rclcpp::Time & time, const rclcpp::Duration & period) { - std::unique_lock lock(actuators_mutex_, std::try_to_lock); - if (!lock.owns_lock()) - { - RCLCPP_DEBUG( - impl_->get_logger(), "Skipping write() call for actuator '%s' since it is locked", - impl_->get_name().c_str()); - return return_type::OK; - } if (lifecycleStateThatRequiresNoAction(impl_->get_lifecycle_state().id())) { + last_write_cycle_time_ = time; return return_type::OK; } return_type result = return_type::ERROR; @@ -334,8 +329,10 @@ return_type Actuator::write(const rclcpp::Time & time, const rclcpp::Duration & { error(); } + last_write_cycle_time_ = time; } return result; } +std::recursive_mutex & Actuator::get_mutex() { return actuators_mutex_; } } // namespace hardware_interface diff --git a/hardware_interface/src/component_parser.cpp b/hardware_interface/src/component_parser.cpp index 0f186531e9..f32db49dcb 100644 --- a/hardware_interface/src/component_parser.cpp +++ b/hardware_interface/src/component_parser.cpp @@ -58,6 +58,7 @@ constexpr const auto kTypeAttribute = "type"; constexpr const auto kRoleAttribute = "role"; constexpr const auto kReductionAttribute = "mechanical_reduction"; constexpr const auto kOffsetAttribute = "offset"; +constexpr const auto kReadWriteRateAttribute = "rw_rate"; constexpr const auto kIsAsyncAttribute = "is_async"; } // namespace @@ -222,6 +223,42 @@ std::string parse_data_type_attribute(const tinyxml2::XMLElement * elem) return data_type; } +/// Parse rw_rate attribute +/** + * Parses an XMLElement and returns the value of the rw_rate attribute. + * Defaults to 0 if not specified. + * + * \param[in] elem XMLElement that has the rw_rate attribute. + * \return unsigned int specifying the read/write rate. + */ +unsigned int parse_rw_rate_attribute(const tinyxml2::XMLElement * elem) +{ + const tinyxml2::XMLAttribute * attr = elem->FindAttribute(kReadWriteRateAttribute); + try + { + const auto rw_rate = attr ? std::stoi(attr->Value()) : 0; + if (rw_rate < 0) + { + throw std::runtime_error( + "Could not parse rw_rate tag in \"" + std::string(elem->Name()) + "\"." + "Got \"" + + std::to_string(rw_rate) + "\", but expected a positive integer."); + } + return static_cast(rw_rate); + } + catch (const std::invalid_argument & e) + { + throw std::runtime_error( + "Could not parse rw_rate tag in \"" + std::string(elem->Name()) + "\"." + + " Invalid value : \"" + attr->Value() + "\", expected a positive integer."); + } + catch (const std::out_of_range & e) + { + throw std::runtime_error( + "Could not parse rw_rate tag in \"" + std::string(elem->Name()) + "\"." + + " Out of range value : \"" + attr->Value() + "\", expected a positive valid integer."); + } +} + /// Parse is_async attribute /** * Parses an XMLElement and returns the value of the is_async attribute. @@ -575,6 +612,7 @@ HardwareInfo parse_resource_from_xml( HardwareInfo hardware; hardware.name = get_attribute_value(ros2_control_it, kNameAttribute, kROS2ControlTag); hardware.type = get_attribute_value(ros2_control_it, kTypeAttribute, kROS2ControlTag); + hardware.rw_rate = parse_rw_rate_attribute(ros2_control_it); hardware.is_async = parse_is_async_attribute(ros2_control_it); // Parse everything under ros2_control tag diff --git a/hardware_interface/src/resource_manager.cpp b/hardware_interface/src/resource_manager.cpp index e5445491c8..d338250e4f 100644 --- a/hardware_interface/src/resource_manager.cpp +++ b/hardware_interface/src/resource_manager.cpp @@ -142,6 +142,10 @@ class ResourceStorage component_info.name = hardware_info.name; component_info.type = hardware_info.type; component_info.group = hardware_info.group; + component_info.rw_rate = + (hardware_info.rw_rate == 0 || hardware_info.rw_rate > cm_update_rate_) + ? cm_update_rate_ + : hardware_info.rw_rate; component_info.plugin_name = hardware_info.hardware_plugin_name; component_info.is_async = hardware_info.is_async; @@ -1836,10 +1840,35 @@ HardwareReadWriteStatus ResourceManager::read( { for (auto & component : components) { + std::unique_lock lock(component.get_mutex(), std::try_to_lock); + if (!lock.owns_lock()) + { + RCLCPP_DEBUG( + get_logger(), "Skipping read() call for the component '%s' since it is locked", + component.get_name().c_str()); + continue; + } auto ret_val = return_type::OK; try { - ret_val = component.read(time, period); + if ( + resource_storage_->hardware_info_map_[component.get_name()].rw_rate == 0 || + resource_storage_->hardware_info_map_[component.get_name()].rw_rate == + resource_storage_->cm_update_rate_) + { + ret_val = component.read(time, period); + } + else + { + const double read_rate = + resource_storage_->hardware_info_map_[component.get_name()].rw_rate; + const auto current_time = resource_storage_->get_clock()->now(); + const rclcpp::Duration actual_period = current_time - component.get_last_read_time(); + if (actual_period.seconds() * read_rate >= 0.99) + { + ret_val = component.read(current_time, actual_period); + } + } const auto component_group = component.get_group_name(); ret_val = resource_storage_->update_hardware_component_group_state(component_group, ret_val); @@ -1897,10 +1926,35 @@ HardwareReadWriteStatus ResourceManager::write( { for (auto & component : components) { + std::unique_lock lock(component.get_mutex(), std::try_to_lock); + if (!lock.owns_lock()) + { + RCLCPP_DEBUG( + get_logger(), "Skipping write() call for the component '%s' since it is locked", + component.get_name().c_str()); + continue; + } auto ret_val = return_type::OK; try { - ret_val = component.write(time, period); + if ( + resource_storage_->hardware_info_map_[component.get_name()].rw_rate == 0 || + resource_storage_->hardware_info_map_[component.get_name()].rw_rate == + resource_storage_->cm_update_rate_) + { + ret_val = component.write(time, period); + } + else + { + const double write_rate = + resource_storage_->hardware_info_map_[component.get_name()].rw_rate; + const auto current_time = resource_storage_->get_clock()->now(); + const rclcpp::Duration actual_period = current_time - component.get_last_write_time(); + if (actual_period.seconds() * write_rate >= 0.99) + { + ret_val = component.write(current_time, actual_period); + } + } const auto component_group = component.get_group_name(); ret_val = resource_storage_->update_hardware_component_group_state(component_group, ret_val); diff --git a/hardware_interface/src/sensor.cpp b/hardware_interface/src/sensor.cpp index 5da01368c9..ff193ff8e1 100644 --- a/hardware_interface/src/sensor.cpp +++ b/hardware_interface/src/sensor.cpp @@ -40,6 +40,7 @@ Sensor::Sensor(Sensor && other) noexcept { std::lock_guard lock(other.sensors_mutex_); impl_ = std::move(other.impl_); + last_read_cycle_time_ = other.last_read_cycle_time_; } const rclcpp_lifecycle::State & Sensor::initialize( @@ -52,6 +53,7 @@ const rclcpp_lifecycle::State & Sensor::initialize( switch (impl_->init(sensor_info, logger, clock_interface)) { case CallbackReturn::SUCCESS: + last_read_cycle_time_ = clock_interface->get_clock()->now(); impl_->set_lifecycle_state(rclcpp_lifecycle::State( lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, lifecycle_state_names::UNCONFIGURED)); @@ -240,18 +242,13 @@ const rclcpp_lifecycle::State & Sensor::get_lifecycle_state() const return impl_->get_lifecycle_state(); } +const rclcpp::Time & Sensor::get_last_read_time() const { return last_read_cycle_time_; } + return_type Sensor::read(const rclcpp::Time & time, const rclcpp::Duration & period) { - std::unique_lock lock(sensors_mutex_, std::try_to_lock); - if (!lock.owns_lock()) - { - RCLCPP_DEBUG( - impl_->get_logger(), "Skipping read() call for the sensor '%s' since it is locked", - impl_->get_name().c_str()); - return return_type::OK; - } if (lifecycleStateThatRequiresNoAction(impl_->get_lifecycle_state().id())) { + last_read_cycle_time_ = time; return return_type::OK; } return_type result = return_type::ERROR; @@ -264,8 +261,10 @@ return_type Sensor::read(const rclcpp::Time & time, const rclcpp::Duration & per { error(); } + last_read_cycle_time_ = time; } return result; } +std::recursive_mutex & Sensor::get_mutex() { return sensors_mutex_; } } // namespace hardware_interface diff --git a/hardware_interface/src/system.cpp b/hardware_interface/src/system.cpp index abae924dfc..9a27aa4f68 100644 --- a/hardware_interface/src/system.cpp +++ b/hardware_interface/src/system.cpp @@ -39,6 +39,8 @@ System::System(System && other) noexcept { std::lock_guard lock(other.system_mutex_); impl_ = std::move(other.impl_); + last_read_cycle_time_ = other.last_read_cycle_time_; + last_write_cycle_time_ = other.last_write_cycle_time_; } const rclcpp_lifecycle::State & System::initialize( @@ -51,6 +53,8 @@ const rclcpp_lifecycle::State & System::initialize( switch (impl_->init(system_info, logger, clock_interface)) { case CallbackReturn::SUCCESS: + last_read_cycle_time_ = clock_interface->get_clock()->now(); + last_write_cycle_time_ = clock_interface->get_clock()->now(); impl_->set_lifecycle_state(rclcpp_lifecycle::State( lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, lifecycle_state_names::UNCONFIGURED)); @@ -280,18 +284,15 @@ const rclcpp_lifecycle::State & System::get_lifecycle_state() const return impl_->get_lifecycle_state(); } +const rclcpp::Time & System::get_last_read_time() const { return last_read_cycle_time_; } + +const rclcpp::Time & System::get_last_write_time() const { return last_write_cycle_time_; } + return_type System::read(const rclcpp::Time & time, const rclcpp::Duration & period) { - std::unique_lock lock(system_mutex_, std::try_to_lock); - if (!lock.owns_lock()) - { - RCLCPP_DEBUG( - impl_->get_logger(), "Skipping read() call for system '%s' since it is locked", - impl_->get_name().c_str()); - return return_type::OK; - } if (lifecycleStateThatRequiresNoAction(impl_->get_lifecycle_state().id())) { + last_read_cycle_time_ = time; return return_type::OK; } return_type result = return_type::ERROR; @@ -304,22 +305,16 @@ return_type System::read(const rclcpp::Time & time, const rclcpp::Duration & per { error(); } + last_read_cycle_time_ = time; } return result; } return_type System::write(const rclcpp::Time & time, const rclcpp::Duration & period) { - std::unique_lock lock(system_mutex_, std::try_to_lock); - if (!lock.owns_lock()) - { - RCLCPP_DEBUG( - impl_->get_logger(), "Skipping write() call for system '%s' since it is locked", - impl_->get_name().c_str()); - return return_type::OK; - } if (lifecycleStateThatRequiresNoAction(impl_->get_lifecycle_state().id())) { + last_write_cycle_time_ = time; return return_type::OK; } return_type result = return_type::ERROR; @@ -332,8 +327,10 @@ return_type System::write(const rclcpp::Time & time, const rclcpp::Duration & pe { error(); } + last_write_cycle_time_ = time; } return result; } +std::recursive_mutex & System::get_mutex() { return system_mutex_; } } // namespace hardware_interface diff --git a/hardware_interface/test/test_component_interfaces.cpp b/hardware_interface/test/test_component_interfaces.cpp index 9b90d81dfd..df2147bd1a 100644 --- a/hardware_interface/test/test_component_interfaces.cpp +++ b/hardware_interface/test/test_component_interfaces.cpp @@ -33,6 +33,7 @@ #include "hardware_interface/types/hardware_interface_type_values.hpp" #include "hardware_interface/types/lifecycle_state_names.hpp" #include "lifecycle_msgs/msg/state.hpp" +#include "rclcpp/node.hpp" #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" #include "ros2_control_test_assets/components_urdfs.hpp" #include "ros2_control_test_assets/descriptions.hpp" @@ -683,8 +684,9 @@ TEST(TestComponentInterfaces, dummy_actuator) hardware_interface::Actuator actuator_hw(std::make_unique()); hardware_interface::HardwareInfo mock_hw_info{}; - rclcpp::Logger logger = rclcpp::get_logger("test_actuator_components"); - auto state = actuator_hw.initialize(mock_hw_info, logger, nullptr); + rclcpp::Node::SharedPtr node = std::make_shared("test_actuator_components"); + auto state = + actuator_hw.initialize(mock_hw_info, node->get_logger(), node->get_node_clock_interface()); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -781,8 +783,9 @@ TEST(TestComponentInterfaces, dummy_actuator_default) const std::vector control_resources = hardware_interface::parse_control_resources_from_urdf(urdf_to_test); const hardware_interface::HardwareInfo dummy_actuator = control_resources[0]; - rclcpp::Logger logger = rclcpp::get_logger("test_actuator_component"); - auto state = actuator_hw.initialize(dummy_actuator, logger, nullptr); + rclcpp::Node::SharedPtr node = std::make_shared("test_system_components"); + auto state = + actuator_hw.initialize(dummy_actuator, node->get_logger(), node->get_node_clock_interface()); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -896,8 +899,9 @@ TEST(TestComponentInterfaces, dummy_sensor) hardware_interface::Sensor sensor_hw(std::make_unique()); hardware_interface::HardwareInfo mock_hw_info{}; - rclcpp::Logger logger = rclcpp::get_logger("test_sensor_components"); - auto state = sensor_hw.initialize(mock_hw_info, logger, nullptr); + rclcpp::Node::SharedPtr node = std::make_shared("test_sensor_components"); + auto state = + sensor_hw.initialize(mock_hw_info, node->get_logger(), node->get_node_clock_interface()); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -935,8 +939,9 @@ TEST(TestComponentInterfaces, dummy_sensor_default) const std::vector control_resources = hardware_interface::parse_control_resources_from_urdf(urdf_to_test); const hardware_interface::HardwareInfo voltage_sensor_res = control_resources[0]; - rclcpp::Logger logger = rclcpp::get_logger("test_sensor_component"); - auto state = sensor_hw.initialize(voltage_sensor_res, logger, nullptr); + rclcpp::Node::SharedPtr node = std::make_shared("test_system_components"); + auto state = + sensor_hw.initialize(voltage_sensor_res, node->get_logger(), node->get_node_clock_interface()); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -974,8 +979,9 @@ TEST(TestComponentInterfaces, dummy_system) hardware_interface::System system_hw(std::make_unique()); hardware_interface::HardwareInfo mock_hw_info{}; - rclcpp::Logger logger = rclcpp::get_logger("test_system_components"); - auto state = system_hw.initialize(mock_hw_info, logger, nullptr); + rclcpp::Node::SharedPtr node = std::make_shared("test_system_components"); + auto state = + system_hw.initialize(mock_hw_info, node->get_logger(), node->get_node_clock_interface()); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -1106,8 +1112,9 @@ TEST(TestComponentInterfaces, dummy_system_default) const std::vector control_resources = hardware_interface::parse_control_resources_from_urdf(urdf_to_test); const hardware_interface::HardwareInfo dummy_system = control_resources[0]; - rclcpp::Logger logger = rclcpp::get_logger("test_system_component"); - auto state = system_hw.initialize(dummy_system, logger, nullptr); + rclcpp::Node::SharedPtr node = std::make_shared("test_system_components"); + auto state = + system_hw.initialize(dummy_system, node->get_logger(), node->get_node_clock_interface()); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -1300,8 +1307,9 @@ TEST(TestComponentInterfaces, dummy_command_mode_system) hardware_interface::System system_hw( std::make_unique()); hardware_interface::HardwareInfo mock_hw_info{}; - rclcpp::Logger logger = rclcpp::get_logger("test_system_components"); - auto state = system_hw.initialize(mock_hw_info, logger, nullptr); + rclcpp::Node::SharedPtr node = std::make_shared("test_system_components"); + auto state = + system_hw.initialize(mock_hw_info, node->get_logger(), node->get_node_clock_interface()); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -1333,8 +1341,9 @@ TEST(TestComponentInterfaces, dummy_actuator_read_error_behavior) hardware_interface::Actuator actuator_hw(std::make_unique()); hardware_interface::HardwareInfo mock_hw_info{}; - rclcpp::Logger logger = rclcpp::get_logger("test_actuator_components"); - auto state = actuator_hw.initialize(mock_hw_info, logger, nullptr); + rclcpp::Node::SharedPtr node = std::make_shared("test_actuator_components"); + auto state = + actuator_hw.initialize(mock_hw_info, node->get_logger(), node->get_node_clock_interface()); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -1401,8 +1410,9 @@ TEST(TestComponentInterfaces, dummy_actuator_default_read_error_behavior) const std::vector control_resources = hardware_interface::parse_control_resources_from_urdf(urdf_to_test); const hardware_interface::HardwareInfo dummy_actuator = control_resources[0]; - rclcpp::Logger logger = rclcpp::get_logger("test_actuator_component"); - auto state = actuator_hw.initialize(dummy_actuator, logger, nullptr); + rclcpp::Node::SharedPtr node = std::make_shared("test_system_components"); + auto state = + actuator_hw.initialize(dummy_actuator, node->get_logger(), node->get_node_clock_interface()); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -1466,8 +1476,9 @@ TEST(TestComponentInterfaces, dummy_actuator_write_error_behavior) hardware_interface::Actuator actuator_hw(std::make_unique()); hardware_interface::HardwareInfo mock_hw_info{}; - rclcpp::Logger logger = rclcpp::get_logger("test_actuator_components"); - auto state = actuator_hw.initialize(mock_hw_info, logger, nullptr); + rclcpp::Node::SharedPtr node = std::make_shared("test_actuator_components"); + auto state = + actuator_hw.initialize(mock_hw_info, node->get_logger(), node->get_node_clock_interface()); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -1534,8 +1545,9 @@ TEST(TestComponentInterfaces, dummy_actuator_default_write_error_behavior) const std::vector control_resources = hardware_interface::parse_control_resources_from_urdf(urdf_to_test); const hardware_interface::HardwareInfo dummy_actuator = control_resources[0]; - rclcpp::Logger logger = rclcpp::get_logger("test_actuator_component"); - auto state = actuator_hw.initialize(dummy_actuator, logger, nullptr); + rclcpp::Node::SharedPtr node = std::make_shared("test_system_components"); + auto state = + actuator_hw.initialize(dummy_actuator, node->get_logger(), node->get_node_clock_interface()); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -1598,8 +1610,9 @@ TEST(TestComponentInterfaces, dummy_sensor_read_error_behavior) hardware_interface::Sensor sensor_hw(std::make_unique()); hardware_interface::HardwareInfo mock_hw_info{}; - rclcpp::Logger logger = rclcpp::get_logger("test_sensor_components"); - auto state = sensor_hw.initialize(mock_hw_info, logger, nullptr); + rclcpp::Node::SharedPtr node = std::make_shared("test_sensor_components"); + auto state = + sensor_hw.initialize(mock_hw_info, node->get_logger(), node->get_node_clock_interface()); auto state_interfaces = sensor_hw.export_state_interfaces(); // Updated because is is INACTIVE @@ -1670,8 +1683,9 @@ TEST(TestComponentInterfaces, dummy_sensor_default_read_error_behavior) const std::vector control_resources = hardware_interface::parse_control_resources_from_urdf(urdf_to_test); const hardware_interface::HardwareInfo voltage_sensor_res = control_resources[0]; - rclcpp::Logger logger = rclcpp::get_logger("test_sensor_component"); - auto state = sensor_hw.initialize(voltage_sensor_res, logger, nullptr); + rclcpp::Node::SharedPtr node = std::make_shared("test_system_components"); + auto state = + sensor_hw.initialize(voltage_sensor_res, node->get_logger(), node->get_node_clock_interface()); auto state_interfaces = sensor_hw.export_state_interfaces(); // Updated because is is INACTIVE @@ -1725,8 +1739,9 @@ TEST(TestComponentInterfaces, dummy_system_read_error_behavior) hardware_interface::System system_hw(std::make_unique()); hardware_interface::HardwareInfo mock_hw_info{}; - rclcpp::Logger logger = rclcpp::get_logger("test_system_components"); - auto state = system_hw.initialize(mock_hw_info, logger, nullptr); + rclcpp::Node::SharedPtr node = std::make_shared("test_system_components"); + auto state = + system_hw.initialize(mock_hw_info, node->get_logger(), node->get_node_clock_interface()); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -1797,8 +1812,9 @@ TEST(TestComponentInterfaces, dummy_system_default_read_error_behavior) const std::vector control_resources = hardware_interface::parse_control_resources_from_urdf(urdf_to_test); const hardware_interface::HardwareInfo dummy_system = control_resources[0]; - rclcpp::Logger logger = rclcpp::get_logger("test_system_component"); - auto state = system_hw.initialize(dummy_system, logger, nullptr); + rclcpp::Node::SharedPtr node = std::make_shared("test_system_components"); + auto state = + system_hw.initialize(dummy_system, node->get_logger(), node->get_node_clock_interface()); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -1863,8 +1879,9 @@ TEST(TestComponentInterfaces, dummy_system_write_error_behavior) hardware_interface::System system_hw(std::make_unique()); hardware_interface::HardwareInfo mock_hw_info{}; - rclcpp::Logger logger = rclcpp::get_logger("test_system_components"); - auto state = system_hw.initialize(mock_hw_info, logger, nullptr); + rclcpp::Node::SharedPtr node = std::make_shared("test_system_components"); + auto state = + system_hw.initialize(mock_hw_info, node->get_logger(), node->get_node_clock_interface()); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -1935,8 +1952,9 @@ TEST(TestComponentInterfaces, dummy_system_default_write_error_behavior) const std::vector control_resources = hardware_interface::parse_control_resources_from_urdf(urdf_to_test); const hardware_interface::HardwareInfo dummy_system = control_resources[0]; - rclcpp::Logger logger = rclcpp::get_logger("test_system_component"); - auto state = system_hw.initialize(dummy_system, logger, nullptr); + rclcpp::Node::SharedPtr node = std::make_shared("test_system_components"); + auto state = + system_hw.initialize(dummy_system, node->get_logger(), node->get_node_clock_interface()); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -1994,3 +2012,10 @@ TEST(TestComponentInterfaces, dummy_system_default_write_error_behavior) EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::FINALIZED, state.label()); } + +int main(int argc, char ** argv) +{ + rclcpp::init(argc, argv); + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/hardware_interface/test/test_component_interfaces_custom_export.cpp b/hardware_interface/test/test_component_interfaces_custom_export.cpp index ab6f490b92..b64ea81bc8 100644 --- a/hardware_interface/test/test_component_interfaces_custom_export.cpp +++ b/hardware_interface/test/test_component_interfaces_custom_export.cpp @@ -33,6 +33,7 @@ #include "hardware_interface/types/hardware_interface_type_values.hpp" #include "hardware_interface/types/lifecycle_state_names.hpp" #include "lifecycle_msgs/msg/state.hpp" +#include "rclcpp/node.hpp" #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" #include "ros2_control_test_assets/components_urdfs.hpp" #include "ros2_control_test_assets/descriptions.hpp" @@ -169,8 +170,9 @@ TEST(TestComponentInterfaces, dummy_actuator_default_custom_export) const std::vector control_resources = hardware_interface::parse_control_resources_from_urdf(urdf_to_test); const hardware_interface::HardwareInfo dummy_actuator = control_resources[0]; - rclcpp::Logger logger = rclcpp::get_logger("test_actuator_component"); - auto state = actuator_hw.initialize(dummy_actuator, logger, nullptr); + rclcpp::Node::SharedPtr node = std::make_shared("test_actuator_component"); + auto state = + actuator_hw.initialize(dummy_actuator, node->get_logger(), node->get_node_clock_interface()); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -234,8 +236,9 @@ TEST(TestComponentInterfaces, dummy_sensor_default_custom_export) const std::vector control_resources = hardware_interface::parse_control_resources_from_urdf(urdf_to_test); const hardware_interface::HardwareInfo voltage_sensor_res = control_resources[0]; - rclcpp::Logger logger = rclcpp::get_logger("test_sensor_component"); - auto state = sensor_hw.initialize(voltage_sensor_res, logger, nullptr); + rclcpp::Node::SharedPtr node = std::make_shared("test_sensor_component"); + auto state = + sensor_hw.initialize(voltage_sensor_res, node->get_logger(), node->get_node_clock_interface()); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -271,8 +274,9 @@ TEST(TestComponentInterfaces, dummy_system_default_custom_export) const std::vector control_resources = hardware_interface::parse_control_resources_from_urdf(urdf_to_test); const hardware_interface::HardwareInfo dummy_system = control_resources[0]; - rclcpp::Logger logger = rclcpp::get_logger("test_system_component"); - auto state = system_hw.initialize(dummy_system, logger, nullptr); + rclcpp::Node::SharedPtr node = std::make_shared("test_system_component"); + auto state = + system_hw.initialize(dummy_system, node->get_logger(), node->get_node_clock_interface()); EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id()); EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label()); @@ -373,3 +377,10 @@ TEST(TestComponentInterfaces, dummy_system_default_custom_export) EXPECT_EQ("joint1", command_interfaces[position]->get_prefix_name()); } } + +int main(int argc, char ** argv) +{ + rclcpp::init(argc, argv); + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/hardware_interface/test/test_component_parser.cpp b/hardware_interface/test/test_component_parser.cpp index 3c24b0cc2a..8c535f04a9 100644 --- a/hardware_interface/test/test_component_parser.cpp +++ b/hardware_interface/test/test_component_parser.cpp @@ -1443,6 +1443,36 @@ TEST_F(TestComponentParser, gripper_no_mimic_valid_config) EXPECT_EQ(hw_info[0].mimic_joints[0].joint_index, 1); } +TEST_F(TestComponentParser, negative_rw_rates_throws_error) +{ + const auto urdf_to_test = + std::string(ros2_control_test_assets::gripper_urdf_head) + + std::string(ros2_control_test_assets::hardware_resources_with_negative_rw_rates) + + std::string(ros2_control_test_assets::urdf_tail); + std::vector hw_info; + ASSERT_THROW(parse_control_resources_from_urdf(urdf_to_test), std::runtime_error); +} + +TEST_F(TestComponentParser, invalid_rw_rates_throws_error) +{ + const auto urdf_to_test = + std::string(ros2_control_test_assets::gripper_urdf_head) + + std::string(ros2_control_test_assets::hardware_resources_invalid_with_text_in_rw_rates) + + std::string(ros2_control_test_assets::urdf_tail); + std::vector hw_info; + ASSERT_THROW(parse_control_resources_from_urdf(urdf_to_test), std::runtime_error); +} + +TEST_F(TestComponentParser, invalid_rw_rates_out_of_range) +{ + const auto urdf_to_test = + std::string(ros2_control_test_assets::gripper_urdf_head) + + std::string(ros2_control_test_assets::hardware_resources_invalid_out_of_range_in_rw_rates) + + std::string(ros2_control_test_assets::urdf_tail); + std::vector hw_info; + ASSERT_THROW(parse_control_resources_from_urdf(urdf_to_test), std::runtime_error); +} + TEST_F(TestComponentParser, gripper_mimic_with_unknown_joint_throws_error) { const auto urdf_to_test = diff --git a/hardware_interface_testing/test/test_components/test_system.cpp b/hardware_interface_testing/test/test_components/test_system.cpp index e30b74488e..795787eb9e 100644 --- a/hardware_interface_testing/test/test_components/test_system.cpp +++ b/hardware_interface_testing/test/test_components/test_system.cpp @@ -104,6 +104,12 @@ class TestSystem : public SystemInterface { return return_type::DEACTIVATE; } + // The next line is for the testing purposes. We need value to be changed to + // be sure that the feedback from hardware to controllers in the chain is + // working as it should. This makes value checks clearer and confirms there + // is no "state = command" line or some other mixture of interfaces + // somewhere in the test stack. + velocity_state_[0] = velocity_command_[0] / 2.0; return return_type::OK; } diff --git a/hardware_interface_testing/test/test_resource_manager.cpp b/hardware_interface_testing/test/test_resource_manager.cpp index e72a4a8214..5f7640546a 100644 --- a/hardware_interface_testing/test/test_resource_manager.cpp +++ b/hardware_interface_testing/test/test_resource_manager.cpp @@ -444,7 +444,8 @@ TEST_F(ResourceManagerTest, default_prepare_perform_switch) TEST_F(ResourceManagerTest, resource_status) { - TestableResourceManager rm(node_, ros2_control_test_assets::minimal_robot_urdf); + TestableResourceManager rm( + node_, ros2_control_test_assets::minimal_robot_urdf_with_different_hw_rw_rate); auto status_map = rm.get_components_status(); @@ -456,6 +457,10 @@ TEST_F(ResourceManagerTest, resource_status) EXPECT_EQ(status_map[TEST_ACTUATOR_HARDWARE_NAME].type, TEST_ACTUATOR_HARDWARE_TYPE); EXPECT_EQ(status_map[TEST_SENSOR_HARDWARE_NAME].type, TEST_SENSOR_HARDWARE_TYPE); EXPECT_EQ(status_map[TEST_SYSTEM_HARDWARE_NAME].type, TEST_SYSTEM_HARDWARE_TYPE); + // read/write_rate + EXPECT_EQ(status_map[TEST_ACTUATOR_HARDWARE_NAME].rw_rate, 50u); + EXPECT_EQ(status_map[TEST_SENSOR_HARDWARE_NAME].rw_rate, 20u); + EXPECT_EQ(status_map[TEST_SYSTEM_HARDWARE_NAME].rw_rate, 25u); // plugin_name EXPECT_EQ( status_map[TEST_ACTUATOR_HARDWARE_NAME].plugin_name, TEST_ACTUATOR_HARDWARE_PLUGIN_NAME); @@ -1733,6 +1738,226 @@ TEST_F(ResourceManagerTest, test_caching_of_controllers_to_hardware) } } +class ResourceManagerTestReadWriteDifferentReadWriteRate : public ResourceManagerTest +{ +public: + void setup_resource_manager_and_do_initial_checks() + { + rm = std::make_shared( + node_, ros2_control_test_assets::minimal_robot_urdf_with_different_hw_rw_rate, false); + activate_components(*rm); + + cm_update_rate_ = 100u; // The default value inside + time = node_.get_clock()->now(); + + auto status_map = rm->get_components_status(); + EXPECT_EQ( + status_map[TEST_ACTUATOR_HARDWARE_NAME].state.id(), + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE); + EXPECT_EQ( + status_map[TEST_SYSTEM_HARDWARE_NAME].state.id(), + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE); + EXPECT_EQ( + status_map[TEST_SENSOR_HARDWARE_NAME].state.id(), + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE); + + // read/write_rate + EXPECT_EQ(status_map[TEST_ACTUATOR_HARDWARE_NAME].rw_rate, 50u); + EXPECT_EQ(status_map[TEST_SENSOR_HARDWARE_NAME].rw_rate, 20u); + EXPECT_EQ(status_map[TEST_SYSTEM_HARDWARE_NAME].rw_rate, 25u); + + actuator_rw_rate_ = status_map[TEST_ACTUATOR_HARDWARE_NAME].rw_rate; + system_rw_rate_ = status_map[TEST_SYSTEM_HARDWARE_NAME].rw_rate; + + claimed_itfs.push_back( + rm->claim_command_interface(TEST_ACTUATOR_HARDWARE_COMMAND_INTERFACES[0])); + claimed_itfs.push_back(rm->claim_command_interface(TEST_SYSTEM_HARDWARE_COMMAND_INTERFACES[0])); + + state_itfs.push_back(rm->claim_state_interface(TEST_ACTUATOR_HARDWARE_STATE_INTERFACES[1])); + state_itfs.push_back(rm->claim_state_interface(TEST_SYSTEM_HARDWARE_STATE_INTERFACES[1])); + + check_if_interface_available(true, true); + // with default values read and write should run without any problems + { + auto [ok, failed_hardware_names] = rm->read(time, duration); + EXPECT_TRUE(ok); + EXPECT_TRUE(failed_hardware_names.empty()); + } + { + claimed_itfs[0].set_value(10.0); + claimed_itfs[1].set_value(20.0); + auto [ok, failed_hardware_names] = rm->write(time, duration); + EXPECT_TRUE(ok); + EXPECT_TRUE(failed_hardware_names.empty()); + } + + time = time + duration; + check_if_interface_available(true, true); + } + + // check if all interfaces are available + void check_if_interface_available(const bool actuator_interfaces, const bool system_interfaces) + { + for (const auto & interface : TEST_ACTUATOR_HARDWARE_COMMAND_INTERFACES) + { + EXPECT_EQ(rm->command_interface_is_available(interface), actuator_interfaces); + } + for (const auto & interface : TEST_ACTUATOR_HARDWARE_STATE_INTERFACES) + { + EXPECT_EQ(rm->state_interface_is_available(interface), actuator_interfaces); + } + for (const auto & interface : TEST_SYSTEM_HARDWARE_COMMAND_INTERFACES) + { + EXPECT_EQ(rm->command_interface_is_available(interface), system_interfaces); + } + for (const auto & interface : TEST_SYSTEM_HARDWARE_STATE_INTERFACES) + { + EXPECT_EQ(rm->state_interface_is_available(interface), system_interfaces); + } + }; + + using FunctionT = + std::function; + + void check_read_and_write_cycles(bool test_for_changing_values) + { + double prev_act_state_value = state_itfs[0].get_value(); + double prev_system_state_value = state_itfs[1].get_value(); + + for (size_t i = 1; i < 100; i++) + { + auto [ok, failed_hardware_names] = rm->read(time, duration); + EXPECT_TRUE(ok); + EXPECT_TRUE(failed_hardware_names.empty()); + if (i % (cm_update_rate_ / system_rw_rate_) == 0 && test_for_changing_values) + { + // The values are computations exactly within the test_components + prev_system_state_value = claimed_itfs[1].get_value() / 2.0; + claimed_itfs[1].set_value(claimed_itfs[1].get_value() + 20.0); + } + if (i % (cm_update_rate_ / actuator_rw_rate_) == 0 && test_for_changing_values) + { + // The values are computations exactly within the test_components + prev_act_state_value = claimed_itfs[0].get_value() / 2.0; + claimed_itfs[0].set_value(claimed_itfs[0].get_value() + 10.0); + } + // Even though we skip some read and write iterations, the state interfaces should be the same + // as previous updated one until the next cycle + ASSERT_EQ(state_itfs[0].get_value(), prev_act_state_value); + ASSERT_EQ(state_itfs[1].get_value(), prev_system_state_value); + auto [ok_write, failed_hardware_names_write] = rm->write(time, duration); + EXPECT_TRUE(ok_write); + EXPECT_TRUE(failed_hardware_names_write.empty()); + node_.get_clock()->sleep_until(time + duration); + time = node_.get_clock()->now(); + } + } + +public: + std::shared_ptr rm; + unsigned int actuator_rw_rate_, system_rw_rate_, cm_update_rate_; + std::vector claimed_itfs; + std::vector state_itfs; + + rclcpp::Time time = rclcpp::Time(1657232, 0); + const rclcpp::Duration duration = rclcpp::Duration::from_seconds(0.01); + + // values to set to hardware to simulate failure on read and write +}; + +TEST_F( + ResourceManagerTestReadWriteDifferentReadWriteRate, + test_components_with_different_read_write_freq_on_activate) +{ + setup_resource_manager_and_do_initial_checks(); + + check_read_and_write_cycles(true); +} + +TEST_F( + ResourceManagerTestReadWriteDifferentReadWriteRate, + test_components_with_different_read_write_freq_on_deactivate) +{ + setup_resource_manager_and_do_initial_checks(); + + // Now deactivate all the components and test the same as above + rclcpp_lifecycle::State state_inactive( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, + hardware_interface::lifecycle_state_names::INACTIVE); + rm->set_component_state(TEST_SYSTEM_HARDWARE_NAME, state_inactive); + rm->set_component_state(TEST_ACTUATOR_HARDWARE_NAME, state_inactive); + rm->set_component_state(TEST_SENSOR_HARDWARE_NAME, state_inactive); + + auto status_map = rm->get_components_status(); + EXPECT_EQ( + status_map[TEST_ACTUATOR_HARDWARE_NAME].state.id(), + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE); + EXPECT_EQ( + status_map[TEST_SYSTEM_HARDWARE_NAME].state.id(), + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE); + EXPECT_EQ( + status_map[TEST_SENSOR_HARDWARE_NAME].state.id(), + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE); + + check_read_and_write_cycles(true); +} + +TEST_F( + ResourceManagerTestReadWriteDifferentReadWriteRate, + test_components_with_different_read_write_freq_on_unconfigured) +{ + setup_resource_manager_and_do_initial_checks(); + + // Now deactivate all the components and test the same as above + rclcpp_lifecycle::State state_unconfigured( + lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, + hardware_interface::lifecycle_state_names::UNCONFIGURED); + rm->set_component_state(TEST_SYSTEM_HARDWARE_NAME, state_unconfigured); + rm->set_component_state(TEST_ACTUATOR_HARDWARE_NAME, state_unconfigured); + rm->set_component_state(TEST_SENSOR_HARDWARE_NAME, state_unconfigured); + + auto status_map = rm->get_components_status(); + EXPECT_EQ( + status_map[TEST_ACTUATOR_HARDWARE_NAME].state.id(), + lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED); + EXPECT_EQ( + status_map[TEST_SYSTEM_HARDWARE_NAME].state.id(), + lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED); + EXPECT_EQ( + status_map[TEST_SENSOR_HARDWARE_NAME].state.id(), + lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED); + + check_read_and_write_cycles(false); +} + +TEST_F( + ResourceManagerTestReadWriteDifferentReadWriteRate, + test_components_with_different_read_write_freq_on_finalized) +{ + setup_resource_manager_and_do_initial_checks(); + + // Now deactivate all the components and test the same as above + rclcpp_lifecycle::State state_finalized( + lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED, + hardware_interface::lifecycle_state_names::FINALIZED); + rm->set_component_state(TEST_SYSTEM_HARDWARE_NAME, state_finalized); + rm->set_component_state(TEST_ACTUATOR_HARDWARE_NAME, state_finalized); + rm->set_component_state(TEST_SENSOR_HARDWARE_NAME, state_finalized); + + auto status_map = rm->get_components_status(); + EXPECT_EQ( + status_map[TEST_ACTUATOR_HARDWARE_NAME].state.id(), + lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED); + EXPECT_EQ( + status_map[TEST_SYSTEM_HARDWARE_NAME].state.id(), + lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED); + EXPECT_EQ( + status_map[TEST_SENSOR_HARDWARE_NAME].state.id(), + lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED); + + check_read_and_write_cycles(false); +} + int main(int argc, char ** argv) { rclcpp::init(argc, argv); diff --git a/ros2_control_test_assets/include/ros2_control_test_assets/descriptions.hpp b/ros2_control_test_assets/include/ros2_control_test_assets/descriptions.hpp index e94d4e6736..5f4512a9d1 100644 --- a/ros2_control_test_assets/include/ros2_control_test_assets/descriptions.hpp +++ b/ros2_control_test_assets/include/ros2_control_test_assets/descriptions.hpp @@ -709,6 +709,100 @@ const auto async_hardware_resources = )"; +const auto hardware_resources_with_different_rw_rates = + R"( + + + test_actuator + + + + + + + + + + + test_sensor + 2 + 2 + + + + + + + + test_system + 2 + 2 + + + + + + + + + + + + + + + + + + + +)"; + +const auto hardware_resources_with_negative_rw_rates = + R"( + + + test_actuator + + + + + + + + +)"; + +const auto hardware_resources_invalid_with_text_in_rw_rates = + R"( + + + test_actuator + + + + + + + + +)"; + +const auto hardware_resources_invalid_out_of_range_in_rw_rates = + R"( + + + test_actuator + + + + + + + + +)"; + const auto uninitializable_hardware_resources = R"( @@ -1938,6 +2032,9 @@ const auto minimal_robot_urdf = std::string(urdf_head) + std::string(hardware_resources) + std::string(urdf_tail); const auto minimal_async_robot_urdf = std::string(urdf_head) + std::string(async_hardware_resources) + std::string(urdf_tail); +const auto minimal_robot_urdf_with_different_hw_rw_rate = + std::string(urdf_head) + std::string(hardware_resources_with_different_rw_rates) + + std::string(urdf_tail); const auto minimal_uninitializable_robot_urdf = std::string(urdf_head) + std::string(uninitializable_hardware_resources) + std::string(urdf_tail); From 331038d9c71194b3f8c4400e6d8e3d10d5ca7b2c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Wed, 4 Dec 2024 19:27:52 +0100 Subject: [PATCH 6/6] CM: Check if a valid time is received (#1901) --- controller_manager/src/controller_manager.cpp | 26 +++++++++++++++++-- 1 file changed, 24 insertions(+), 2 deletions(-) diff --git a/controller_manager/src/controller_manager.cpp b/controller_manager/src/controller_manager.cpp index 56e95c9f7b..42542dec7c 100644 --- a/controller_manager/src/controller_manager.cpp +++ b/controller_manager/src/controller_manager.cpp @@ -2390,14 +2390,36 @@ controller_interface::return_type ControllerManager::update( run_controller_at_cm_rate ? period : rclcpp::Duration::from_seconds((1.0 / controller_update_rate)); - const rclcpp::Time current_time = get_clock()->now(); + rclcpp::Time current_time; bool first_update_cycle = false; + if (get_clock()->started()) + { + current_time = get_clock()->now(); + } + else if ( + time == rclcpp::Time(0, 0, this->get_node_clock_interface()->get_clock()->get_clock_type())) + { + throw std::runtime_error( + "No clock received, and time argument is zero. Check your controller_manager node's " + "clock configuration (use_sim_time parameter) and if a valid clock source is " + "available. Also pass a proper time argument to the update method."); + } + else + { + // this can happen with use_sim_time=true until the /clock is received + rclcpp::Clock clock = rclcpp::Clock(); + RCLCPP_WARN_THROTTLE( + get_logger(), clock, 1000, + "No clock received, using time argument instead! Check your node's clock " + "configuration (use_sim_time parameter) and if a valid clock source is available"); + current_time = time; + } if ( *loaded_controller.last_update_cycle_time == rclcpp::Time(0, 0, this->get_node_clock_interface()->get_clock()->get_clock_type())) { + // last_update_cycle_time is zero after activation first_update_cycle = true; - // it is zero after activation *loaded_controller.last_update_cycle_time = current_time; RCLCPP_DEBUG( get_logger(), "Setting last_update_cycle_time to %fs for the controller : %s",