Skip to content

Commit 9bf94a7

Browse files
authored
Merge branch 'master' into isolate/start_stop_interfaces
2 parents 5b23a55 + ffbcd16 commit 9bf94a7

File tree

29 files changed

+327
-31
lines changed

29 files changed

+327
-31
lines changed

controller_interface/CHANGELOG.rst

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,16 @@
22
Changelog for package controller_interface
33
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
44

5+
4.28.0 (2025-04-10)
6+
-------------------
7+
* Make all packages use gmock, not gtest (`#2162 <https://github.com/ros-controls/ros2_control/issues/2162>`_)
8+
* Fix async controllers deactivation regime (`#2017 <https://github.com/ros-controls/ros2_control/issues/2017>`_)
9+
* Bump version of pre-commit hooks (`#2156 <https://github.com/ros-controls/ros2_control/issues/2156>`_)
10+
* Use ros2_control_cmake (`#2134 <https://github.com/ros-controls/ros2_control/issues/2134>`_)
11+
* [Handle] Add support for booleans in the handles (`#2065 <https://github.com/ros-controls/ros2_control/issues/2065>`_)
12+
* Improve package descriptions & update maintainers (`#2103 <https://github.com/ros-controls/ros2_control/issues/2103>`_)
13+
* Contributors: Bence Magyar, Christoph Fröhlich, Sai Kishor Kothakota, Soham Patil, github-actions[bot]
14+
515
4.27.0 (2025-03-01)
616
-------------------
717
* [Handle] Use `get_optional` instead of `get_value<double>` (`#2061 <https://github.com/ros-controls/ros2_control/issues/2061>`_)

controller_interface/package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="2">
44
<name>controller_interface</name>
5-
<version>4.27.0</version>
5+
<version>4.28.0</version>
66
<description>Base classes for controllers and syntax cookies for supporting common sensor types in controllers and broadcasters</description>
77
<maintainer email="[email protected]">Bence Magyar</maintainer>
88
<maintainer email="[email protected]">Denis Štogl</maintainer>

controller_manager/CHANGELOG.rst

Lines changed: 26 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,32 @@
22
Changelog for package controller_manager
33
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
44

5+
4.28.0 (2025-04-10)
6+
-------------------
7+
* Integrate joint limit enforcement into `ros2_control` framework functional with Async controllers and components (`#2047 <https://github.com/ros-controls/ros2_control/issues/2047>`_)
8+
* Make all packages use gmock, not gtest (`#2162 <https://github.com/ros-controls/ros2_control/issues/2162>`_)
9+
* Fix async controllers deactivation regime (`#2017 <https://github.com/ros-controls/ros2_control/issues/2017>`_)
10+
* apply pre-commit changes (`#2160 <https://github.com/ros-controls/ros2_control/issues/2160>`_)
11+
* Add tests for multiple controller ros args (`#2155 <https://github.com/ros-controls/ros2_control/issues/2155>`_)
12+
* Bump version of pre-commit hooks (`#2156 <https://github.com/ros-controls/ros2_control/issues/2156>`_)
13+
* Allow for multiple controller-ros-args arguments in spawner.py (`#2150 <https://github.com/ros-controls/ros2_control/issues/2150>`_)
14+
* Update `rqt_controller_manager` controller state color scheme to match list_controllers color scheme (`#2143 <https://github.com/ros-controls/ros2_control/issues/2143>`_)
15+
* Fix generate_controllers_spawner_launch_description_from_dict (`#2146 <https://github.com/ros-controls/ros2_control/issues/2146>`_)
16+
* Use ros2_control_cmake (`#2134 <https://github.com/ros-controls/ros2_control/issues/2134>`_)
17+
* [Docs] Update determinism section (`#2131 <https://github.com/ros-controls/ros2_control/issues/2131>`_)
18+
* Remove the dangling param flag for robot_description fom ROS parameters (`#2115 <https://github.com/ros-controls/ros2_control/issues/2115>`_)
19+
* [Doc] Add documentation of different controller manager clocks (`#2109 <https://github.com/ros-controls/ros2_control/issues/2109>`_)
20+
* [CM] Extend the list controller and hardware components messages (`#2102 <https://github.com/ros-controls/ros2_control/issues/2102>`_)
21+
* Improve package descriptions & update maintainers (`#2103 <https://github.com/ros-controls/ros2_control/issues/2103>`_)
22+
* Reject duplicate state/command interfaces after configuring the controller (`#2090 <https://github.com/ros-controls/ros2_control/issues/2090>`_)
23+
* [CM] Add message field to the `switch_controller` service (`#2088 <https://github.com/ros-controls/ros2_control/issues/2088>`_)
24+
* Update doc: async update support for controller (`#2096 <https://github.com/ros-controls/ros2_control/issues/2096>`_)
25+
* Use monotonic clock for triggering read-update-write cycles + fix for overruns (`#2046 <https://github.com/ros-controls/ros2_control/issues/2046>`_)
26+
* Add some logging for `unload_on_kill` keyboard interrupt (`#2097 <https://github.com/ros-controls/ros2_control/issues/2097>`_)
27+
* [CM] Add controller_manager activity topic (`#2006 <https://github.com/ros-controls/ros2_control/issues/2006>`_)
28+
* Improve diagnostics strings (`#2078 <https://github.com/ros-controls/ros2_control/issues/2078>`_)
29+
* Contributors: Bence Magyar, Christoph Fröhlich, Julia Jia, Sai Kishor Kothakota, Soham Patil, danielcostanzi18, github-actions[bot]
30+
531
4.27.0 (2025-03-01)
632
-------------------
733
* [HW Components] Add fix for async hardware components improper rate (`#2076 <https://github.com/ros-controls/ros2_control/issues/2076>`_)

