Skip to content
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
28 changes: 14 additions & 14 deletions test_rclcpp/test/parameter_fixtures.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,13 +33,13 @@ void set_test_parameters(
printf("Setting parameters\n");
// Set several differnet types of parameters.
auto set_parameters_results = parameters_client->set_parameters({
rclcpp::parameter::ParameterVariant("foo", 2),
rclcpp::parameter::ParameterVariant("bar", "hello"),
rclcpp::parameter::ParameterVariant("barstr", std::string("hello_str")),
rclcpp::parameter::ParameterVariant("baz", 1.45),
rclcpp::parameter::ParameterVariant("foo.first", 8),
rclcpp::parameter::ParameterVariant("foo.second", 42),
rclcpp::parameter::ParameterVariant("foobar", true),
rclcpp::Parameter("foo", 2),
rclcpp::Parameter("bar", "hello"),
rclcpp::Parameter("barstr", std::string("hello_str")),
rclcpp::Parameter("baz", 1.45),
rclcpp::Parameter("foo.first", 8),
rclcpp::Parameter("foo.second", 42),
rclcpp::Parameter("foobar", true),
});
printf("Got set_parameters result\n");

Expand All @@ -57,13 +57,13 @@ void verify_set_parameters_async(
printf("Setting parameters\n");
// Set several differnet types of parameters.
auto set_parameters_results = parameters_client->set_parameters({
rclcpp::parameter::ParameterVariant("foo", 2),
rclcpp::parameter::ParameterVariant("bar", "hello"),
rclcpp::parameter::ParameterVariant("barstr", std::string("hello_str")),
rclcpp::parameter::ParameterVariant("baz", 1.45),
rclcpp::parameter::ParameterVariant("foo.first", 8),
rclcpp::parameter::ParameterVariant("foo.second", 42),
rclcpp::parameter::ParameterVariant("foobar", true),
rclcpp::Parameter("foo", 2),
rclcpp::Parameter("bar", "hello"),
rclcpp::Parameter("barstr", std::string("hello_str")),
rclcpp::Parameter("baz", 1.45),
rclcpp::Parameter("foo.first", 8),
rclcpp::Parameter("foo.second", 42),
rclcpp::Parameter("foobar", true),
});
rclcpp::spin_until_future_complete(node, set_parameters_results); // Wait for the results.
printf("Got set_parameters result\n");
Expand Down
104 changes: 55 additions & 49 deletions test_rclcpp/test/test_local_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,17 +34,17 @@ using namespace std::chrono_literals;
#endif

TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), to_string) {
rclcpp::parameter::ParameterVariant pv("foo", "bar");
rclcpp::parameter::ParameterVariant pv2("foo2", "bar2");
rclcpp::Parameter pv("foo", "bar");
rclcpp::Parameter pv2("foo2", "bar2");
std::string json_dict = std::to_string(pv);
EXPECT_STREQ(
"{\"name\": \"foo\", \"type\": \"string\", \"value\": \"bar\"}",
json_dict.c_str());
json_dict = rclcpp::parameter::_to_json_dict_entry(pv);
json_dict = rclcpp::_to_json_dict_entry(pv);
EXPECT_STREQ(
"\"foo\": {\"type\": \"string\", \"value\": \"bar\"}",
json_dict.c_str());
std::vector<rclcpp::parameter::ParameterVariant> vpv;
std::vector<rclcpp::Parameter> vpv;
vpv.push_back(pv);
vpv.push_back(pv2);
json_dict = std::to_string(vpv);
Expand All @@ -53,12 +53,12 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), to_string) {
"\"foo2\": {\"type\": \"string\", \"value\": \"bar2\"}}",
json_dict.c_str());

pv = rclcpp::parameter::ParameterVariant("foo", 2.1);
pv = rclcpp::Parameter("foo", 2.1);
// TODO(tfoote) convert the value to a float and use epsilon test.
EXPECT_STREQ(
"{\"name\": \"foo\", \"type\": \"double\", \"value\": \"2.100000\"}",
std::to_string(pv).c_str());
pv = rclcpp::parameter::ParameterVariant("foo", 8);
pv = rclcpp::Parameter("foo", 8);
EXPECT_STREQ(
"{\"name\": \"foo\", \"type\": \"integer\", \"value\": \"8\"}",
std::to_string(pv).c_str());
Expand Down Expand Up @@ -109,16 +109,16 @@ class ParametersAsyncNode : public rclcpp::Node

