Skip to content

Commit fdeb59e

Browse files
authored
Merge branch 'master' into async_hardware_components
2 parents 36652f8 + 6164883 commit fdeb59e

File tree

27 files changed

+165
-24
lines changed

27 files changed

+165
-24
lines changed

controller_interface/CHANGELOG.rst

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

5+
4.16.1 (2024-08-24)
6+
-------------------
7+
8+
4.16.0 (2024-08-22)
9+
-------------------
10+
* Fix params_file typo in spawner and update release notes for use_global_arguments (`#1701 <https://github.com/ros-controls/ros2_control/issues/1701>`_)
11+
* Avoid using the global arguments for internal controller nodes (`#1694 <https://github.com/ros-controls/ros2_control/issues/1694>`_)
12+
* Contributors: Sai Kishor Kothakota
13+
514
4.15.0 (2024-08-05)
615
-------------------
716

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.15.0</version>
5+
<version>4.16.1</version>
66
<description>Description of controller_interface</description>
77
<maintainer email="[email protected]">Bence Magyar</maintainer>
88
<maintainer email="[email protected]">Denis Štogl</maintainer>

controller_manager/CHANGELOG.rst

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

5+
4.16.1 (2024-08-24)
6+
-------------------
7+
* propage a portion of global args to the controller nodes (`#1712 <https://github.com/ros-controls/ros2_control/issues/1712>`_)
8+
* Contributors: Sai Kishor Kothakota
9+
10+
4.16.0 (2024-08-22)
11+
-------------------
12+
* inform user what reason is for not setting rt policy, inform is policy (`#1705 <https://github.com/ros-controls/ros2_control/issues/1705>`_)
13+
* Fix params_file typo in spawner and update release notes for use_global_arguments (`#1701 <https://github.com/ros-controls/ros2_control/issues/1701>`_)
14+
* Fix spawner tests timeout (`#1692 <https://github.com/ros-controls/ros2_control/issues/1692>`_)
15+
* Refactor spawner to be able to reuse code for ros2controlcli (`#1661 <https://github.com/ros-controls/ros2_control/issues/1661>`_)
16+
* Robustify controller spawner and add integration test with many controllers (`#1501 <https://github.com/ros-controls/ros2_control/issues/1501>`_)
17+
* Handle waiting in Spawner and align Hardware Spawner functionality (`#1562 <https://github.com/ros-controls/ros2_control/issues/1562>`_)
18+
* Make list controller and list hardware components immediately visualize the state. (`#1606 <https://github.com/ros-controls/ros2_control/issues/1606>`_)
19+
* [CI] Add coveragepy and remove ignore: test (`#1668 <https://github.com/ros-controls/ros2_control/issues/1668>`_)
20+
* Fix spawner unload on kill test (`#1675 <https://github.com/ros-controls/ros2_control/issues/1675>`_)
21+
* [CM] Add more logging for easier debugging (`#1645 <https://github.com/ros-controls/ros2_control/issues/1645>`_)
22+
* refactor SwitchParams to fix the incosistencies in the spawner tests (`#1638 <https://github.com/ros-controls/ros2_control/issues/1638>`_)
23+
* Contributors: Bence Magyar, Christoph Fröhlich, Dr. Denis, Felix Exner (fexner), Manuel Muth, Sai Kishor Kothakota
24+
525
4.15.0 (2024-08-05)
626
-------------------
727
* Add missing include for executors (`#1653 <https://github.com/ros-controls/ros2_control/issues/1653>`_)

controller_manager/include/controller_manager/controller_manager.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -577,6 +577,7 @@ class ControllerManager : public rclcpp::Node
577577
std::map<std::string, std::vector<std::string>> controller_chained_reference_interfaces_cache_;
578578
std::map<std::string, std::vector<std::string>> controller_chained_state_interfaces_cache_;
579579

580+
rclcpp::NodeOptions cm_node_options_;
580581
std::string robot_description_;
581582
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr robot_description_subscription_;
582583
rclcpp::TimerBase::SharedPtr robot_description_notification_timer_;

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.15.0</version>
5+
<version>4.16.1</version>
66
<description>Description of controller_manager</description>
77
<maintainer email="[email protected]">Bence Magyar</maintainer>
88
<maintainer email="[email protected]">Denis Štogl</maintainer>

