From 63dafed98f5f442fd17a1dcc56c5659f84b10978 Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Wed, 15 Nov 2023 22:26:09 +0100 Subject: [PATCH] update tests to use the new get_node_options API --- .../test/test_controller_with_options.hpp | 15 +++++++++------ .../test_controller_failed_init.cpp | 7 ------- .../test_controller_failed_init.hpp | 16 +++++++--------- 3 files changed, 16 insertions(+), 22 deletions(-) diff --git a/controller_interface/test/test_controller_with_options.hpp b/controller_interface/test/test_controller_with_options.hpp index 892ec56f9dd..480b85291bd 100644 --- a/controller_interface/test/test_controller_with_options.hpp +++ b/controller_interface/test/test_controller_with_options.hpp @@ -41,13 +41,9 @@ class ControllerWithOptions : public controller_interface::ControllerInterface controller_interface::return_type init( const std::string & controller_name, const std::string & urdf, - const std::string & namespace_ = "", - const rclcpp::NodeOptions & node_options = - rclcpp::NodeOptions() - .allow_undeclared_parameters(true) - .automatically_declare_parameters_from_overrides(true)) override + const std::string & namespace_ = "") override { - ControllerInterface::init(controller_name, urdf, namespace_, node_options); + ControllerInterface::init(controller_name, urdf, namespace_); switch (on_init()) { @@ -68,6 +64,13 @@ class ControllerWithOptions : public controller_interface::ControllerInterface } } + rclcpp::NodeOptions get_node_options() const override + { + return rclcpp::NodeOptions() + .allow_undeclared_parameters(true) + .automatically_declare_parameters_from_overrides(true); + } + controller_interface::InterfaceConfiguration command_interface_configuration() const override { return controller_interface::InterfaceConfiguration{ diff --git a/controller_manager/test/test_controller_failed_init/test_controller_failed_init.cpp b/controller_manager/test/test_controller_failed_init/test_controller_failed_init.cpp index ba762573c72..1b2276bf3ca 100644 --- a/controller_manager/test/test_controller_failed_init/test_controller_failed_init.cpp +++ b/controller_manager/test/test_controller_failed_init/test_controller_failed_init.cpp @@ -31,13 +31,6 @@ TestControllerFailedInit::on_init() return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::FAILURE; } -controller_interface::return_type TestControllerFailedInit::init( - const std::string & /* controller_name */, const std::string & /* urdf */, - const std::string & /*namespace_*/, const rclcpp::NodeOptions & /*node_options*/) -{ - return controller_interface::return_type::ERROR; -} - controller_interface::return_type TestControllerFailedInit::update( const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) { diff --git a/controller_manager/test/test_controller_failed_init/test_controller_failed_init.hpp b/controller_manager/test/test_controller_failed_init/test_controller_failed_init.hpp index 69530e40b00..32b2f7a221e 100644 --- a/controller_manager/test/test_controller_failed_init/test_controller_failed_init.hpp +++ b/controller_manager/test/test_controller_failed_init/test_controller_failed_init.hpp @@ -38,21 +38,19 @@ class TestControllerFailedInit : public controller_interface::ControllerInterfac CONTROLLER_MANAGER_PUBLIC virtual ~TestControllerFailedInit() = default; - CONTROLLER_INTERFACE_PUBLIC - controller_interface::return_type init( - const std::string & controller_name, const std::string & urdf, - const std::string & namespace_ = "", - const rclcpp::NodeOptions & node_options = - rclcpp::NodeOptions() - .allow_undeclared_parameters(true) - .automatically_declare_parameters_from_overrides(true)) override; - controller_interface::InterfaceConfiguration command_interface_configuration() const override { return controller_interface::InterfaceConfiguration{ controller_interface::interface_configuration_type::NONE}; } + rclcpp::NodeOptions get_node_options() const override + { + return rclcpp::NodeOptions() + .allow_undeclared_parameters(true) + .automatically_declare_parameters_from_overrides(true); + } + controller_interface::InterfaceConfiguration state_interface_configuration() const override { return controller_interface::InterfaceConfiguration{