void queue_set_parameter_request(rclcpp::executors::SingleThreadedExecutor & executor)
{
using rclcpp::parameter::ParameterVariant;
using rclcpp::Parameter;
using SetParametersResult =
std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>;
auto set_parameters_results = parameters_client_->set_parameters({
ParameterVariant("foo", 2),
ParameterVariant("bar", "hello"),
ParameterVariant("barstr", std::string("hello_str")),
ParameterVariant("baz", 1.45),
ParameterVariant("foobar", true),
ParameterVariant("barfoo", std::vector<uint8_t>{3, 4, 5}),
Parameter("foo", 2),
Parameter("bar", "hello"),
Parameter("barstr", std::string("hello_str")),
Parameter("baz", 1.45),
Parameter("foobar", true),
Parameter("barfoo", std::vector<uint8_t>{3, 4, 5}),
},
[&executor](SetParametersResult future)
{
Expand Down Expand Up @@ -156,12 +156,12 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), helpers) {
ASSERT_TRUE(false) << "service not available after waiting";
}
auto set_parameters_results = parameters_client->set_parameters({
rclcpp::parameter::ParameterVariant("foo", 2),
rclcpp::parameter::ParameterVariant("bar", "hello"),
rclcpp::parameter::ParameterVariant("barstr", std::string("hello_str")),
rclcpp::parameter::ParameterVariant("baz", 1.45),
rclcpp::parameter::ParameterVariant("foobar", true),
rclcpp::parameter::ParameterVariant("barfoo", std::vector<uint8_t>{0, 1, 2}),
rclcpp::Parameter("foo", 2),
rclcpp::Parameter("bar", "hello"),
rclcpp::Parameter("barstr", std::string("hello_str")),
rclcpp::Parameter("baz", 1.45),
rclcpp::Parameter("foobar", true),
rclcpp::Parameter("barfoo", std::vector<uint8_t>{0, 1, 2}),
});
printf("Got set_parameters result\n");

Expand All @@ -178,42 +178,48 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), helpers) {

// Test variables that are set, verifying that types are obeyed, and defaults not used.
EXPECT_TRUE(parameters_client->has_parameter("foo"));
EXPECT_THROW(baz = parameters_client->get_parameter<double>("foo"), std::runtime_error);
EXPECT_THROW(baz = parameters_client->get_parameter<double>("foo"),
rclcpp::ParameterTypeException);
EXPECT_NO_THROW(foo = parameters_client->get_parameter<int>("foo"));
EXPECT_EQ(foo, 2);
EXPECT_NO_THROW(foo = parameters_client->get_parameter("foo", 42));
EXPECT_EQ(foo, 2);

EXPECT_TRUE(parameters_client->has_parameter("bar"));
EXPECT_THROW(foo = parameters_client->get_parameter<int>("bar"), std::runtime_error);
EXPECT_THROW(foo = parameters_client->get_parameter<int>("bar"),
rclcpp::ParameterTypeException);
EXPECT_NO_THROW(bar = parameters_client->get_parameter<std::string>("bar"));
EXPECT_EQ(bar, "hello");
EXPECT_NO_THROW(bar = parameters_client->get_parameter<std::string>("bar", "goodbye"));
EXPECT_EQ(bar, "hello");

EXPECT_TRUE(parameters_client->has_parameter("barstr"));
EXPECT_THROW(foobar = parameters_client->get_parameter<bool>("barstr"), std::runtime_error);
EXPECT_THROW(foobar = parameters_client->get_parameter<bool>("barstr"),
rclcpp::ParameterTypeException);
EXPECT_NO_THROW(barstr = parameters_client->get_parameter<std::string>("barstr"));
EXPECT_EQ(barstr, "hello_str");
EXPECT_NO_THROW(barstr = parameters_client->get_parameter("barstr", std::string("heya")));
EXPECT_EQ(barstr, "hello_str");

EXPECT_TRUE(parameters_client->has_parameter("baz"));
EXPECT_THROW(foobar = parameters_client->get_parameter<bool>("baz"), std::runtime_error);
EXPECT_THROW(foobar = parameters_client->get_parameter<bool>("baz"),
rclcpp::ParameterTypeException);
EXPECT_NO_THROW(baz = parameters_client->get_parameter<double>("baz"));
EXPECT_DOUBLE_EQ(baz, 1.45);
EXPECT_NO_THROW(baz = parameters_client->get_parameter("baz", -4.2));
EXPECT_DOUBLE_EQ(baz, 1.45);

EXPECT_TRUE(parameters_client->has_parameter("foobar"));
EXPECT_THROW(baz = parameters_client->get_parameter<double>("foobar"), std::runtime_error);
EXPECT_THROW(baz = parameters_client->get_parameter<double>("foobar"),
rclcpp::ParameterTypeException);
EXPECT_NO_THROW(foobar = parameters_client->get_parameter<bool>("foobar"));
EXPECT_EQ(foobar, true);
EXPECT_NO_THROW(foobar = parameters_client->get_parameter("foobar", false));
EXPECT_EQ(foobar, true);

EXPECT_TRUE(parameters_client->has_parameter("barfoo"));
EXPECT_THROW(bar = parameters_client->get_parameter<std::string>("barfoo"), std::runtime_error);
EXPECT_THROW(bar = parameters_client->get_parameter<std::string>("barfoo"),
rclcpp::ParameterTypeException);
EXPECT_NO_THROW(barfoo = parameters_client->get_parameter<std::vector<uint8_t>>("barfoo"));
EXPECT_EQ(barfoo[0], 0);
EXPECT_EQ(barfoo[1], 1);
Expand Down Expand Up @@ -259,12 +265,12 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), get_from_node_primiti
ASSERT_TRUE(false) << "service not available after waiting";
}
auto set_parameters_results = parameters_client->set_parameters({
rclcpp::parameter::ParameterVariant("foo", 2),
rclcpp::parameter::ParameterVariant("bar", "hello"),
rclcpp::parameter::ParameterVariant("barstr", std::string("hello_str")),
rclcpp::parameter::ParameterVariant("baz", 1.45),
rclcpp::parameter::ParameterVariant("foobar", true),
rclcpp::parameter::ParameterVariant("barfoo", std::vector<uint8_t>{3, 4, 5}),
rclcpp::Parameter("foo", 2),
rclcpp::Parameter("bar", "hello"),
rclcpp::Parameter("barstr", std::string("hello_str")),
rclcpp::Parameter("baz", 1.45),
rclcpp::Parameter("foobar", true),
rclcpp::Parameter("barfoo", std::vector<uint8_t>{3, 4, 5}),
});
printf("Got set_parameters result\n");

