Skip to content

Commit

Permalink
Get parameters that aren't set (#276)
Browse files Browse the repository at this point in the history
  • Loading branch information
sloretz authored Jun 6, 2018
1 parent 3019217 commit 8a632be
Showing 1 changed file with 17 additions and 6 deletions.
23 changes: 17 additions & 6 deletions test_rclcpp/test/parameter_fixtures.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -132,8 +132,14 @@ void verify_test_parameters(

printf("Getting nonexistent parameters\n");
// Get a few non existant parameters
for (auto & parameter : parameters_client->get_parameters({"not_foo", "not_baz"})) {
EXPECT_STREQ("There should be no matches", parameter.get_name().c_str());
{
std::vector<rclcpp::Parameter> retrieved_params =
parameters_client->get_parameters({"not_foo", "not_baz"});
ASSERT_EQ(2u, retrieved_params.size());
EXPECT_STREQ("not_foo", retrieved_params[0].get_name().c_str());
EXPECT_STREQ("not_baz", retrieved_params[1].get_name().c_str());
EXPECT_EQ(rclcpp::ParameterType::PARAMETER_NOT_SET, retrieved_params[0].get_type());
EXPECT_EQ(rclcpp::ParameterType::PARAMETER_NOT_SET, retrieved_params[1].get_type());
}

printf("Listing parameters with recursive depth\n");
Expand Down Expand Up @@ -246,10 +252,15 @@ void verify_get_parameters_async(

printf("Getting nonexistent parameters\n");
// Get a few non existant parameters
auto result3 = parameters_client->get_parameters({"not_foo", "not_baz"});
rclcpp::spin_until_future_complete(node, result3);
for (auto & parameter : result3.get()) {
EXPECT_STREQ("There should be no matches", parameter.get_name().c_str());
{
auto result3 = parameters_client->get_parameters({"not_foo", "not_baz"});
rclcpp::spin_until_future_complete(node, result3);
std::vector<rclcpp::Parameter> retrieved_params = result3.get();
ASSERT_EQ(2u, retrieved_params.size());
EXPECT_STREQ("not_foo", retrieved_params[0].get_name().c_str());
EXPECT_STREQ("not_baz", retrieved_params[1].get_name().c_str());
EXPECT_EQ(rclcpp::ParameterType::PARAMETER_NOT_SET, retrieved_params[0].get_type());
EXPECT_EQ(rclcpp::ParameterType::PARAMETER_NOT_SET, retrieved_params[1].get_type());
}

printf("Listing parameters with recursive depth\n");
Expand Down

0 comments on commit 8a632be

Please sign in to comment.