Skip to content

Commit

Permalink
Merge branch 'humble' into init_srvs_after_resource_manager_init_humble
Browse files Browse the repository at this point in the history
  • Loading branch information
dyackzan authored Jan 8, 2024
2 parents 6291eff + f4f875a commit c1583fd
Show file tree
Hide file tree
Showing 28 changed files with 194 additions and 12 deletions.
3 changes: 3 additions & 0 deletions controller_interface/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package controller_interface
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.36.1 (2024-01-08)
-------------------

2.36.0 (2023-12-12)
-------------------

Expand Down
2 changes: 1 addition & 1 deletion controller_interface/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="2">
<name>controller_interface</name>
<version>2.36.0</version>
<version>2.36.1</version>
<description>Description of controller_interface</description>
<maintainer email="bence.magyar.robotics@gmail.com">Bence Magyar</maintainer>
<maintainer email="denis@stoglrobotics.de">Denis Štogl</maintainer>
Expand Down
6 changes: 6 additions & 0 deletions controller_manager/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,12 @@
Changelog for package controller_manager
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.36.1 (2024-01-08)
-------------------
* [docs] Remove joint_state_controller (`#1263 <https://github.com/ros-controls/ros2_control/issues/1263>`_) (`#1264 <https://github.com/ros-controls/ros2_control/issues/1264>`_)
* [CI] Increase timeout for controller_managers_srv test (backport `#1224 <https://github.com/ros-controls/ros2_control/issues/1224>`_) (`#1225 <https://github.com/ros-controls/ros2_control/issues/1225>`_)
* Contributors: mergify[bot]

2.36.0 (2023-12-12)
-------------------
* Fix controller sorting issue while loading large number of controllers (`#1180 <https://github.com/ros-controls/ros2_control/issues/1180>`_) (`#1186 <https://github.com/ros-controls/ros2_control/issues/1186>`_)
Expand Down
2 changes: 1 addition & 1 deletion controller_manager/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="2">
<name>controller_manager</name>
<version>2.36.0</version>
<version>2.36.1</version>
<description>Description of controller_manager</description>
<maintainer email="bence.magyar.robotics@gmail.com">Bence Magyar</maintainer>
<maintainer email="denis@stoglrobotics.de">Denis Štogl</maintainer>
Expand Down
3 changes: 3 additions & 0 deletions controller_manager_msgs/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package controller_manager_msgs
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.36.1 (2024-01-08)
-------------------

2.36.0 (2023-12-12)
-------------------

Expand Down
2 changes: 1 addition & 1 deletion controller_manager_msgs/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>controller_manager_msgs</name>
<version>2.36.0</version>
<version>2.36.1</version>
<description>Messages and services for the controller manager.</description>
<maintainer email="bence.magyar.robotics@gmail.com">Bence Magyar</maintainer>
<maintainer email="denis@stoglrobotics.de">Denis Štogl</maintainer>
Expand Down
7 changes: 7 additions & 0 deletions hardware_interface/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,13 @@
Changelog for package hardware_interface
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.36.1 (2024-01-08)
-------------------
* [ResourceManager] adds test for uninitialized hardware (`#1243 <https://github.com/ros-controls/ros2_control/issues/1243>`_) (`#1274 <https://github.com/ros-controls/ros2_control/issues/1274>`_)
* Use portable version for string-to-double conversion (backport `#1257 <https://github.com/ros-controls/ros2_control/issues/1257>`_) (`#1268 <https://github.com/ros-controls/ros2_control/issues/1268>`_)
* Fix typo in docs (`#1219 <https://github.com/ros-controls/ros2_control/issues/1219>`_) (`#1221 <https://github.com/ros-controls/ros2_control/issues/1221>`_)
* Contributors: Christoph Fröhlich, mergify[bot]