controller_manager/src/controller_manager.cpp

Lines changed: 41 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,7 @@
2424
#include "controller_manager_msgs/msg/hardware_component_state.hpp"
2525
#include "hardware_interface/types/lifecycle_state_names.hpp"
2626
#include "lifecycle_msgs/msg/state.hpp"
27+
#include "rcl/arguments.h"
2728
#include "rclcpp/version.h"
2829
#include "rclcpp_lifecycle/state.hpp"
2930

@@ -197,7 +198,8 @@ ControllerManager::ControllerManager(
197198
kControllerInterfaceNamespace, kControllerInterfaceClassName)),
198199
chainable_loader_(
199200
std::make_shared<pluginlib::ClassLoader<controller_interface::ChainableControllerInterface>>(
200-
kControllerInterfaceNamespace, kChainableControllerInterfaceClassName))
201+
kControllerInterfaceNamespace, kChainableControllerInterfaceClassName)),
202+
cm_node_options_(options)
201203
{
202204
init_controller_manager();
203205
}
@@ -217,7 +219,8 @@ ControllerManager::ControllerManager(
217219
kControllerInterfaceNamespace, kControllerInterfaceClassName)),
218220
chainable_loader_(
219221
std::make_shared<pluginlib::ClassLoader<controller_interface::ChainableControllerInterface>>(
220-
kControllerInterfaceNamespace, kChainableControllerInterfaceClassName))
222+
kControllerInterfaceNamespace, kChainableControllerInterfaceClassName)),
223+
cm_node_options_(options)
221224
{
222225
init_controller_manager();
223226
}
@@ -234,7 +237,8 @@ ControllerManager::ControllerManager(
234237
kControllerInterfaceNamespace, kControllerInterfaceClassName)),
235238
chainable_loader_(
236239
std::make_shared<pluginlib::ClassLoader<controller_interface::ChainableControllerInterface>>(
237-
kControllerInterfaceNamespace, kChainableControllerInterfaceClassName))
240+
kControllerInterfaceNamespace, kChainableControllerInterfaceClassName)),
241+
cm_node_options_(options)
238242
{
239243
init_controller_manager();
240244
}
@@ -2818,29 +2822,56 @@ rclcpp::NodeOptions ControllerManager::determine_controller_node_options(
28182822

28192823
rclcpp::NodeOptions controller_node_options = controller.c->define_custom_node_options();
28202824
std::vector<std::string> node_options_arguments = controller_node_options.arguments();
2821-
const std::string ros_args_arg = "--ros-args";
2825+
2826+
for (const std::string & arg : cm_node_options_.arguments())
2827+
{
2828+
if (arg.find("__ns") != std::string::npos || arg.find("__node") != std::string::npos)
2829+
{
2830+
if (
2831+
node_options_arguments.back() == RCL_REMAP_FLAG ||
2832+
node_options_arguments.back() == RCL_SHORT_REMAP_FLAG)
2833+
{
2834+
node_options_arguments.pop_back();
2835+
}
2836+
continue;
2837+
}
2838+
2839+
node_options_arguments.push_back(arg);
2840+
}
2841+
28222842
if (controller.info.parameters_file.has_value())
28232843
{
2824-
if (!check_for_element(node_options_arguments, ros_args_arg))
2844+
if (!check_for_element(node_options_arguments, RCL_ROS_ARGS_FLAG))
28252845
{
2826-
node_options_arguments.push_back(ros_args_arg);
2846+
node_options_arguments.push_back(RCL_ROS_ARGS_FLAG);
28272847
}
2828-
node_options_arguments.push_back("--params-file");
2848+
node_options_arguments.push_back(RCL_PARAM_FILE_FLAG);
28292849
node_options_arguments.push_back(controller.info.parameters_file.value());
28302850
}
28312851

28322852
// ensure controller's `use_sim_time` parameter matches controller_manager's
28332853
const rclcpp::Parameter use_sim_time = this->get_parameter("use_sim_time");
28342854
if (use_sim_time.as_bool())
28352855
{
2836-
if (!check_for_element(node_options_arguments, ros_args_arg))
2856+
if (!check_for_element(node_options_arguments, RCL_ROS_ARGS_FLAG))
28372857
{
2838-
node_options_arguments.push_back(ros_args_arg);
2858+
node_options_arguments.push_back(RCL_ROS_ARGS_FLAG);
28392859
}
2840-
node_options_arguments.push_back("-p");
2860+
node_options_arguments.push_back(RCL_PARAM_FLAG);
28412861
node_options_arguments.push_back("use_sim_time:=true");
28422862
}
28432863

2864+
std::string arguments;
2865+
arguments.reserve(1000);
2866+
for (const auto & arg : node_options_arguments)
2867+
{
2868+
arguments.append(arg);
2869+
arguments.append(" ");
2870+
}
2871+
RCLCPP_INFO(
2872+
get_logger(), "Controller '%s' node arguments: %s", controller.info.name.c_str(),
2873+
arguments.c_str());
2874+
28442875
controller_node_options = controller_node_options.arguments(node_options_arguments);
28452876
controller_node_options.use_global_arguments(false);
28462877
return controller_node_options;

controller_manager/src/ros2_control_node.cpp

Lines changed: 16 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -41,7 +41,22 @@ int main(int argc, char ** argv)
4141
std::make_shared<rclcpp::executors::MultiThreadedExecutor>();
4242
std::string manager_node_name = "controller_manager";
4343

44-
auto cm = std::make_shared<controller_manager::ControllerManager>(executor, manager_node_name);
44+
rclcpp::NodeOptions cm_node_options = controller_manager::get_cm_node_options();
45+
std::vector<std::string> node_arguments = cm_node_options.arguments();
46+
for (int i = 1; i < argc; ++i)
47+
{
48+
if (node_arguments.empty() && std::string(argv[i]) != "--ros-args")
49+
{
50+
// A simple way to reject non ros args
51+
continue;
52+
}
53+
RCLCPP_INFO(rclcpp::get_logger("CM args"), "Adding argument: %s", argv[i]);
54+
node_arguments.push_back(argv[i]);
55+
}
56+
cm_node_options.arguments(node_arguments);
57+
58+
auto cm = std::make_shared<controller_manager::ControllerManager>(
59+
executor, manager_node_name, "", cm_node_options);
4560

4661
RCLCPP_INFO(cm->get_logger(), "update rate is %d Hz", cm->get_update_rate());
4762

controller_manager_msgs/CHANGELOG.rst

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

5+
4.16.1 (2024-08-24)
6+
-------------------
7+
8+
4.16.0 (2024-08-22)
9+
-------------------
10+
511
4.15.0 (2024-08-05)
612
-------------------
713

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.15.0</version>
5+
<version>4.16.1</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: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,17 @@
22
Changelog for package hardware_interface
33
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
44

5+
4.16.1 (2024-08-24)
6+
-------------------
7+
8+
4.16.0 (2024-08-22)
9+
-------------------
10+
* Use handle_name\_ variable instead of allocating for every `get_name` call (`#1706 <https://github.com/ros-controls/ros2_control/issues/1706>`_)
11+
* Introduce Creation of Handles with InterfaceDescription (variant support) (`#1679 <https://github.com/ros-controls/ros2_control/issues/1679>`_)
12+
* Preparation of Handles for Variant Support (`#1678 <https://github.com/ros-controls/ros2_control/issues/1678>`_)
13+
* [RM] Decouple read/write cycles of each component with mutex to not block other components (`#1646 <https://github.com/ros-controls/ros2_control/issues/1646>`_)
14+
* Contributors: Manuel Muth, Sai Kishor Kothakota
15+
516
4.15.0 (2024-08-05)
617
-------------------
718
* [RM] Add `get_hardware_info` method to the Hardware Components (`#1643 <https://github.com/ros-controls/ros2_control/issues/1643>`_)

0 commit comments

Comments
 (0)