From 993a431e5605b292ae034a15336ee9d47e9d946e Mon Sep 17 00:00:00 2001 From: "Tomoya.Fujita" Date: Wed, 13 Jan 2021 11:08:48 +0900 Subject: [PATCH 1/5] get_parameters_service_ should return empty if allow_undeclared_ is false. Signed-off-by: Tomoya.Fujita --- rclcpp/src/rclcpp/parameter_service.cpp | 13 +++++++------ rclcpp/test/rclcpp/test_parameter_client.cpp | 3 ++- 2 files changed, 9 insertions(+), 7 deletions(-) diff --git a/rclcpp/src/rclcpp/parameter_service.cpp b/rclcpp/src/rclcpp/parameter_service.cpp index 0cbb9667e4..203bdfc154 100644 --- a/rclcpp/src/rclcpp/parameter_service.cpp +++ b/rclcpp/src/rclcpp/parameter_service.cpp @@ -41,12 +41,13 @@ ParameterService::ParameterService( const std::shared_ptr request, std::shared_ptr response) { - for (const auto & name : request->names) { - // Default construct param to NOT_SET - rclcpp::Parameter param; - node_params->get_parameter(name, param); - // push back NOT_SET when get_parameter() call fails - response->values.push_back(param.get_value_message()); + try { + auto parameters = node_params->get_parameters(request->names); + for (const auto param : parameters) { + response->values.push_back(param.get_value_message()); + } + } catch (const rclcpp::exceptions::ParameterNotDeclaredException & ex) { + RCLCPP_WARN(rclcpp::get_logger("rclcpp"), "Failed to get parameters: %s", ex.what()); } }, qos_profile, nullptr); diff --git a/rclcpp/test/rclcpp/test_parameter_client.cpp b/rclcpp/test/rclcpp/test_parameter_client.cpp index ba7cc99c29..59a436250e 100644 --- a/rclcpp/test/rclcpp/test_parameter_client.cpp +++ b/rclcpp/test/rclcpp/test_parameter_client.cpp @@ -226,7 +226,8 @@ TEST_F(TestParameterClient, async_parameter_get_parameters) { bool callback_called = false; auto callback = [&callback_called](std::shared_future> result) { - if (result.valid() && result.get().size() == 1 && result.get()[0].get_name() == "foo") { + // 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; } }; From d0d58e9ee3bd2ef7d46dad53ac78315d47b11596 Mon Sep 17 00:00:00 2001 From: "Tomoya.Fujita" Date: Wed, 13 Jan 2021 11:19:44 +0900 Subject: [PATCH 2/5] add tests for async parameter client with allow_undeclared_ enabled Signed-off-by: Tomoya.Fujita --- rclcpp/test/rclcpp/test_parameter_client.cpp | 46 ++++++++++++++++++++ 1 file changed, 46 insertions(+) diff --git a/rclcpp/test/rclcpp/test_parameter_client.cpp b/rclcpp/test/rclcpp/test_parameter_client.cpp index 59a436250e..c8d3d49b54 100644 --- a/rclcpp/test/rclcpp/test_parameter_client.cpp +++ b/rclcpp/test/rclcpp/test_parameter_client.cpp @@ -218,6 +218,30 @@ TEST_F(TestParameterClient, async_parameter_get_parameter_types) { ASSERT_TRUE(callback_called); } +/* + Coverage for async get_parameter_types with allow_undeclared_ enabled + */ +TEST_F(TestParameterClient, async_parameter_get_parameter_types_allow_undeclared) { + auto asynchronous_client = + std::make_shared(node_with_option); + bool callback_called = false; + auto callback = [&callback_called](std::shared_future> result) + { + if (result.valid() && result.get().size() == 1 && + result.get()[0] == rclcpp::PARAMETER_NOT_SET) + { + callback_called = true; + } + }; + std::vector names{"foo"}; + std::shared_future> future = + asynchronous_client->get_parameter_types(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); + ASSERT_TRUE(callback_called); +} + /* Coverage for async get_parameters */ @@ -240,6 +264,28 @@ TEST_F(TestParameterClient, async_parameter_get_parameters) { ASSERT_TRUE(callback_called); } +/* + Coverage for async get_parameters with allow_undeclared_ enabled + */ +TEST_F(TestParameterClient, async_parameter_get_parameters_allow_undeclared) { + auto asynchronous_client = + std::make_shared(node_with_option); + bool callback_called = false; + auto callback = [&callback_called](std::shared_future> result) + { + if (result.valid() && result.get().size() == 1 && result.get()[0].get_name() == "foo") { + callback_called = true; + } + }; + std::vector names{"foo"}; + std::shared_future> future = asynchronous_client->get_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); + ASSERT_TRUE(callback_called); +} + /* Coverage for async set_parameters_atomically */ From da99c6d9b9cb709c474a186ea5a7dd760eafd80d Mon Sep 17 00:00:00 2001 From: "Tomoya.Fujita" Date: Wed, 13 Jan 2021 11:44:31 +0900 Subject: [PATCH 3/5] add coverage for sync get_parameter_types Signed-off-by: Tomoya.Fujita --- rclcpp/test/rclcpp/test_parameter_client.cpp | 97 +++++++++++++++++++- 1 file changed, 92 insertions(+), 5 deletions(-) diff --git a/rclcpp/test/rclcpp/test_parameter_client.cpp b/rclcpp/test/rclcpp/test_parameter_client.cpp index c8d3d49b54..ea0e272446 100644 --- a/rclcpp/test/rclcpp/test_parameter_client.cpp +++ b/rclcpp/test/rclcpp/test_parameter_client.cpp @@ -339,12 +339,99 @@ TEST_F(TestParameterClient, async_parameter_list_parameters) { */ TEST_F(TestParameterClient, sync_parameter_get_parameter_types) { 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->get_parameter_types(names, 10s); - ASSERT_EQ(1u, parameter_types.size()); - ASSERT_EQ(rclcpp::ParameterType::PARAMETER_INTEGER, parameter_types[0]); + + { + std::vector names{"none"}; + std::vector parameter_types = + synchronous_client->get_parameter_types(names, 10s); + ASSERT_EQ(0u, parameter_types.size()); + } + + { + std::vector names{"none", "foo", "bar"}; + std::vector parameter_types = + synchronous_client->get_parameter_types(names, 10s); + ASSERT_EQ(0u, parameter_types.size()); + } + + { + std::vector names{"foo"}; + std::vector parameter_types = + synchronous_client->get_parameter_types(names, 10s); + ASSERT_EQ(1u, parameter_types.size()); + ASSERT_EQ(rclcpp::ParameterType::PARAMETER_INTEGER, parameter_types[0]); + } + + { + std::vector names{"bar"}; + std::vector parameter_types = + synchronous_client->get_parameter_types(names, 10s); + ASSERT_EQ(1u, parameter_types.size()); + ASSERT_EQ(rclcpp::ParameterType::PARAMETER_STRING, parameter_types[0]); + } + + { + std::vector names{"foo", "bar"}; + std::vector parameter_types = + synchronous_client->get_parameter_types(names, 10s); + ASSERT_EQ(2u, parameter_types.size()); + ASSERT_EQ(rclcpp::ParameterType::PARAMETER_INTEGER, parameter_types[0]); + ASSERT_EQ(rclcpp::ParameterType::PARAMETER_STRING, parameter_types[1]); + } +} + +/* + Coverage for sync get_parameter_types with allow_undeclared_ enabled + */ +TEST_F(TestParameterClient, sync_parameter_get_parameter_types_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_types = + synchronous_client->get_parameter_types(names, 10s); + ASSERT_EQ(1u, parameter_types.size()); + ASSERT_EQ(rclcpp::ParameterType::PARAMETER_NOT_SET, parameter_types[0]); + } + + { + std::vector names{"none", "foo", "bar"}; + std::vector parameter_types = + synchronous_client->get_parameter_types(names, 10s); + ASSERT_EQ(3u, parameter_types.size()); + ASSERT_EQ(rclcpp::ParameterType::PARAMETER_NOT_SET, parameter_types[0]); + ASSERT_EQ(rclcpp::ParameterType::PARAMETER_INTEGER, parameter_types[1]); + ASSERT_EQ(rclcpp::ParameterType::PARAMETER_STRING, parameter_types[2]); + } + + { + std::vector names{"foo"}; + std::vector parameter_types = + synchronous_client->get_parameter_types(names, 10s); + ASSERT_EQ(1u, parameter_types.size()); + ASSERT_EQ(rclcpp::ParameterType::PARAMETER_INTEGER, parameter_types[0]); + } + + { + std::vector names{"bar"}; + std::vector parameter_types = + synchronous_client->get_parameter_types(names, 10s); + ASSERT_EQ(1u, parameter_types.size()); + ASSERT_EQ(rclcpp::ParameterType::PARAMETER_STRING, parameter_types[0]); + } + + { + std::vector names{"foo", "bar"}; + std::vector parameter_types = + synchronous_client->get_parameter_types(names, 10s); + ASSERT_EQ(2u, parameter_types.size()); + ASSERT_EQ(rclcpp::ParameterType::PARAMETER_INTEGER, parameter_types[0]); + ASSERT_EQ(rclcpp::ParameterType::PARAMETER_STRING, parameter_types[1]); + } } /* From 53d657f8bb460e6720ba63e2f027dbe6ed909530 Mon Sep 17 00:00:00 2001 From: "Tomoya.Fujita" Date: Wed, 13 Jan 2021 12:18:04 +0900 Subject: [PATCH 4/5] add coverage for sync get_parameters Signed-off-by: Tomoya.Fujita --- rclcpp/test/rclcpp/test_parameter_client.cpp | 98 ++++++++++++++++++++ 1 file changed, 98 insertions(+) diff --git a/rclcpp/test/rclcpp/test_parameter_client.cpp b/rclcpp/test/rclcpp/test_parameter_client.cpp index ea0e272446..c7f8ad6581 100644 --- a/rclcpp/test/rclcpp/test_parameter_client.cpp +++ b/rclcpp/test/rclcpp/test_parameter_client.cpp @@ -434,6 +434,104 @@ TEST_F(TestParameterClient, sync_parameter_get_parameter_types_allow_undeclared) } } +/* + Coverage for sync get_parameters + */ +TEST_F(TestParameterClient, sync_parameter_get_parameters) { + node->declare_parameter("foo", 4); + node->declare_parameter("bar", "this is bar"); + auto synchronous_client = std::make_shared(node); + + { + std::vector names{"none"}; + std::vector parameters = synchronous_client->get_parameters(names, 10s); + ASSERT_EQ(0u, parameters.size()); + } + + { + std::vector names{"none", "foo", "bar"}; + std::vector parameters = synchronous_client->get_parameters(names, 10s); + ASSERT_EQ(0u, parameters.size()); + } + + { + std::vector names{"foo"}; + std::vector parameters = synchronous_client->get_parameters(names, 10s); + ASSERT_EQ(1u, parameters.size()); + ASSERT_EQ("foo", parameters[0].get_name()); + ASSERT_EQ(4u, parameters[0].as_int()); + } + + { + std::vector names{"bar"}; + std::vector parameters = synchronous_client->get_parameters(names, 10s); + ASSERT_EQ(1u, parameters.size()); + ASSERT_EQ("bar", parameters[0].get_name()); + ASSERT_EQ("this is bar", parameters[0].as_string()); + } + + { + std::vector names{"foo", "bar"}; + std::vector parameters = synchronous_client->get_parameters(names, 10s); + ASSERT_EQ(2u, parameters.size()); + ASSERT_EQ("foo", parameters[0].get_name()); + ASSERT_EQ(4u, parameters[0].as_int()); + ASSERT_EQ("bar", parameters[1].get_name()); + ASSERT_EQ("this is bar", parameters[1].as_string()); + } +} + +/* + Coverage for sync get_parameters with allow_undeclared_ enabled + */ +TEST_F(TestParameterClient, sync_parameter_get_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 parameters = synchronous_client->get_parameters(names, 10s); + ASSERT_EQ(1u, parameters.size()); + } + + { + std::vector names{"none", "foo", "bar"}; + std::vector parameters = synchronous_client->get_parameters(names, 10s); + ASSERT_EQ(3u, parameters.size()); + ASSERT_EQ("foo", parameters[1].get_name()); + ASSERT_EQ(4u, parameters[1].as_int()); + ASSERT_EQ("bar", parameters[2].get_name()); + ASSERT_EQ("this is bar", parameters[2].as_string()); + } + + { + std::vector names{"foo"}; + std::vector parameters = synchronous_client->get_parameters(names, 10s); + ASSERT_EQ(1u, parameters.size()); + ASSERT_EQ("foo", parameters[0].get_name()); + ASSERT_EQ(4u, parameters[0].as_int()); + } + + { + std::vector names{"bar"}; + std::vector parameters = synchronous_client->get_parameters(names, 10s); + ASSERT_EQ(1u, parameters.size()); + ASSERT_EQ("bar", parameters[0].get_name()); + ASSERT_EQ("this is bar", parameters[0].as_string()); + } + + { + std::vector names{"foo", "bar"}; + std::vector parameters = synchronous_client->get_parameters(names, 10s); + ASSERT_EQ(2u, parameters.size()); + ASSERT_EQ("foo", parameters[0].get_name()); + ASSERT_EQ(4u, parameters[0].as_int()); + ASSERT_EQ("bar", parameters[1].get_name()); + ASSERT_EQ("this is bar", parameters[1].as_string()); + } +} + /* Coverage for async describe_parameters */ From 2c3fc466d4debad14587cd314c8f86a0527aba7d Mon Sep 17 00:00:00 2001 From: "Tomoya.Fujita" Date: Tue, 19 Jan 2021 23:00:17 +0900 Subject: [PATCH 5/5] change warnings into debug information since node does not malfunction. Signed-off-by: Tomoya.Fujita --- rclcpp/src/rclcpp/parameter_service.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/rclcpp/src/rclcpp/parameter_service.cpp b/rclcpp/src/rclcpp/parameter_service.cpp index 203bdfc154..a766696f64 100644 --- a/rclcpp/src/rclcpp/parameter_service.cpp +++ b/rclcpp/src/rclcpp/parameter_service.cpp @@ -47,7 +47,7 @@ ParameterService::ParameterService( response->values.push_back(param.get_value_message()); } } catch (const rclcpp::exceptions::ParameterNotDeclaredException & ex) { - RCLCPP_WARN(rclcpp::get_logger("rclcpp"), "Failed to get parameters: %s", ex.what()); + RCLCPP_DEBUG(rclcpp::get_logger("rclcpp"), "Failed to get parameters: %s", ex.what()); } }, qos_profile, nullptr); @@ -68,7 +68,7 @@ ParameterService::ParameterService( return static_cast(type); }); } catch (const rclcpp::exceptions::ParameterNotDeclaredException & ex) { - RCLCPP_WARN(rclcpp::get_logger("rclcpp"), "Failed to get parameter types: %s", ex.what()); + RCLCPP_DEBUG(rclcpp::get_logger("rclcpp"), "Failed to get parameter types: %s", ex.what()); } }, qos_profile, nullptr); @@ -89,7 +89,7 @@ ParameterService::ParameterService( result = node_params->set_parameters_atomically( {rclcpp::Parameter::from_parameter_msg(p)}); } catch (const rclcpp::exceptions::ParameterNotDeclaredException & ex) { - RCLCPP_WARN(rclcpp::get_logger("rclcpp"), "Failed to set parameter: %s", ex.what()); + RCLCPP_DEBUG(rclcpp::get_logger("rclcpp"), "Failed to set parameter: %s", ex.what()); result.successful = false; result.reason = ex.what(); } @@ -117,7 +117,7 @@ ParameterService::ParameterService( auto result = node_params->set_parameters_atomically(pvariants); response->result = result; } catch (const rclcpp::exceptions::ParameterNotDeclaredException & ex) { - RCLCPP_WARN( + RCLCPP_DEBUG( rclcpp::get_logger("rclcpp"), "Failed to set parameters atomically: %s", ex.what()); response->result.successful = false; response->result.reason = "One or more parameters were not declared before setting"; @@ -137,7 +137,7 @@ ParameterService::ParameterService( auto descriptors = node_params->describe_parameters(request->names); response->descriptors = descriptors; } catch (const rclcpp::exceptions::ParameterNotDeclaredException & ex) { - RCLCPP_WARN(rclcpp::get_logger("rclcpp"), "Failed to describe parameters: %s", ex.what()); + RCLCPP_DEBUG(rclcpp::get_logger("rclcpp"), "Failed to describe parameters: %s", ex.what()); } }, qos_profile, nullptr);