2.36.0 (2023-12-12)
-------------------
* Cleanup Resource Manager a bit to increase clarity. (backport `#816 <https://github.com/ros-controls/ros2_control/issues/816>`_) (`#1191 <https://github.com/ros-controls/ros2_control/issues/1191>`_)
Expand Down
2 changes: 1 addition & 1 deletion hardware_interface/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="2">
<name>hardware_interface</name>
<version>2.36.0</version>
<version>2.36.1</version>
<description>ros2_control hardware interface</description>
<maintainer email="bence.magyar.robotics@gmail.com">Bence Magyar</maintainer>
<maintainer email="denis@stoglrobotics.de">Denis Štogl</maintainer>
Expand Down
10 changes: 10 additions & 0 deletions hardware_interface/test/test_components/test_actuator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -109,5 +109,15 @@ class TestActuator : public ActuatorInterface
double max_velocity_command_ = 0.0;
};

class TestUnitilizableActuator : public TestActuator
{
CallbackReturn on_init(const hardware_interface::HardwareInfo & info) override
{
ActuatorInterface::on_init(info);
return CallbackReturn::ERROR;
}
};

#include "pluginlib/class_list_macros.hpp" // NOLINT
PLUGINLIB_EXPORT_CLASS(TestActuator, hardware_interface::ActuatorInterface)
PLUGINLIB_EXPORT_CLASS(TestUnitilizableActuator, hardware_interface::ActuatorInterface)
18 changes: 18 additions & 0 deletions hardware_interface/test/test_components/test_components.xml
Original file line number Diff line number Diff line change
Expand Up @@ -17,4 +17,22 @@
Test System
</description>
</class>

<class name="test_unitilizable_actuator" type="TestUnitilizableActuator" base_class_type="hardware_interface::ActuatorInterface">
<description>
Test Unitilizable Actuator
</description>
</class>

<class name="test_unitilizable_sensor" type="TestUnitilizableSensor" base_class_type="hardware_interface::SensorInterface">
<description>
Test Unitilizable Sensor
</description>
</class>

<class name="test_unitilizable_system" type="TestUnitilizableSystem" base_class_type="hardware_interface::SystemInterface">
<description>
Test Unitilizable System
</description>
</class>
</library>
10 changes: 10 additions & 0 deletions hardware_interface/test/test_components/test_sensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,5 +55,15 @@ class TestSensor : public SensorInterface
double velocity_state_ = 0.0;
};

class TestUnitilizableSensor : public TestSensor
{
CallbackReturn on_init(const hardware_interface::HardwareInfo & info) override
{
SensorInterface::on_init(info);
return CallbackReturn::ERROR;
}
};

#include "pluginlib/class_list_macros.hpp" // NOLINT
PLUGINLIB_EXPORT_CLASS(TestSensor, hardware_interface::SensorInterface)
PLUGINLIB_EXPORT_CLASS(TestUnitilizableSensor, hardware_interface::SensorInterface)
10 changes: 10 additions & 0 deletions hardware_interface/test/test_components/test_system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -115,5 +115,15 @@ class TestSystem : public SystemInterface
double configuration_command_ = 0.0;
};

class TestUnitilizableSystem : public TestSystem
{
CallbackReturn on_init(const hardware_interface::HardwareInfo & info) override
{
SystemInterface::on_init(info);
return CallbackReturn::ERROR;
}
};

#include "pluginlib/class_list_macros.hpp" // NOLINT
PLUGINLIB_EXPORT_CLASS(TestSystem, hardware_interface::SystemInterface)
PLUGINLIB_EXPORT_CLASS(TestUnitilizableSystem, hardware_interface::SystemInterface)
40 changes: 40 additions & 0 deletions hardware_interface/test/test_resource_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,7 @@ class TestableResourceManager : public hardware_interface::ResourceManager
FRIEND_TEST(ResourceManagerTest, post_initialization_add_components);
FRIEND_TEST(ResourceManagerTest, managing_controllers_reference_interfaces);
FRIEND_TEST(ResourceManagerTest, resource_availability_and_claiming_in_lifecycle);
FRIEND_TEST(ResourceManagerTest, test_unitilizable_hardware_no_validation);

TestableResourceManager() : hardware_interface::ResourceManager() {}

Expand Down Expand Up @@ -153,6 +154,45 @@ TEST_F(ResourceManagerTest, post_initialization_with_urdf)
ASSERT_NO_THROW(rm.load_urdf(ros2_control_test_assets::minimal_robot_urdf));
}

