Skip to content

Commit 4498d25

Browse files
authored
Avoid using the global arguments for internal controller nodes (#1694)
1 parent 079392b commit 4498d25

File tree

2 files changed

+12
-6
lines changed

2 files changed

+12
-6
lines changed

controller_interface/include/controller_interface/controller_interface_base.hpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -174,11 +174,12 @@ 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);
177+
return rclcpp::NodeOptions().enable_logger_service(true).use_global_arguments(false);
178178
#else
179179
return rclcpp::NodeOptions()
180180
.allow_undeclared_parameters(true)
181-
.automatically_declare_parameters_from_overrides(true);
181+
.automatically_declare_parameters_from_overrides(true)
182+
.use_global_arguments(false);
182183
#endif
183184
}
184185

controller_interface/test/test_controller_interface.cpp

Lines changed: 9 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,8 @@
1616

1717
#include <gmock/gmock.h>
1818
#include <memory>
19+
#include <string>
20+
#include <vector>
1921

2022
#include "rclcpp/executor_options.hpp"
2123
#include "rclcpp/executors/multi_threaded_executor.hpp"
@@ -57,13 +59,16 @@ TEST(TestableControllerInterface, init)
5759
TEST(TestableControllerInterface, setting_update_rate_in_configure)
5860
{
5961
// mocks the declaration of overrides parameters in a yaml file
60-
char const * const argv[] = {"", "--ros-args", "-p", "update_rate:=2812"};
61-
int argc = arrlen(argv);
62-
rclcpp::init(argc, argv);
62+
rclcpp::init(0, nullptr);
6363

6464
TestableControllerInterface controller;
6565
// initialize, create node
66-
const auto node_options = controller.define_custom_node_options();
66+
auto node_options = controller.define_custom_node_options();
67+
std::vector<std::string> node_options_arguments = node_options.arguments();
68+
node_options_arguments.push_back("--ros-args");
69+
node_options_arguments.push_back("-p");
70+
node_options_arguments.push_back("update_rate:=2812");
71+
node_options = node_options.arguments(node_options_arguments);
6772
ASSERT_EQ(
6873
controller.init(TEST_CONTROLLER_NAME, "", 1.0, "", node_options),
6974
controller_interface::return_type::OK);

0 commit comments

Comments
 (0)