From 3d57fc81572558b2ce5962bd59de66e20a8213d5 Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Wed, 4 Dec 2024 13:02:40 +0100 Subject: [PATCH] [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);