TEST_F(ResourceManagerTest, test_unitilizable_hardware_validation)
{
// If the the hardware can not be initialized and load_urdf tried to validate the interfaces a
// runtime exception is thrown
TestableResourceManager rm;
ASSERT_THROW(
rm.load_urdf(ros2_control_test_assets::minimal_unitilizable_robot_urdf, true),
std::runtime_error);
}

TEST_F(ResourceManagerTest, test_unitilizable_hardware_no_validation)
{
// If the the hardware can not be initialized and load_urdf didn't try to validate the interfaces,
// the interface should not show up
TestableResourceManager rm;
EXPECT_NO_THROW(rm.load_urdf(ros2_control_test_assets::minimal_unitilizable_robot_urdf, false));

// test actuator
EXPECT_FALSE(rm.state_interface_exists("joint1/position"));
EXPECT_FALSE(rm.state_interface_exists("joint1/velocity"));
EXPECT_FALSE(rm.command_interface_exists("joint1/position"));
EXPECT_FALSE(rm.command_interface_exists("joint1/max_velocity"));

// test sensor
EXPECT_FALSE(rm.state_interface_exists("sensor1/velocity"));

// test system
EXPECT_FALSE(rm.state_interface_exists("joint2/position"));
EXPECT_FALSE(rm.state_interface_exists("joint2/velocity"));
EXPECT_FALSE(rm.state_interface_exists("joint2/acceleration"));
EXPECT_FALSE(rm.command_interface_exists("joint2/velocity"));
EXPECT_FALSE(rm.command_interface_exists("joint2/max_acceleration"));
EXPECT_FALSE(rm.state_interface_exists("joint3/position"));
EXPECT_FALSE(rm.state_interface_exists("joint3/velocity"));
EXPECT_FALSE(rm.state_interface_exists("joint3/acceleration"));
EXPECT_FALSE(rm.command_interface_exists("joint3/velocity"));
EXPECT_FALSE(rm.command_interface_exists("joint3/max_acceleration"));
}

TEST_F(ResourceManagerTest, initialization_with_urdf_manual_validation)
{
// we validate the results manually
Expand Down
3 changes: 3 additions & 0 deletions joint_limits/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package joint_limits
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.36.1 (2024-01-08)
-------------------

2.36.0 (2023-12-12)
-------------------

Expand Down
2 changes: 1 addition & 1 deletion joint_limits/package.xml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<package format="3">
<name>joint_limits</name>
<version>2.36.0</version>
<version>2.36.1</version>
<description>Interfaces for handling of joint limits for controllers or hardware.</description>

<maintainer email="bence.magyar.robotics@gmail.com">Bence Magyar</maintainer>
Expand Down
3 changes: 3 additions & 0 deletions ros2_control/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package ros2_control
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.36.1 (2024-01-08)
-------------------

2.36.0 (2023-12-12)
-------------------

Expand Down
2 changes: 1 addition & 1 deletion ros2_control/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="3">
<name>ros2_control</name>
<version>2.36.0</version>
<version>2.36.1</version>
<description>Metapackage for ROS2 control related packages</description>
<maintainer email="bence.magyar.robotics@gmail.com">Bence Magyar</maintainer>
<maintainer email="denis@stoglrobotics.de">Denis Štogl</maintainer>
Expand Down
5 changes: 5 additions & 0 deletions ros2_control_test_assets/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,11 @@
Changelog for package ros2_control_test_assets
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.36.1 (2024-01-08)
-------------------
* [ResourceManager] adds test for uninitialized hardware (`#1243 <https://github.com/ros-controls/ros2_control/issues/1243>`_) (`#1274 <https://github.com/ros-controls/ros2_control/issues/1274>`_)
* Contributors: mergify[bot]

2.36.0 (2023-12-12)
-------------------

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -176,6 +176,55 @@ const auto hardware_resources =
</ros2_control>
)";