controller_manager/package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="2">
44
<name>controller_manager</name>
5-
<version>4.27.0</version>
5+
<version>4.28.0</version>
66
<description>The main runnable entrypoint of ros2_control and home of controller management and resource management.</description>
77
<maintainer email="[email protected]">Bence Magyar</maintainer>
88
<maintainer email="[email protected]">Denis Štogl</maintainer>

controller_manager_msgs/CHANGELOG.rst

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,14 @@
22
Changelog for package controller_manager_msgs
33
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
44

5+
4.28.0 (2025-04-10)
6+
-------------------
7+
* [CM] Extend the list controller and hardware components messages (`#2102 <https://github.com/ros-controls/ros2_control/issues/2102>`_)
8+
* Improve package descriptions & update maintainers (`#2103 <https://github.com/ros-controls/ros2_control/issues/2103>`_)
9+
* [CM] Add message field to the `switch_controller` service (`#2088 <https://github.com/ros-controls/ros2_control/issues/2088>`_)
10+
* [CM] Add controller_manager activity topic (`#2006 <https://github.com/ros-controls/ros2_control/issues/2006>`_)
11+
* Contributors: Bence Magyar, Sai Kishor Kothakota
12+
513
4.27.0 (2025-03-01)
614
-------------------
715

controller_manager_msgs/package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="3">
44
<name>controller_manager_msgs</name>
5-
<version>4.27.0</version>
5+
<version>4.28.0</version>
66
<description>Messages and services for the controller manager.</description>
77
<maintainer email="[email protected]">Bence Magyar</maintainer>
88
<maintainer email="[email protected]">Denis Štogl</maintainer>

hardware_interface/CHANGELOG.rst

Lines changed: 17 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,23 @@
22
Changelog for package hardware_interface
33
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
44

