Skip to content

Commit c3558f1

Browse files
sloretzwjwwood
authored andcommitted
Expect declared parameters + use_sim_time
1 parent 4424f64 commit c3558f1

File tree

3 files changed

+65
-5
lines changed

3 files changed

+65
-5
lines changed

test_rclcpp/test/parameter_fixtures.hpp

Lines changed: 15 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,17 @@
2727

2828
const double test_epsilon = 1e-6;
2929

30+
void declare_test_parameters(std::shared_ptr<rclcpp::Node> node)
31+
{
32+
node->create_parameter("foo");
33+
node->create_parameter("bar");
34+
node->create_parameter("barstr");
35+
node->create_parameter("baz");
36+
node->create_parameter("foo.first");
37+
node->create_parameter("foo.second");
38+
node->create_parameter("foobar");
39+
}
40+
3041
void set_test_parameters(
3142
std::shared_ptr<rclcpp::SyncParametersClient> parameters_client)
3243
{
@@ -167,7 +178,7 @@ void verify_test_parameters(
167178
parameters_and_prefixes = parameters_client->list_parameters({},
168179
rcl_interfaces::srv::ListParameters::Request::DEPTH_RECURSIVE);
169180
std::vector<std::string> all_names = {
170-
"foo", "bar", "barstr", "baz", "foo.first", "foo.second", "foobar"
181+
"foo", "bar", "barstr", "baz", "foo.first", "foo.second", "foobar", "use_sim_time"
171182
};
172183
EXPECT_EQ(parameters_and_prefixes.names.size(), all_names.size());
173184
for (auto & name : all_names) {
@@ -190,9 +201,9 @@ void verify_test_parameters(
190201
}
191202
printf("Listing parameters with depth 1\n");
192203
// List most of the parameters, using an empty prefix list and depth=1
193-
parameters_and_prefixes = parameters_client->list_parameters({}, 1);
204+
parameters_and_prefixes = parameters_client->list_parameters({}, 1u);
194205
std::vector<std::string> depth_one_names = {
195-
"foo", "bar", "barstr", "baz", "foobar"
206+
"foo", "bar", "barstr", "baz", "foobar", "use_sim_time"
196207
};
197208
EXPECT_EQ(parameters_and_prefixes.names.size(), depth_one_names.size());
198209
for (auto & name : depth_one_names) {
@@ -290,7 +301,7 @@ void verify_get_parameters_async(
290301
rclcpp::spin_until_future_complete(node, result5);
291302
parameters_and_prefixes = result5.get();
292303
std::vector<std::string> all_names = {
293-
"foo", "bar", "barstr", "baz", "foo.first", "foo.second", "foobar"
304+
"foo", "bar", "barstr", "baz", "foo.first", "foo.second", "foobar", "use_sim_time"
294305
};
295306
EXPECT_EQ(parameters_and_prefixes.names.size(), all_names.size());
296307
for (auto & name : all_names) {

test_rclcpp/test/test_local_parameters.cpp

Lines changed: 35 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -68,6 +68,7 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), to_string) {
6868
TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_synchronous) {
6969
if (!rclcpp::ok()) {rclcpp::init(0, nullptr);}
7070
auto node = rclcpp::Node::make_shared("test_parameters_local_synchronous");
71+
declare_test_parameters(node);
7172
auto parameters_client = std::make_shared<rclcpp::SyncParametersClient>(node);
7273
if (!parameters_client->wait_for_service(20s)) {
7374
ASSERT_TRUE(false) << "service not available after waiting";
@@ -79,6 +80,7 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_synchronous) {
7980
TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_synchronous_repeated) {
8081
if (!rclcpp::ok()) {rclcpp::init(0, nullptr);}
8182
auto node = rclcpp::Node::make_shared("test_parameters_local_synchronous_repeated");
83+
declare_test_parameters(node);
8284
auto parameters_client = std::make_shared<rclcpp::SyncParametersClient>(node);
8385
if (!parameters_client->wait_for_service(20s)) {
8486
ASSERT_TRUE(false) << "service not available after waiting";
@@ -93,6 +95,7 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_synchronous_rep
9395
TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_asynchronous) {
9496
if (!rclcpp::ok()) {rclcpp::init(0, nullptr);}
9597
auto node = rclcpp::Node::make_shared(std::string("test_parameters_local_asynchronous"));
98+
declare_test_parameters(node);
9699
auto parameters_client = std::make_shared<rclcpp::AsyncParametersClient>(node);
97100
if (!parameters_client->wait_for_service(20s)) {
98101
ASSERT_TRUE(false) << "service not available after waiting";
@@ -107,6 +110,13 @@ class ParametersAsyncNode : public rclcpp::Node
107110
ParametersAsyncNode()
108111
: Node("test_local_parameters_async_with_callback")
109112
{
113+
this->create_parameter("foo");
114+
this->create_parameter("bar");
115+
this->create_parameter("barstr");
116+
this->create_parameter("baz");
117+
this->create_parameter("foobar");
118+
this->create_parameter("barfoo");
119+
110120
parameters_client_ =
111121
std::make_shared<rclcpp::AsyncParametersClient>(this);
112122
}
@@ -157,6 +167,13 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_async_with_call
157167
TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), helpers) {
158168
if (!rclcpp::ok()) {rclcpp::init(0, nullptr);}
159169
auto node = rclcpp::Node::make_shared("test_parameters_local_helpers");
170+
node->create_parameter("foo");
171+
node->create_parameter("bar");
172+
node->create_parameter("barstr");
173+
node->create_parameter("baz");
174+
node->create_parameter("foobar");
175+
node->create_parameter("barfoo");
176+
160177
auto parameters_client = std::make_shared<rclcpp::SyncParametersClient>(node);
161178
if (!parameters_client->wait_for_service(20s)) {
162179
ASSERT_TRUE(false) << "service not available after waiting";
@@ -267,6 +284,13 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), helpers) {
267284
TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), get_from_node_primitive_type) {
268285
if (!rclcpp::ok()) {rclcpp::init(0, nullptr);}
269286
auto node = rclcpp::Node::make_shared("test_parameters_local_helpers");
287+
node->create_parameter("foo");
288+
node->create_parameter("bar");
289+
node->create_parameter("barstr");
290+
node->create_parameter("baz");
291+
node->create_parameter("foobar");
292+
node->create_parameter("barfoo");
293+
270294
auto parameters_client = std::make_shared<rclcpp::SyncParametersClient>(node);
271295
if (!parameters_client->wait_for_service(20s)) {
272296
ASSERT_TRUE(false) << "service not available after waiting";
@@ -333,6 +357,13 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), get_from_node_variant
333357
using rclcpp::Parameter;
334358

335359
auto node = rclcpp::Node::make_shared("test_parameters_local_helpers");
360+
node->create_parameter("foo");
361+
node->create_parameter("bar");
362+
node->create_parameter("barstr");
363+
node->create_parameter("baz");
364+
node->create_parameter("foobar");
365+
node->create_parameter("barfoo");
366+
336367
auto parameters_client = std::make_shared<rclcpp::SyncParametersClient>(node);
337368
if (!parameters_client->wait_for_service(20s)) {
338369
ASSERT_TRUE(false) << "service not available after waiting";
@@ -391,6 +422,7 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), get_parameter_or) {
391422
using rclcpp::Parameter;
392423

393424
auto node = rclcpp::Node::make_shared("test_parameters_get_parameter_or");
425+
node->create_parameter("foo");
394426
auto set_parameters_results = node->set_parameters({
395427
Parameter("foo", 2),
396428
});
@@ -461,6 +493,9 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), set_parameter_if_not_
461493
using rclcpp::Parameter;
462494

463495
auto node = rclcpp::Node::make_shared("test_parameters_set_parameter_if_not_set");
496+
node->create_parameter("foo");
497+
node->create_parameter("bar");
498+
464499
auto set_parameters_results = node->set_parameters({
465500
Parameter("foo", 2),
466501
});

test_rclcpp/test/test_parameters_server.cpp

Lines changed: 15 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717
#include <memory>
1818
#include <stdexcept>
1919
#include <string>
20+
#include <vector>
2021

2122
#include "rclcpp/rclcpp.hpp"
2223

@@ -25,7 +26,20 @@ int main(int argc, char ** argv)
2526
{
2627
rclcpp::init(argc, argv);
2728

28-
auto node = rclcpp::Node::make_shared(std::string("test_parameters_server"));
29+
const std::string node_name = "test_parameters_server";
30+
const std::string namespace_ = "/";
31+
rclcpp::Context::SharedPtr context =
32+
rclcpp::contexts::default_context::get_global_default_context();
33+
const std::vector<std::string> arguments = {};
34+
const std::vector<rclcpp::Parameter> initial_parameters = {};
35+
const bool use_global_arguments = true;
36+
const bool use_intra_process_comms = false;
37+
const bool start_parameter_services = true;
38+
const bool allow_undeclared_parameters = true;
39+
40+
auto node = rclcpp::Node::make_shared(node_name, namespace_, context, arguments,
41+
initial_parameters, use_global_arguments, use_intra_process_comms, start_parameter_services,
42+
allow_undeclared_parameters);
2943

3044
rclcpp::spin(node);
3145

0 commit comments

Comments
 (0)