From 8f58fb43401a2a07e0b7a966e96b83fc32b4f78d Mon Sep 17 00:00:00 2001 From: stevemacenski Date: Tue, 21 Nov 2023 14:22:42 -0800 Subject: [PATCH] removing API with rclcpp new version --- .../bt_action_server_impl.hpp | 2 +- nav2_util/include/nav2_util/node_utils.hpp | 19 ----------- nav2_util/test/test_node_utils.cpp | 32 ------------------- 3 files changed, 1 insertion(+), 52 deletions(-) diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp index cd089692b87..49574999c40 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp @@ -135,7 +135,7 @@ bool BtActionServer::on_configure() node, "robot_base_frame", rclcpp::ParameterValue(std::string("base_link"))); nav2_util::declare_parameter_if_not_declared( node, "transform_tolerance", rclcpp::ParameterValue(0.1)); - nav2_util::copy_all_parameters(node, client_node_); + rclcpp::copy_all_parameter_values(node, client_node_); // set the timeout in seconds for the action server to discard goal handles if not finished double action_server_result_timeout; diff --git a/nav2_util/include/nav2_util/node_utils.hpp b/nav2_util/include/nav2_util/node_utils.hpp index a6a511a89c5..99570224add 100644 --- a/nav2_util/include/nav2_util/node_utils.hpp +++ b/nav2_util/include/nav2_util/node_utils.hpp @@ -153,25 +153,6 @@ std::string get_plugin_type_param( return plugin_type; } -/** - * @brief A method to copy all parameters from one node (parent) to another (child). - * May throw parameter exceptions in error conditions - * @param parent Node to copy parameters from - * @param child Node to copy parameters to - */ -template -void copy_all_parameters(const NodeT1 & parent, const NodeT2 & child) -{ - using Parameters = std::vector; - std::vector param_names = parent->list_parameters({}, 0).names; - Parameters params = parent->get_parameters(param_names); - for (Parameters::const_iterator iter = params.begin(); iter != params.end(); ++iter) { - if (!child->has_parameter(iter->get_name())) { - child->declare_parameter(iter->get_name(), iter->get_parameter_value()); - } - } -} - /** * @brief Sets the caller thread to have a soft-realtime prioritization by * increasing the priority level of the host thread. diff --git a/nav2_util/test/test_node_utils.cpp b/nav2_util/test/test_node_utils.cpp index ff85d2bd415..bf945276358 100644 --- a/nav2_util/test/test_node_utils.cpp +++ b/nav2_util/test/test_node_utils.cpp @@ -94,35 +94,3 @@ TEST(GetPluginTypeParam, GetPluginTypeParam) ASSERT_EQ(get_plugin_type_param(node, "Foo"), "bar"); EXPECT_THROW(get_plugin_type_param(node, "Waldo"), std::runtime_error); } - -TEST(TestParamCopying, TestParamCopying) -{ - auto node1 = std::make_shared("test_node1"); - auto node2 = std::make_shared("test_node2"); - - // Tests for (1) multiple types, (2) recursion, (3) overriding values - node1->declare_parameter("Foo1", rclcpp::ParameterValue(std::string(("bar1")))); - node1->declare_parameter("Foo2", rclcpp::ParameterValue(0.123)); - node1->declare_parameter("Foo", rclcpp::ParameterValue(std::string(("bar")))); - node1->declare_parameter("Foo.bar", rclcpp::ParameterValue(std::string(("steve")))); - node2->declare_parameter("Foo", rclcpp::ParameterValue(std::string(("barz2")))); - - // Show Node2 is empty of Node1's parameters, but contains its own - EXPECT_FALSE(node2->has_parameter("Foo1")); - EXPECT_FALSE(node2->has_parameter("Foo2")); - EXPECT_FALSE(node2->has_parameter("Foo.bar")); - EXPECT_TRUE(node2->has_parameter("Foo")); - EXPECT_EQ(node2->get_parameter("Foo").as_string(), std::string("barz2")); - - nav2_util::copy_all_parameters(node1, node2); - - // Test new parameters exist, of expected value, and original param is not overridden - EXPECT_TRUE(node2->has_parameter("Foo1")); - EXPECT_EQ(node2->get_parameter("Foo1").as_string(), std::string("bar1")); - EXPECT_TRUE(node2->has_parameter("Foo2")); - EXPECT_EQ(node2->get_parameter("Foo2").as_double(), 0.123); - EXPECT_TRUE(node2->has_parameter("Foo.bar")); - EXPECT_EQ(node2->get_parameter("Foo.bar").as_string(), std::string("steve")); - EXPECT_TRUE(node2->has_parameter("Foo")); - EXPECT_EQ(node2->get_parameter("Foo").as_string(), std::string("barz2")); -}