5+
4.28.0 (2025-04-10)
6+
-------------------
7+
* [HW Interface] Use new handle API inside the hardware components (`#2092 <https://github.com/ros-controls/ros2_control/issues/2092>`_)
8+
* Integrate joint limit enforcement into `ros2_control` framework functional with Async controllers and components (`#2047 <https://github.com/ros-controls/ros2_control/issues/2047>`_)
9+
* Make all packages use gmock, not gtest (`#2162 <https://github.com/ros-controls/ros2_control/issues/2162>`_)
10+
* Bump version of pre-commit hooks (`#2156 <https://github.com/ros-controls/ros2_control/issues/2156>`_)
11+
* [RM] Add error handling for missing `plugin` tags in URDF parsing (`#2138 <https://github.com/ros-controls/ros2_control/issues/2138>`_)
12+
* Use ros2_control_cmake (`#2134 <https://github.com/ros-controls/ros2_control/issues/2134>`_)
13+
* [Handle] Add support for booleans in the handles (`#2065 <https://github.com/ros-controls/ros2_control/issues/2065>`_)
14+
* Docs: Remove link to gazebo_ros2_control (`#2106 <https://github.com/ros-controls/ros2_control/issues/2106>`_)
15+
* Improve package descriptions & update maintainers (`#2103 <https://github.com/ros-controls/ros2_control/issues/2103>`_)
16+
* Use monotonic clock for triggering read-update-write cycles + fix for overruns (`#2046 <https://github.com/ros-controls/ros2_control/issues/2046>`_)
17+
* [RM] Fix skipped cycles by adjusting `rw_rate` handling (`#2091 <https://github.com/ros-controls/ros2_control/issues/2091>`_)
18+
* [CM] Add controller_manager activity topic (`#2006 <https://github.com/ros-controls/ros2_control/issues/2006>`_)
19+
* Improve API/lifecycle docs (`#2081 <https://github.com/ros-controls/ros2_control/issues/2081>`_)
20+
* Contributors: Bence Magyar, Christoph Fröhlich, Mehul Anand, RobertWilbrandt, Sai Kishor Kothakota, Soham Patil, github-actions[bot]
21+
522
4.27.0 (2025-03-01)
623
-------------------
724
* [HW Components] Add fix for async hardware components improper rate (`#2076 <https://github.com/ros-controls/ros2_control/issues/2076>`_)

hardware_interface/include/hardware_interface/actuator_interface.hpp

Lines changed: 60 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -513,24 +513,77 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod
513513
lifecycle_state_ = new_state;
514514
}
515515

516-
void set_state(const std::string & interface_name, const double & value)
516+
template <typename T>
517+
void set_state(const std::string & interface_name, const T & value)
517518
{
518-
actuator_states_.at(interface_name)->set_value(value);
519+
auto it = actuator_states_.find(interface_name);
520+
if (it == actuator_states_.end())
521+
{
522+
throw std::runtime_error(
523+
"State interface not found: " + interface_name +
524+
" in actuator hardware component: " + info_.name + ". This should not happen.");
525+
}
526+
auto & handle = it->second;
527+
std::unique_lock<std::shared_mutex> lock(handle->get_mutex());
528+
std::ignore = handle->set_value(lock, value);
519529
}
520530

521-
double get_state(const std::string & interface_name) const
531+
template <typename T = double>
532+
T get_state(const std::string & interface_name) const
522533
{
523-
return actuator_states_.at(interface_name)->get_value();
534+
auto it = actuator_states_.find(interface_name);
535+
if (it == actuator_states_.end())
536+
{
537+
throw std::runtime_error(
538+
"State interface not found: " + interface_name +
539+
" in actuator hardware component: " + info_.name + ". This should not happen.");
540+
}
541+
auto & handle = it->second;
542+
std::shared_lock<std::shared_mutex> lock(handle->get_mutex());
543+
const auto opt_value = handle->get_optional<T>(lock);
544+
if (!opt_value)
545+
{
546+
throw std::runtime_error(
547+
"Failed to get state value from interface: " + interface_name +
548+
". This should not happen.");
549+
}
550+
return opt_value.value();
524551
}
525552

526553
void set_command(const std::string & interface_name, const double & value)
527554
{
528-
actuator_commands_.at(interface_name)->set_value(value);
555+
auto it = actuator_commands_.find(interface_name);
556+
if (it == actuator_commands_.end())
557+
{
558+
throw std::runtime_error(
559+
"Command interface not found: " + interface_name +
560+
" in actuator hardware component: " + info_.name + ". This should not happen.");
561+
}
562+
auto & handle = it->second;
563+
std::unique_lock<std::shared_mutex> lock(handle->get_mutex());
564+
std::ignore = handle->set_value(lock, value);
529565
}
530566