const auto unitilizable_hardware_resources =
R"(
<ros2_control name="TestUnitilizableActuatorHardware" type="actuator">
<hardware>
<plugin>test_unitilizable_actuator</plugin>
</hardware>
<joint name="joint1">
<command_interface name="position"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<command_interface name="max_velocity" />
</joint>
</ros2_control>
<ros2_control name="TestUnitilizableSensorHardware" type="sensor">
<hardware>
<plugin>test_unitilizable_sensor</plugin>
<param name="example_param_write_for_sec">2</param>
<param name="example_param_read_for_sec">2</param>
</hardware>
<sensor name="sensor1">
<state_interface name="velocity"/>
</sensor>
</ros2_control>
<ros2_control name="TestUnitilizableSystemHardware" type="system">
<hardware>
<plugin>test_unitilizable_system</plugin>
<param name="example_param_write_for_sec">2</param>
<param name="example_param_read_for_sec">2</param>
</hardware>
<joint name="joint2">
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="acceleration"/>
<command_interface name="max_acceleration" />
</joint>
<joint name="joint3">
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="acceleration"/>
</joint>
<joint name="configuration">
<command_interface name="max_tcp_jerk"/>
<state_interface name="max_tcp_jerk"/>
</joint>
</ros2_control>
)";

const auto hardware_resources_missing_state_keys =
R"(
<ros2_control name="TestActuatorHardware" type="actuator">
Expand Down Expand Up @@ -406,6 +455,8 @@ const auto diffbot_urdf =

const auto minimal_robot_urdf =
std::string(urdf_head) + std::string(hardware_resources) + std::string(urdf_tail);
const auto minimal_unitilizable_robot_urdf =
std::string(urdf_head) + std::string(unitilizable_hardware_resources) + std::string(urdf_tail);

const auto minimal_robot_missing_state_keys_urdf =
std::string(urdf_head) + std::string(hardware_resources_missing_state_keys) +
Expand Down
2 changes: 1 addition & 1 deletion ros2_control_test_assets/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>ros2_control_test_assets</name>
<version>2.36.0</version>
<version>2.36.1</version>
<description>The package provides shared test resources for ros2_control stack
</description>
<maintainer email="bence.magyar.robotics@gmail.com">Bence Magyar</maintainer>
Expand Down
5 changes: 5 additions & 0 deletions ros2controlcli/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,11 @@
Changelog for package ros2controlcli
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.36.1 (2024-01-08)
-------------------
* [docs] Remove joint_state_controller (`#1263 <https://github.com/ros-controls/ros2_control/issues/1263>`_) (`#1264 <https://github.com/ros-controls/ros2_control/issues/1264>`_)
* Contributors: mergify[bot]

2.36.0 (2023-12-12)
-------------------

Expand Down
2 changes: 1 addition & 1 deletion ros2controlcli/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="2">
<name>ros2controlcli</name>
<version>2.36.0</version>
<version>2.36.1</version>
<description>
The ROS 2 command line tools for ROS2 Control.
</description>
Expand Down
2 changes: 1 addition & 1 deletion ros2controlcli/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@

setup(
name=package_name,
version='2.36.0',
version='2.36.1',
packages=find_packages(exclude=['test']),
data_files=[
('share/' + package_name, ['package.xml']),
Expand Down
3 changes: 3 additions & 0 deletions rqt_controller_manager/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package rqt_controller_manager
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.36.1 (2024-01-08)
-------------------

2.36.0 (2023-12-12)
-------------------

Expand Down
2 changes: 1 addition & 1 deletion rqt_controller_manager/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>rqt_controller_manager</name>
<version>2.36.0</version>
<version>2.36.1</version>
<description>Graphical frontend for interacting with the controller manager.</description>
<maintainer email="bence.magyar.robotics@gmail.com">Bence Magyar</maintainer>
<maintainer email="denis@stoglrobotics.de">Denis Štogl</maintainer>
Expand Down
2 changes: 1 addition & 1 deletion rqt_controller_manager/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@

setup(
name=package_name,
version='2.36.0',
version='2.36.1',
packages=[package_name],
data_files=[
('share/ament_index/resource_index/packages', ['resource/' + package_name]),
Expand Down
Loading

0 comments on commit c1583fd

Please sign in to comment.