diff --git a/controller_interface/include/controller_interface/controller_interface_base.hpp b/controller_interface/include/controller_interface/controller_interface_base.hpp index e881f08aae..9eaee9f15b 100644 --- a/controller_interface/include/controller_interface/controller_interface_base.hpp +++ b/controller_interface/include/controller_interface/controller_interface_base.hpp @@ -174,12 +174,11 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy { // \note The versions conditioning is added here to support the source-compatibility with Humble #if RCLCPP_VERSION_MAJOR >= 21 - return rclcpp::NodeOptions().enable_logger_service(true).use_global_arguments(false); + return rclcpp::NodeOptions().enable_logger_service(true); #else return rclcpp::NodeOptions() .allow_undeclared_parameters(true) - .automatically_declare_parameters_from_overrides(true) - .use_global_arguments(false); + .automatically_declare_parameters_from_overrides(true); #endif } diff --git a/controller_manager/controller_manager/controller_manager_services.py b/controller_manager/controller_manager/controller_manager_services.py index 7b0f726d68..a09be5d14b 100644 --- a/controller_manager/controller_manager/controller_manager_services.py +++ b/controller_manager/controller_manager/controller_manager_services.py @@ -312,7 +312,7 @@ def set_controller_parameters_from_param_file( if parameter_file: spawner_namespace = namespace if namespace else node.get_namespace() set_controller_parameters( - node, controller_manager_name, controller_name, "param_file", parameter_file + node, controller_manager_name, controller_name, "params_file", parameter_file ) controller_type = get_parameter_from_param_file( diff --git a/controller_manager/src/controller_manager.cpp b/controller_manager/src/controller_manager.cpp index 541fc57d02..734596f8bd 100644 --- a/controller_manager/src/controller_manager.cpp +++ b/controller_manager/src/controller_manager.cpp @@ -2843,6 +2843,7 @@ rclcpp::NodeOptions ControllerManager::determine_controller_node_options( } controller_node_options = controller_node_options.arguments(node_options_arguments); + controller_node_options.use_global_arguments(false); return controller_node_options; } diff --git a/doc/migration.rst b/doc/migration.rst index 68359f072f..f24f338e52 100644 --- a/doc/migration.rst +++ b/doc/migration.rst @@ -2,6 +2,10 @@ Iron to Jazzy ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +controller_interface +******************** +* The changes from `(PR #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. + 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. controller_manager ****************** diff --git a/doc/release_notes.rst b/doc/release_notes.rst index caa28ca9d0..fa393d72ff 100644 --- a/doc/release_notes.rst +++ b/doc/release_notes.rst @@ -22,6 +22,8 @@ For details see the controller_manager section. * A method to get node options to setup the controller node #api-breaking (`#1169 `_) * Export state interfaces from the chainable controller #api-breaking (`#1021 `_) * 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. +* The controllers will now set ``use_global_arguments`` from NodeOptions to false, to avoid getting influenced by global arguments (Issue : `#1684 `_) (`#1694 `_). + From now on, in order to set the parameters to the controller, the ``--param-file`` option from spawner should be used. controller_manager ******************