Skip to content

Commit

Permalink
Avoid using the global arguments for internal controller nodes (#1694)
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor committed Aug 19, 2024
1 parent 079392b commit 4498d25
Show file tree
Hide file tree
Showing 2 changed files with 12 additions and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -174,11 +174,12 @@ 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);
return rclcpp::NodeOptions().enable_logger_service(true).use_global_arguments(false);
#else
return rclcpp::NodeOptions()
.allow_undeclared_parameters(true)
.automatically_declare_parameters_from_overrides(true);
.automatically_declare_parameters_from_overrides(true)
.use_global_arguments(false);
#endif
}

Expand Down
13 changes: 9 additions & 4 deletions controller_interface/test/test_controller_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,8 @@

#include <gmock/gmock.h>
#include <memory>
#include <string>
#include <vector>

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

TestableControllerInterface controller;
// initialize, create node
const auto node_options = controller.define_custom_node_options();
auto node_options = controller.define_custom_node_options();
std::vector<std::string> node_options_arguments = node_options.arguments();
node_options_arguments.push_back("--ros-args");
node_options_arguments.push_back("-p");
node_options_arguments.push_back("update_rate:=2812");
node_options = node_options.arguments(node_options_arguments);
ASSERT_EQ(
controller.init(TEST_CONTROLLER_NAME, "", 1.0, "", node_options),
controller_interface::return_type::OK);
Expand Down

0 comments on commit 4498d25

Please sign in to comment.