Expand All @@ -288,7 +294,7 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), get_from_node_primiti
EXPECT_EQ(2, foo);

// Throw on type error
EXPECT_THROW(got_param = node->get_parameter("foo", foostr), std::runtime_error);
EXPECT_THROW(got_param = node->get_parameter("foo", foostr), rclcpp::ParameterTypeException);

// No throw on non-existent param, param shouldn't change
foo = 1000;
Expand Down Expand Up @@ -316,20 +322,20 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), get_from_node_primiti
}

TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), get_from_node_variant_type) {
using rclcpp::parameter::ParameterVariant;
using rclcpp::Parameter;

auto node = rclcpp::Node::make_shared("test_parameters_local_helpers");
auto parameters_client = std::make_shared<rclcpp::SyncParametersClient>(node);
if (!parameters_client->wait_for_service(20s)) {
ASSERT_TRUE(false) << "service not available after waiting";
}
auto set_parameters_results = parameters_client->set_parameters({
ParameterVariant("foo", 2),
ParameterVariant("bar", "hello"),
ParameterVariant("barstr", std::string("hello_str")),
ParameterVariant("baz", 1.45),
ParameterVariant("foobar", true),
ParameterVariant("barfoo", std::vector<uint8_t>{3, 4, 5}),
Parameter("foo", 2),
Parameter("bar", "hello"),
Parameter("barstr", std::string("hello_str")),
Parameter("baz", 1.45),
Parameter("foobar", true),
Parameter("barfoo", std::vector<uint8_t>{3, 4, 5}),
});
printf("Got set_parameters result\n");

Expand All @@ -340,13 +346,13 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), get_from_node_variant

bool got_param = false;

ParameterVariant foo;
ParameterVariant foostr;
Parameter foo;
Parameter foostr;

ParameterVariant bar;
ParameterVariant baz;
ParameterVariant foobar;
ParameterVariant barfoo;
Parameter bar;
Parameter baz;
Parameter foobar;
Parameter barfoo;

EXPECT_NO_THROW(got_param = node->get_parameter("foo", foo));
EXPECT_EQ(true, got_param);
Expand All @@ -373,11 +379,11 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), get_from_node_variant
}

TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), get_parameter_or) {
using rclcpp::parameter::ParameterVariant;
using rclcpp::Parameter;

auto node = rclcpp::Node::make_shared("test_parameters_get_parameter_or");
auto set_parameters_results = node->set_parameters({
ParameterVariant("foo", 2),
Parameter("foo", 2),
});
printf("Got set_parameters result\n");

Expand Down Expand Up @@ -409,11 +415,11 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), get_parameter_or) {
}

TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), set_parameter_if_not_set) {
using rclcpp::parameter::ParameterVariant;
using rclcpp::Parameter;

auto node = rclcpp::Node::make_shared("test_parameters_set_parameter_if_not_set");
auto set_parameters_results = node->set_parameters({
ParameterVariant("foo", 2),
Parameter("foo", 2),
});
printf("Got set_parameters result\n");

Expand Down