From 51aee9b000d2a57547517ada88fbeb2409a61909 Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Mon, 19 Aug 2024 10:45:57 +0200 Subject: [PATCH] Fix controller interface global parameter setting test --- .../test/test_controller_interface.cpp | 13 +++++++++---- 1 file changed, 9 insertions(+), 4 deletions(-) diff --git a/controller_interface/test/test_controller_interface.cpp b/controller_interface/test/test_controller_interface.cpp index 03838b1a2e..f5c0a6b3de 100644 --- a/controller_interface/test/test_controller_interface.cpp +++ b/controller_interface/test/test_controller_interface.cpp @@ -16,6 +16,8 @@ #include #include +#include +#include #include "rclcpp/executor_options.hpp" #include "rclcpp/executors/multi_threaded_executor.hpp" @@ -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 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);