531-
double get_command(const std::string & interface_name) const
567+
template <typename T = double>
568+
T get_command(const std::string & interface_name) const
532569
{
533-
return actuator_commands_.at(interface_name)->get_value();
570+
auto it = actuator_commands_.find(interface_name);
571+
if (it == actuator_commands_.end())
572+
{
573+
throw std::runtime_error(
574+
"Command interface not found: " + interface_name +
575+
" in actuator hardware component: " + info_.name + ". This should not happen.");
576+
}
577+
auto & handle = it->second;
578+
std::shared_lock<std::shared_mutex> lock(handle->get_mutex());
579+
const auto opt_value = handle->get_optional<double>(lock);
580+
if (!opt_value)
581+
{
582+
throw std::runtime_error(
583+
"Failed to get command value from interface: " + interface_name +
584+
". This should not happen.");
585+
}
586+
return opt_value.value();
534587
}
535588

536589
/// Get the logger of the ActuatorInterface.

hardware_interface/include/hardware_interface/handle.hpp

Lines changed: 36 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -172,6 +172,22 @@ class Handle
172172
[[nodiscard]] std::optional<T> get_optional() const
173173
{
174174
std::shared_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
175+
return get_optional<T>(lock);
176+
}
177+
/**
178+
* @brief Get the value of the handle.
179+
* @tparam T The type of the value to be retrieved.
180+
* @param lock The lock to access the value.
181+
* @return The value of the handle if it accessed successfully, std::nullopt otherwise.
182+
*
183+
* @note The method is thread-safe and non-blocking.
184+
* @note When different threads access the same handle at same instance, and if they are unable to
185+
* lock the handle to access the value, the handle returns std::nullopt. If the operation is
186+
* successful, the value is returned.
187+
*/
188+
template <typename T = double>
189+
[[nodiscard]] std::optional<T> get_optional(std::shared_lock<std::shared_mutex> & lock) const
190+
{
175191
if (!lock.owns_lock())
176192
{
177193
return std::nullopt;
@@ -259,6 +275,24 @@ class Handle
259275
[[nodiscard]] bool set_value(const T & value)
260276
{
261277
std::unique_lock<std::shared_mutex> lock(handle_mutex_, std::try_to_lock);
278+
return set_value(lock, value);
279+
}
280+
281+
/**
282+
* @brief Set the value of the handle.
283+
* @tparam T The type of the value to be set.
284+
* @param lock The lock to set the value.
285+
* @param value The value to be set.
286+
* @return true if the value is set successfully, false otherwise.
287+
*
288+
* @note The method is thread-safe and non-blocking.
289+
* @note When different threads access the same handle at same instance, and if they are unable to
290+
* lock the handle to set the value, the handle returns false. If the operation is successful, the
291+
* handle is updated and returns true.
292+
*/
293+
template <typename T>
294+
[[nodiscard]] bool set_value(std::unique_lock<std::shared_mutex> & lock, const T & value)
295+
{
262296
if (!lock.owns_lock())
263297
{
264298
return false;
@@ -285,6 +319,8 @@ class Handle
285319
// END
286320
}
287321

322+
std::shared_mutex & get_mutex() { return handle_mutex_; }
323+
288324
HandleDataType get_data_type() const { return data_type_; }
289325

290326
private:

hardware_interface/include/hardware_interface/sensor_interface.hpp

Lines changed: 31 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -325,14 +325,41 @@ class SensorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
325325
lifecycle_state_ = new_state;
326326
}
327327

328-
void set_state(const std::string & interface_name, const double & value)
328+
template <typename T>
329+
void set_state(const std::string & interface_name, const T & value)
329330
{
330-
sensor_states_map_.at(interface_name)->set_value(value);
331+
auto it = sensor_states_map_.find(interface_name);
332+
if (it == sensor_states_map_.end())
333+
{
334+
throw std::runtime_error(
335+
"State interface not found: " + interface_name +
336+
" in sensor hardware component: " + info_.name + ". This should not happen.");
337+
}
338+
auto & handle = it->second;
339+
std::unique_lock<std::shared_mutex> lock(handle->get_mutex());
340+
std::ignore = handle->set_value(lock, value);
331341
}
332342

333-
double get_state(const std::string & interface_name) const
343+
template <typename T = double>
344+
T get_state(const std::string & interface_name) const
334345
{
335-
return sensor_states_map_.at(interface_name)->get_value();
346+
auto it = sensor_states_map_.find(interface_name);
347+
if (it == sensor_states_map_.end())
348+
{
349+
throw std::runtime_error(
350+
"State interface not found: " + interface_name +
351+
" in sensor hardware component: " + info_.name + ". This should not happen.");
352+
}
353+
auto & handle = it->second;
354+
std::shared_lock<std::shared_mutex> lock(handle->get_mutex());
355+
const auto opt_value = handle->get_optional<T>(lock);
356+
if (!opt_value)
357+
{
358+
throw std::runtime_error(
359+
"Failed to get state value from interface: " + interface_name +
360+
". This should not happen.");
361+
}
362+
return opt_value.value();
336363
}
337364

338365
/// Get the logger of the SensorInterface.

hardware_interface/include/hardware_interface/system_interface.hpp

Lines changed: 60 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -543,24 +543,77 @@ class SystemInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
543543
lifecycle_state_ = new_state;
544544
}
545545

546-
void set_state(const std::string & interface_name, const double & value)
546+
template <typename T>
547+
void set_state(const std::string & interface_name, const T & value)
547548
{
548-
system_states_.at(interface_name)->set_value(value);
549+
auto it = system_states_.find(interface_name);
550+
if (it == system_states_.end())
551+
{
552+
throw std::runtime_error(
553+
"State interface not found: " + interface_name +
554+
" in system hardware component: " + info_.name + ". This should not happen.");
555+
}
556+
auto & handle = it->second;
557+
std::unique_lock<std::shared_mutex> lock(handle->get_mutex());
558+
std::ignore = handle->set_value(lock, value);
549559
}
550560

551-
double get_state(const std::string & interface_name) const
561+
template <typename T = double>
562+
T get_state(const std::string & interface_name) const
552563
{
553-
return system_states_.at(interface_name)->get_value();
564+
auto it = system_states_.find(interface_name);
565+
if (it == system_states_.end())
566+
{
567+
throw std::runtime_error(
568+
"State interface not found: " + interface_name +
569+
" in system hardware component: " + info_.name + ". This should not happen.");
570+
}
571+
auto & handle = it->second;
572+
std::shared_lock<std::shared_mutex> lock(handle->get_mutex());
573+
const auto opt_value = handle->get_optional<T>(lock);
574+
if (!opt_value)
575+
{
576+
throw std::runtime_error(
577+
"Failed to get state value from interface: " + interface_name +
578+
". This should not happen.");
579+
}
580+
return opt_value.value();
554581
}
555582

556583
void set_command(const std::string & interface_name, const double & value)
557584
{
558-
system_commands_.at(interface_name)->set_value(value);
585+
auto it = system_commands_.find(interface_name);
586+
if (it == system_commands_.end())
587+
{
588+
throw std::runtime_error(
589+
"Command interface not found: " + interface_name +
590+
" in system hardware component: " + info_.name + ". This should not happen.");
591+
}
592+
auto & handle = it->second;
593+
std::unique_lock<std::shared_mutex> lock(handle->get_mutex());
594+
std::ignore = handle->set_value(lock, value);
559595
}
560596

561-
double get_command(const std::string & interface_name) const
597+
template <typename T = double>
598+
T get_command(const std::string & interface_name) const
562599
{
563-
return system_commands_.at(interface_name)->get_value();
600+
auto it = system_commands_.find(interface_name);
601+
if (it == system_commands_.end())
602+
{
603+
throw std::runtime_error(
604+
"Command interface not found: " + interface_name +
605+
" in system hardware component: " + info_.name + ". This should not happen.");
606+
}
607+
auto & handle = it->second;
608+
std::shared_lock<std::shared_mutex> lock(handle->get_mutex());
609+
const auto opt_value = handle->get_optional<double>(lock);
610+
if (!opt_value)
611+
{
612+
throw std::runtime_error(
613+
"Failed to get command value from interface: " + interface_name +
614+
". This should not happen.");
615+
}
616+
return opt_value.value();
564617
}
565618

566619
/// Get the logger of the SystemInterface.

hardware_interface/package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
<?xml version="1.0"?>
22
<package format="2">
33
<name>hardware_interface</name>
4-
<version>4.27.0</version>
4+
<version>4.28.0</version>
55
<description>Base classes for hardware abstraction and tooling for them</description>
66
<maintainer email="[email protected]">Bence Magyar</maintainer>
77
<maintainer email="[email protected]">Denis Štogl</maintainer>

0 commit comments

Comments
 (0)