Skip to content

Commit fb1d254

Browse files
authored
Fix params_file typo in spawner and update release notes for use_global_arguments (#1701)
1 parent 4498d25 commit fb1d254

File tree

5 files changed

+10
-4
lines changed

5 files changed

+10
-4
lines changed

controller_interface/include/controller_interface/controller_interface_base.hpp

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -174,12 +174,11 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
174174
{
175175
// \note The versions conditioning is added here to support the source-compatibility with Humble
176176
#if RCLCPP_VERSION_MAJOR >= 21
177-
return rclcpp::NodeOptions().enable_logger_service(true).use_global_arguments(false);
177+
return rclcpp::NodeOptions().enable_logger_service(true);
178178
#else
179179
return rclcpp::NodeOptions()
180180
.allow_undeclared_parameters(true)
181-
.automatically_declare_parameters_from_overrides(true)
182-
.use_global_arguments(false);
181+
.automatically_declare_parameters_from_overrides(true);
183182
#endif
184183
}
185184

controller_manager/controller_manager/controller_manager_services.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -312,7 +312,7 @@ def set_controller_parameters_from_param_file(
312312
if parameter_file:
313313
spawner_namespace = namespace if namespace else node.get_namespace()
314314
set_controller_parameters(
315-
node, controller_manager_name, controller_name, "param_file", parameter_file
315+
node, controller_manager_name, controller_name, "params_file", parameter_file
316316
)
317317

318318
controller_type = get_parameter_from_param_file(

controller_manager/src/controller_manager.cpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2843,6 +2843,7 @@ rclcpp::NodeOptions ControllerManager::determine_controller_node_options(
28432843
}
28442844

28452845
controller_node_options = controller_node_options.arguments(node_options_arguments);
2846+
controller_node_options.use_global_arguments(false);
28462847
return controller_node_options;
28472848
}
28482849

doc/migration.rst

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,10 @@
22

33
Iron to Jazzy
44
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
5+
controller_interface
6+
********************
7+
* The changes from `(PR #1694) <https://github.com/ros-controls/ros2_control/pull/1694>`__ will affect how the controllers will be loading the parameters. Defining parameters in a single yaml file and loading it to the controller_manager node alone will no longer work.
8+
In order to load the parameters to the controllers properly, it is needed to use ``--param-file`` option from the spawner. This is because the controllers will now set ``use_global_arguments`` from NodeOptions to false, to avoid getting influenced by global arguments.
59

610
controller_manager
711
******************

doc/release_notes.rst

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,8 @@ For details see the controller_manager section.
2222
* A method to get node options to setup the controller node #api-breaking (`#1169 <https://github.com/ros-controls/ros2_control/pull/1169>`_)
2323
* Export state interfaces from the chainable controller #api-breaking (`#1021 <https://github.com/ros-controls/ros2_control/pull/1021>`_)
2424
* All chainable controllers must implement the method ``export_state_interfaces`` to export the state interfaces, similar to ``export_reference_interfaces`` method that is exporting the reference interfaces.
25+
* The controllers will now set ``use_global_arguments`` from NodeOptions to false, to avoid getting influenced by global arguments (Issue : `#1684 <https://github.com/ros-controls/ros2_control/issues/1684>`_) (`#1694 <https://github.com/ros-controls/ros2_control/pull/1694>`_).
26+
From now on, in order to set the parameters to the controller, the ``--param-file`` option from spawner should be used.
2527

2628
controller_manager
2729
******************

0 commit comments

Comments
 (0)