From 49c8aec6efa5879d5dac69fde72ef4c2bb0f7406 Mon Sep 17 00:00:00 2001 From: "Tomoya.Fujita" Date: Thu, 12 Nov 2020 20:29:24 +0900 Subject: [PATCH 1/5] support describe_parameters methods to parameter client. Signed-off-by: Tomoya.Fujita --- rclcpp/include/rclcpp/parameter_client.hpp | 12 +++++ rclcpp/src/rclcpp/parameter_client.cpp | 51 ++++++++++++++++++++ rclcpp/test/rclcpp/test_parameter_client.cpp | 40 +++++++++++++++ 3 files changed, 103 insertions(+) diff --git a/rclcpp/include/rclcpp/parameter_client.hpp b/rclcpp/include/rclcpp/parameter_client.hpp index 8eb3b013e2..923c04f75a 100644 --- a/rclcpp/include/rclcpp/parameter_client.hpp +++ b/rclcpp/include/rclcpp/parameter_client.hpp @@ -120,6 +120,14 @@ class AsyncParametersClient void(std::shared_future>) > callback = nullptr); + RCLCPP_PUBLIC + std::shared_future> + describe_parameters( + const std::vector & names, + std::function< + void(std::shared_future>) + > callback = nullptr); + RCLCPP_PUBLIC std::shared_future> get_parameter_types( @@ -378,6 +386,10 @@ class SyncParametersClient ); } + RCLCPP_PUBLIC + std::vector + describe_parameters(const std::vector & parameter_names); + RCLCPP_PUBLIC std::vector get_parameter_types(const std::vector & parameter_names); diff --git a/rclcpp/src/rclcpp/parameter_client.cpp b/rclcpp/src/rclcpp/parameter_client.cpp index 82434f98bf..76cc540391 100644 --- a/rclcpp/src/rclcpp/parameter_client.cpp +++ b/rclcpp/src/rclcpp/parameter_client.cpp @@ -144,6 +144,41 @@ AsyncParametersClient::get_parameters( return future_result; } +std::shared_future> +AsyncParametersClient::describe_parameters( + const std::vector & names, + std::function< + void(std::shared_future>) + > callback) +{ + auto promise_result = + std::make_shared>>(); + auto future_result = promise_result->get_future().share(); + + auto request = std::make_shared(); + request->names = names; + + describe_parameters_client_->async_send_request( + request, + [promise_result, future_result, callback]( + rclcpp::Client::SharedFuture cb_f) + { + std::vector descriptors; + auto & descs = cb_f.get()->descriptors; + for (auto & desc : descs) { + descriptors.push_back( + static_cast(desc)); + } + promise_result->set_value(descriptors); + if (callback != nullptr) { + callback(future_result); + } + } + ); + + return future_result; +} + std::shared_future> AsyncParametersClient::get_parameter_types( const std::vector & names, @@ -337,6 +372,22 @@ SyncParametersClient::has_parameter(const std::string & parameter_name) return vars.names.size() > 0; } +std::vector +SyncParametersClient::describe_parameters(const std::vector & parameter_names) +{ + auto f = async_parameters_client_->describe_parameters(parameter_names); + + using rclcpp::executors::spin_node_until_future_complete; + if ( + spin_node_until_future_complete( + *executor_, node_base_interface_, + f) == rclcpp::FutureReturnCode::SUCCESS) + { + return f.get(); + } + return std::vector(); +} + std::vector SyncParametersClient::get_parameter_types(const std::vector & parameter_names) { diff --git a/rclcpp/test/rclcpp/test_parameter_client.cpp b/rclcpp/test/rclcpp/test_parameter_client.cpp index 9e5bcdd437..a38a7d4145 100644 --- a/rclcpp/test/rclcpp/test_parameter_client.cpp +++ b/rclcpp/test/rclcpp/test_parameter_client.cpp @@ -291,3 +291,43 @@ TEST_F(TestParameterClient, sync_parameter_get_parameter_types) { ASSERT_EQ(1u, parameter_types.size()); ASSERT_EQ(rclcpp::ParameterType::PARAMETER_INTEGER, parameter_types[0]); } + +/* + Coverage for async describe_parameters + */ +TEST_F(TestParameterClient, async_parameter_describe_parameters) { + auto asynchronous_client = std::make_shared(node); + bool callback_called = false; + auto callback = [&callback_called]( + std::shared_future> result) + { + // We expect the result to be empty since we tried to get a parameter that didn't exist. + if (result.valid() && result.get().size() == 0) { + callback_called = true; + } + }; + std::vector names{"foo"}; + std::shared_future> future = + asynchronous_client->describe_parameters(names, callback); + auto return_code = rclcpp::spin_until_future_complete( + node, future, std::chrono::milliseconds(100)); + ASSERT_EQ(rclcpp::FutureReturnCode::SUCCESS, return_code); + ASSERT_TRUE(callback_called); +} + +/* + Coverage for sync describe_parameters + */ +TEST_F(TestParameterClient, sync_parameter_describe_parameters) { + node->declare_parameter("foo", 4); + auto synchronous_client = std::make_shared(node); + std::vector names{"foo"}; + std::vector parameter_types = + synchronous_client->describe_parameters(names); + ASSERT_EQ(1u, parameter_types.size()); + ASSERT_EQ("foo", parameter_types[0].name); + ASSERT_EQ(rclcpp::ParameterType::PARAMETER_INTEGER, parameter_types[0].type); + ASSERT_EQ("", parameter_types[0].description); + ASSERT_EQ("", parameter_types[0].additional_constraints); + ASSERT_FALSE(parameter_types[0].read_only); +} From 7f2c3134ceeb3d685bafd0d191b44f7842c7fe4e Mon Sep 17 00:00:00 2001 From: "Tomoya.Fujita" Date: Fri, 13 Nov 2020 06:07:11 +0900 Subject: [PATCH 2/5] add test scenarios to describe_parameters. Signed-off-by: Tomoya.Fujita --- rclcpp/include/rclcpp/parameter_client.hpp | 2 + rclcpp/src/rclcpp/parameter_client.cpp | 15 +- rclcpp/test/rclcpp/test_parameter_client.cpp | 136 +++++++++++++++---- 3 files changed, 118 insertions(+), 35 deletions(-) diff --git a/rclcpp/include/rclcpp/parameter_client.hpp b/rclcpp/include/rclcpp/parameter_client.hpp index 923c04f75a..f8240de989 100644 --- a/rclcpp/include/rclcpp/parameter_client.hpp +++ b/rclcpp/include/rclcpp/parameter_client.hpp @@ -15,6 +15,8 @@ #ifndef RCLCPP__PARAMETER_CLIENT_HPP_ #define RCLCPP__PARAMETER_CLIENT_HPP_ +#include +#include #include #include #include diff --git a/rclcpp/src/rclcpp/parameter_client.cpp b/rclcpp/src/rclcpp/parameter_client.cpp index 76cc540391..25bae27826 100644 --- a/rclcpp/src/rclcpp/parameter_client.cpp +++ b/rclcpp/src/rclcpp/parameter_client.cpp @@ -164,10 +164,9 @@ AsyncParametersClient::describe_parameters( rclcpp::Client::SharedFuture cb_f) { std::vector descriptors; - auto & descs = cb_f.get()->descriptors; - for (auto & desc : descs) { - descriptors.push_back( - static_cast(desc)); + std::vector & descs = cb_f.get()->descriptors; + for (rcl_interfaces::msg::ParameterDescriptor & desc : descs) { + descriptors.push_back(desc); } promise_result->set_value(descriptors); if (callback != nullptr) { @@ -378,11 +377,9 @@ SyncParametersClient::describe_parameters(const std::vector & param auto f = async_parameters_client_->describe_parameters(parameter_names); using rclcpp::executors::spin_node_until_future_complete; - if ( - spin_node_until_future_complete( - *executor_, node_base_interface_, - f) == rclcpp::FutureReturnCode::SUCCESS) - { + rclcpp::FutureReturnCode future = + spin_node_until_future_complete(*executor_, node_base_interface_, f); + if (future == rclcpp::FutureReturnCode::SUCCESS) { return f.get(); } return std::vector(); diff --git a/rclcpp/test/rclcpp/test_parameter_client.cpp b/rclcpp/test/rclcpp/test_parameter_client.cpp index a38a7d4145..f58574c947 100644 --- a/rclcpp/test/rclcpp/test_parameter_client.cpp +++ b/rclcpp/test/rclcpp/test_parameter_client.cpp @@ -296,38 +296,122 @@ TEST_F(TestParameterClient, sync_parameter_get_parameter_types) { Coverage for async describe_parameters */ TEST_F(TestParameterClient, async_parameter_describe_parameters) { + node->declare_parameter("foo", 4); + node->declare_parameter("bar", "this is bar"); auto asynchronous_client = std::make_shared(node); - bool callback_called = false; - auto callback = [&callback_called]( - std::shared_future> result) - { - // We expect the result to be empty since we tried to get a parameter that didn't exist. - if (result.valid() && result.get().size() == 0) { - callback_called = true; - } - }; - std::vector names{"foo"}; - std::shared_future> future = - asynchronous_client->describe_parameters(names, callback); - auto return_code = rclcpp::spin_until_future_complete( - node, future, std::chrono::milliseconds(100)); - ASSERT_EQ(rclcpp::FutureReturnCode::SUCCESS, return_code); - ASSERT_TRUE(callback_called); -} + { + bool callback_called = false; + auto callback = [&callback_called]( + std::shared_future> result) + { + // We expect the result to be empty since we tried to get a parameter that didn't exist. + if (result.valid() && result.get().size() == 0) { + callback_called = true; + } + }; + std::vector names{"none"}; + std::shared_future> future = + asynchronous_client->describe_parameters(names, callback); + auto return_code = rclcpp::spin_until_future_complete( + node, future, std::chrono::milliseconds(100)); + ASSERT_EQ(rclcpp::FutureReturnCode::SUCCESS, return_code); + ASSERT_TRUE(callback_called); + } + + { + bool callback_called = false; + auto callback = [&callback_called]( + std::shared_future> result) + { + if (result.valid() && result.get().size() == 1) { + callback_called = true; + } + }; + std::vector names{"foo"}; + std::shared_future> future = + asynchronous_client->describe_parameters(names, callback); + auto return_code = rclcpp::spin_until_future_complete( + node, future, std::chrono::milliseconds(100)); + ASSERT_EQ(rclcpp::FutureReturnCode::SUCCESS, return_code); + std::vector parameter_descs = future.get(); + ASSERT_EQ(1u, parameter_descs.size()); + ASSERT_EQ("foo", parameter_descs[0].name); + ASSERT_EQ(rclcpp::ParameterType::PARAMETER_INTEGER, parameter_descs[0].type); + ASSERT_EQ("", parameter_descs[0].description); + ASSERT_EQ("", parameter_descs[0].additional_constraints); + ASSERT_TRUE(callback_called); + } + + { + bool callback_called = false; + auto callback = [&callback_called]( + std::shared_future> result) + { + if (result.valid() && result.get().size() == 2) { + callback_called = true; + } + }; + std::vector names{"foo", "bar"}; + std::shared_future> future = + asynchronous_client->describe_parameters(names, callback); + auto return_code = rclcpp::spin_until_future_complete( + node, future, std::chrono::milliseconds(100)); + ASSERT_EQ(rclcpp::FutureReturnCode::SUCCESS, return_code); + std::vector parameter_descs = future.get(); + ASSERT_EQ(2u, parameter_descs.size()); + ASSERT_EQ("foo", parameter_descs[0].name); + ASSERT_EQ(rclcpp::ParameterType::PARAMETER_INTEGER, parameter_descs[0].type); + ASSERT_EQ("", parameter_descs[0].description); + ASSERT_EQ("", parameter_descs[0].additional_constraints); + ASSERT_EQ("bar", parameter_descs[1].name); + ASSERT_EQ(rclcpp::ParameterType::PARAMETER_STRING, parameter_descs[1].type); + ASSERT_EQ("", parameter_descs[1].description); + ASSERT_EQ("", parameter_descs[1].additional_constraints); + ASSERT_TRUE(callback_called); + } +} /* Coverage for sync describe_parameters */ TEST_F(TestParameterClient, sync_parameter_describe_parameters) { node->declare_parameter("foo", 4); + node->declare_parameter("bar", "this is bar"); auto synchronous_client = std::make_shared(node); - std::vector names{"foo"}; - std::vector parameter_types = - synchronous_client->describe_parameters(names); - ASSERT_EQ(1u, parameter_types.size()); - ASSERT_EQ("foo", parameter_types[0].name); - ASSERT_EQ(rclcpp::ParameterType::PARAMETER_INTEGER, parameter_types[0].type); - ASSERT_EQ("", parameter_types[0].description); - ASSERT_EQ("", parameter_types[0].additional_constraints); - ASSERT_FALSE(parameter_types[0].read_only); + + { + std::vector names{"none"}; + std::vector parameter_descs = + synchronous_client->describe_parameters(names); + ASSERT_EQ(0u, parameter_descs.size()); + } + + { + std::vector names{"foo"}; + std::vector parameter_descs = + synchronous_client->describe_parameters(names); + ASSERT_EQ(1u, parameter_descs.size()); + ASSERT_EQ("foo", parameter_descs[0].name); + ASSERT_EQ(rclcpp::ParameterType::PARAMETER_INTEGER, parameter_descs[0].type); + ASSERT_EQ("", parameter_descs[0].description); + ASSERT_EQ("", parameter_descs[0].additional_constraints); + ASSERT_FALSE(parameter_descs[0].read_only); + } + + { + std::vector names{"foo", "bar"}; + std::vector parameter_descs = + synchronous_client->describe_parameters(names); + ASSERT_EQ(2u, parameter_descs.size()); + ASSERT_EQ("foo", parameter_descs[0].name); + ASSERT_EQ(rclcpp::ParameterType::PARAMETER_INTEGER, parameter_descs[0].type); + ASSERT_EQ("", parameter_descs[0].description); + ASSERT_EQ("", parameter_descs[0].additional_constraints); + ASSERT_FALSE(parameter_descs[0].read_only); + ASSERT_EQ("bar", parameter_descs[1].name); + ASSERT_EQ(rclcpp::ParameterType::PARAMETER_STRING, parameter_descs[1].type); + ASSERT_EQ("", parameter_descs[1].description); + ASSERT_EQ("", parameter_descs[1].additional_constraints); + ASSERT_FALSE(parameter_descs[1].read_only); + } } From 1b0ca9909a85ca44263a58b5eafaefee08a13297 Mon Sep 17 00:00:00 2001 From: "Tomoya.Fujita" Date: Tue, 17 Nov 2020 10:06:22 +0900 Subject: [PATCH 3/5] add more test scenarios for test_parameter_client. Signed-off-by: Tomoya.Fujita --- rclcpp/test/rclcpp/test_parameter_client.cpp | 52 ++++++++++++++++++++ 1 file changed, 52 insertions(+) diff --git a/rclcpp/test/rclcpp/test_parameter_client.cpp b/rclcpp/test/rclcpp/test_parameter_client.cpp index f58574c947..e090455be3 100644 --- a/rclcpp/test/rclcpp/test_parameter_client.cpp +++ b/rclcpp/test/rclcpp/test_parameter_client.cpp @@ -343,6 +343,44 @@ TEST_F(TestParameterClient, async_parameter_describe_parameters) { ASSERT_TRUE(callback_called); } + { + bool callback_called = false; + auto callback = [&callback_called]( + std::shared_future> result) + { + // We expect the result to be empty since we tried to get a parameter that didn't exist. + if (result.valid() && result.get().size() == 0) { + callback_called = true; + } + }; + std::vector names{"foo", "baz"}; + std::shared_future> future = + asynchronous_client->describe_parameters(names, callback); + auto return_code = rclcpp::spin_until_future_complete( + node, future, std::chrono::milliseconds(100)); + ASSERT_EQ(rclcpp::FutureReturnCode::SUCCESS, return_code); + ASSERT_TRUE(callback_called); + } + + { + bool callback_called = false; + auto callback = [&callback_called]( + std::shared_future> result) + { + // We expect the result to be empty since we tried to get a parameter that didn't exist. + if (result.valid() && result.get().size() == 0) { + callback_called = true; + } + }; + std::vector names{"baz", "foo"}; + std::shared_future> future = + asynchronous_client->describe_parameters(names, callback); + auto return_code = rclcpp::spin_until_future_complete( + node, future, std::chrono::milliseconds(100)); + ASSERT_EQ(rclcpp::FutureReturnCode::SUCCESS, return_code); + ASSERT_TRUE(callback_called); + } + { bool callback_called = false; auto callback = [&callback_called]( @@ -398,6 +436,20 @@ TEST_F(TestParameterClient, sync_parameter_describe_parameters) { ASSERT_FALSE(parameter_descs[0].read_only); } + { + std::vector names{"foo", "baz"}; + std::vector parameter_descs = + synchronous_client->describe_parameters(names); + ASSERT_EQ(0u, parameter_descs.size()); + } + + { + std::vector names{"baz", "foo"}; + std::vector parameter_descs = + synchronous_client->describe_parameters(names); + ASSERT_EQ(0u, parameter_descs.size()); + } + { std::vector names{"foo", "bar"}; std::vector parameter_descs = From 07f4b126f7bf1552648fa2ee345f93f22918448c Mon Sep 17 00:00:00 2001 From: "Tomoya.Fujita" Date: Wed, 18 Nov 2020 15:28:51 +0900 Subject: [PATCH 4/5] add test cases for describe_parameters with allow_undeclared_ enabled Signed-off-by: Tomoya.Fujita --- rclcpp/test/rclcpp/test_parameter_client.cpp | 160 +++++++++++++++++++ 1 file changed, 160 insertions(+) diff --git a/rclcpp/test/rclcpp/test_parameter_client.cpp b/rclcpp/test/rclcpp/test_parameter_client.cpp index e090455be3..e5fc83d888 100644 --- a/rclcpp/test/rclcpp/test_parameter_client.cpp +++ b/rclcpp/test/rclcpp/test_parameter_client.cpp @@ -45,14 +45,20 @@ class TestParameterClient : public ::testing::Test void SetUp() { node = std::make_shared("test_parameter_client", "/ns"); + node_with_option = + std::make_shared( + "test_parameter_client_allow_undeclare", "/ns", + rclcpp::NodeOptions().allow_undeclared_parameters(true)); } void TearDown() { node.reset(); + node_with_option.reset(); } rclcpp::Node::SharedPtr node; + rclcpp::Node::SharedPtr node_with_option; }; /* @@ -340,6 +346,7 @@ TEST_F(TestParameterClient, async_parameter_describe_parameters) { ASSERT_EQ(rclcpp::ParameterType::PARAMETER_INTEGER, parameter_descs[0].type); ASSERT_EQ("", parameter_descs[0].description); ASSERT_EQ("", parameter_descs[0].additional_constraints); + ASSERT_FALSE(parameter_descs[0].read_only); ASSERT_TRUE(callback_called); } @@ -402,10 +409,12 @@ TEST_F(TestParameterClient, async_parameter_describe_parameters) { ASSERT_EQ(rclcpp::ParameterType::PARAMETER_INTEGER, parameter_descs[0].type); ASSERT_EQ("", parameter_descs[0].description); ASSERT_EQ("", parameter_descs[0].additional_constraints); + ASSERT_FALSE(parameter_descs[0].read_only); ASSERT_EQ("bar", parameter_descs[1].name); ASSERT_EQ(rclcpp::ParameterType::PARAMETER_STRING, parameter_descs[1].type); ASSERT_EQ("", parameter_descs[1].description); ASSERT_EQ("", parameter_descs[1].additional_constraints); + ASSERT_FALSE(parameter_descs[1].read_only); ASSERT_TRUE(callback_called); } } @@ -467,3 +476,154 @@ TEST_F(TestParameterClient, sync_parameter_describe_parameters) { ASSERT_FALSE(parameter_descs[1].read_only); } } + +/* + Coverage for async describe_parameters with allow_undeclared_ enabled + */ +TEST_F(TestParameterClient, async_parameter_describe_parameters_allow_undeclared) { + node_with_option->declare_parameter("foo", 4); + node_with_option->declare_parameter("bar", "this is bar"); + auto asynchronous_client = + std::make_shared(node_with_option); + + { + bool callback_called = false; + auto callback = [&callback_called]( + std::shared_future> result) + { + // We expect the result to be defaut since we tried to get a parameter that didn't exist. + if (result.valid() && result.get().size() == 1) { + callback_called = true; + } + }; + std::vector names{"none"}; + std::shared_future> future = + asynchronous_client->describe_parameters(names, callback); + auto return_code = rclcpp::spin_until_future_complete( + node_with_option, future, std::chrono::milliseconds(100)); + ASSERT_EQ(rclcpp::FutureReturnCode::SUCCESS, return_code); + std::vector parameter_descs = future.get(); + ASSERT_EQ(1u, parameter_descs.size()); + ASSERT_EQ("none", parameter_descs[0].name); + ASSERT_EQ(rclcpp::ParameterType::PARAMETER_NOT_SET, parameter_descs[0].type); + ASSERT_EQ("", parameter_descs[0].description); + ASSERT_EQ("", parameter_descs[0].additional_constraints); + ASSERT_FALSE(parameter_descs[0].read_only); + ASSERT_TRUE(callback_called); + } + + { + bool callback_called = false; + auto callback = [&callback_called]( + std::shared_future> result) + { + if (result.valid() && result.get().size() == 2) { + callback_called = true; + } + }; + std::vector names{"foo", "baz"}; + std::shared_future> future = + asynchronous_client->describe_parameters(names, callback); + auto return_code = rclcpp::spin_until_future_complete( + node_with_option, future, std::chrono::milliseconds(100)); + ASSERT_EQ(rclcpp::FutureReturnCode::SUCCESS, return_code); + std::vector parameter_descs = future.get(); + ASSERT_EQ(2u, parameter_descs.size()); + ASSERT_EQ("foo", parameter_descs[0].name); + ASSERT_EQ(rclcpp::ParameterType::PARAMETER_INTEGER, parameter_descs[0].type); + ASSERT_EQ("", parameter_descs[0].description); + ASSERT_EQ("", parameter_descs[0].additional_constraints); + ASSERT_FALSE(parameter_descs[0].read_only); + ASSERT_EQ("baz", parameter_descs[1].name); + ASSERT_EQ(rclcpp::ParameterType::PARAMETER_NOT_SET, parameter_descs[1].type); + ASSERT_EQ("", parameter_descs[1].description); + ASSERT_EQ("", parameter_descs[1].additional_constraints); + ASSERT_FALSE(parameter_descs[1].read_only); + ASSERT_TRUE(callback_called); + } + + { + bool callback_called = false; + auto callback = [&callback_called]( + std::shared_future> result) + { + if (result.valid() && result.get().size() == 2) { + callback_called = true; + } + }; + std::vector names{"baz", "foo"}; + std::shared_future> future = + asynchronous_client->describe_parameters(names, callback); + auto return_code = rclcpp::spin_until_future_complete( + node_with_option, future, std::chrono::milliseconds(100)); + ASSERT_EQ(rclcpp::FutureReturnCode::SUCCESS, return_code); + std::vector parameter_descs = future.get(); + ASSERT_EQ(2u, parameter_descs.size()); + ASSERT_EQ("baz", parameter_descs[0].name); + ASSERT_EQ(rclcpp::ParameterType::PARAMETER_NOT_SET, parameter_descs[0].type); + ASSERT_EQ("", parameter_descs[0].description); + ASSERT_EQ("", parameter_descs[0].additional_constraints); + ASSERT_FALSE(parameter_descs[0].read_only); + ASSERT_EQ("foo", parameter_descs[1].name); + ASSERT_EQ(rclcpp::ParameterType::PARAMETER_INTEGER, parameter_descs[1].type); + ASSERT_EQ("", parameter_descs[1].description); + ASSERT_EQ("", parameter_descs[1].additional_constraints); + ASSERT_FALSE(parameter_descs[1].read_only); + ASSERT_TRUE(callback_called); + } +} +/* + Coverage for sync describe_parameters with allow_undeclared_ enabled + */ +TEST_F(TestParameterClient, sync_parameter_describe_parameters_allow_undeclared) { + node_with_option->declare_parameter("foo", 4); + node_with_option->declare_parameter("bar", "this is bar"); + auto synchronous_client = + std::make_shared(node_with_option); + + { + std::vector names{"none"}; + std::vector parameter_descs = + synchronous_client->describe_parameters(names); + ASSERT_EQ(1u, parameter_descs.size()); + ASSERT_EQ("none", parameter_descs[0].name); + ASSERT_EQ(rclcpp::ParameterType::PARAMETER_NOT_SET, parameter_descs[0].type); + ASSERT_EQ("", parameter_descs[0].description); + ASSERT_EQ("", parameter_descs[0].additional_constraints); + ASSERT_FALSE(parameter_descs[0].read_only); + } + + { + std::vector names{"foo", "baz"}; + std::vector parameter_descs = + synchronous_client->describe_parameters(names); + ASSERT_EQ(2u, parameter_descs.size()); + ASSERT_EQ("foo", parameter_descs[0].name); + ASSERT_EQ(rclcpp::ParameterType::PARAMETER_INTEGER, parameter_descs[0].type); + ASSERT_EQ("", parameter_descs[0].description); + ASSERT_EQ("", parameter_descs[0].additional_constraints); + ASSERT_FALSE(parameter_descs[0].read_only); + ASSERT_EQ("baz", parameter_descs[1].name); + ASSERT_EQ(rclcpp::ParameterType::PARAMETER_NOT_SET, parameter_descs[1].type); + ASSERT_EQ("", parameter_descs[1].description); + ASSERT_EQ("", parameter_descs[1].additional_constraints); + ASSERT_FALSE(parameter_descs[1].read_only); + } + + { + std::vector names{"baz", "foo"}; + std::vector parameter_descs = + synchronous_client->describe_parameters(names); + ASSERT_EQ(2u, parameter_descs.size()); + ASSERT_EQ("baz", parameter_descs[0].name); + ASSERT_EQ(rclcpp::ParameterType::PARAMETER_NOT_SET, parameter_descs[0].type); + ASSERT_EQ("", parameter_descs[0].description); + ASSERT_EQ("", parameter_descs[0].additional_constraints); + ASSERT_FALSE(parameter_descs[0].read_only); + ASSERT_EQ("foo", parameter_descs[1].name); + ASSERT_EQ(rclcpp::ParameterType::PARAMETER_INTEGER, parameter_descs[1].type); + ASSERT_EQ("", parameter_descs[1].description); + ASSERT_EQ("", parameter_descs[1].additional_constraints); + ASSERT_FALSE(parameter_descs[1].read_only); + } +} From bb7d1cc8af27214b35695c97f2726087fa4e0072 Mon Sep 17 00:00:00 2001 From: "Tomoya.Fujita" Date: Mon, 14 Dec 2020 09:58:18 +0900 Subject: [PATCH 5/5] minor fix, not to do unnecessary data copy. Signed-off-by: Tomoya.Fujita --- rclcpp/src/rclcpp/parameter_client.cpp | 7 +------ 1 file changed, 1 insertion(+), 6 deletions(-) diff --git a/rclcpp/src/rclcpp/parameter_client.cpp b/rclcpp/src/rclcpp/parameter_client.cpp index 25bae27826..3413f8301c 100644 --- a/rclcpp/src/rclcpp/parameter_client.cpp +++ b/rclcpp/src/rclcpp/parameter_client.cpp @@ -163,12 +163,7 @@ AsyncParametersClient::describe_parameters( [promise_result, future_result, callback]( rclcpp::Client::SharedFuture cb_f) { - std::vector descriptors; - std::vector & descs = cb_f.get()->descriptors; - for (rcl_interfaces::msg::ParameterDescriptor & desc : descs) { - descriptors.push_back(desc); - } - promise_result->set_value(descriptors); + promise_result->set_value(cb_f.get()->descriptors); if (callback != nullptr) { callback(future_result); }