Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

get_parameters_service_ should return empty if allow_undeclared_ is false #1514

Merged
merged 5 commits into from
Mar 22, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
21 changes: 11 additions & 10 deletions rclcpp/src/rclcpp/parameter_service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,12 +41,13 @@ ParameterService::ParameterService(
const std::shared_ptr<rcl_interfaces::srv::GetParameters::Request> request,
std::shared_ptr<rcl_interfaces::srv::GetParameters::Response> 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_DEBUG(rclcpp::get_logger("rclcpp"), "Failed to get parameters: %s", ex.what());
}
},
qos_profile, nullptr);
Expand All @@ -67,7 +68,7 @@ ParameterService::ParameterService(
return static_cast<rclcpp::ParameterType>(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);
Expand All @@ -88,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();
}
Expand Down Expand Up @@ -116,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";
Expand All @@ -136,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);
Expand Down
244 changes: 238 additions & 6 deletions rclcpp/test/rclcpp/test_parameter_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<rclcpp::AsyncParametersClient>(node_with_option);
bool callback_called = false;
auto callback = [&callback_called](std::shared_future<std::vector<rclcpp::ParameterType>> result)
{
if (result.valid() && result.get().size() == 1 &&
result.get()[0] == rclcpp::PARAMETER_NOT_SET)
{
callback_called = true;
}
};
std::vector<std::string> names{"foo"};
std::shared_future<std::vector<rclcpp::ParameterType>> 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
*/
Expand All @@ -226,7 +250,8 @@ TEST_F(TestParameterClient, async_parameter_get_parameters) {
bool callback_called = false;
auto callback = [&callback_called](std::shared_future<std::vector<rclcpp::Parameter>> 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;
}
};
Expand All @@ -239,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<rclcpp::AsyncParametersClient>(node_with_option);
bool callback_called = false;
auto callback = [&callback_called](std::shared_future<std::vector<rclcpp::Parameter>> result)
{
if (result.valid() && result.get().size() == 1 && result.get()[0].get_name() == "foo") {
callback_called = true;
}
};
std::vector<std::string> names{"foo"};
std::shared_future<std::vector<rclcpp::Parameter>> 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
*/
Expand Down Expand Up @@ -292,12 +339,197 @@ 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<rclcpp::SyncParametersClient>(node);
std::vector<std::string> names{"foo"};
std::vector<rclcpp::ParameterType> 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<std::string> names{"none"};
std::vector<rclcpp::ParameterType> parameter_types =
synchronous_client->get_parameter_types(names, 10s);
ASSERT_EQ(0u, parameter_types.size());
}

{
std::vector<std::string> names{"none", "foo", "bar"};
std::vector<rclcpp::ParameterType> parameter_types =
synchronous_client->get_parameter_types(names, 10s);
ASSERT_EQ(0u, parameter_types.size());
}

{
std::vector<std::string> names{"foo"};
std::vector<rclcpp::ParameterType> 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<std::string> names{"bar"};
std::vector<rclcpp::ParameterType> 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<std::string> names{"foo", "bar"};
std::vector<rclcpp::ParameterType> 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<rclcpp::SyncParametersClient>(node_with_option);

{
std::vector<std::string> names{"none"};
std::vector<rclcpp::ParameterType> 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<std::string> names{"none", "foo", "bar"};
std::vector<rclcpp::ParameterType> 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<std::string> names{"foo"};
std::vector<rclcpp::ParameterType> 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<std::string> names{"bar"};
std::vector<rclcpp::ParameterType> 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<std::string> names{"foo", "bar"};
std::vector<rclcpp::ParameterType> 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_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<rclcpp::SyncParametersClient>(node);

{
std::vector<std::string> names{"none"};
std::vector<rclcpp::Parameter> parameters = synchronous_client->get_parameters(names, 10s);
ASSERT_EQ(0u, parameters.size());
}

{
std::vector<std::string> names{"none", "foo", "bar"};
std::vector<rclcpp::Parameter> parameters = synchronous_client->get_parameters(names, 10s);
ASSERT_EQ(0u, parameters.size());
}

{
std::vector<std::string> names{"foo"};
std::vector<rclcpp::Parameter> 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<std::string> names{"bar"};
std::vector<rclcpp::Parameter> 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<std::string> names{"foo", "bar"};
std::vector<rclcpp::Parameter> 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<rclcpp::SyncParametersClient>(node_with_option);

{
std::vector<std::string> names{"none"};
std::vector<rclcpp::Parameter> parameters = synchronous_client->get_parameters(names, 10s);
ASSERT_EQ(1u, parameters.size());
}

{
std::vector<std::string> names{"none", "foo", "bar"};
std::vector<rclcpp::Parameter> 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<std::string> names{"foo"};
std::vector<rclcpp::Parameter> 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<std::string> names{"bar"};
std::vector<rclcpp::Parameter> 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<std::string> names{"foo", "bar"};
std::vector<rclcpp::Parameter> 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());
}
}

/*
Expand Down