Skip to content

Commit 9f504fb

Browse files
committed
Expect declared parameters + use_sim_time
1 parent 9377eb6 commit 9f504fb

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
{
@@ -141,7 +152,7 @@ void verify_test_parameters(
141152
parameters_and_prefixes = parameters_client->list_parameters({},
142153
rcl_interfaces::srv::ListParameters::Request::DEPTH_RECURSIVE);
143154
std::vector<std::string> all_names = {
144-
"foo", "bar", "barstr", "baz", "foo.first", "foo.second", "foobar"
155+
"foo", "bar", "barstr", "baz", "foo.first", "foo.second", "foobar", "use_sim_time"
145156
};
146157
EXPECT_EQ(parameters_and_prefixes.names.size(), all_names.size());
147158
for (auto & name : all_names) {
@@ -164,9 +175,9 @@ void verify_test_parameters(
164175
}
165176
printf("Listing parameters with depth 1\n");
166177
// List most of the parameters, using an empty prefix list and depth=1
167-
parameters_and_prefixes = parameters_client->list_parameters({}, 1);
178+
parameters_and_prefixes = parameters_client->list_parameters({}, 1u);
168179
std::vector<std::string> depth_one_names = {
169-
"foo", "bar", "barstr", "baz", "foobar"
180+
"foo", "bar", "barstr", "baz", "foobar", "use_sim_time"
170181
};
171182
EXPECT_EQ(parameters_and_prefixes.names.size(), depth_one_names.size());
172183
for (auto & name : depth_one_names) {
@@ -259,7 +270,7 @@ void verify_get_parameters_async(
259270
rclcpp::spin_until_future_complete(node, result5);
260271
parameters_and_prefixes = result5.get();
261272
std::vector<std::string> all_names = {
262-
"foo", "bar", "barstr", "baz", "foo.first", "foo.second", "foobar"
273+
"foo", "bar", "barstr", "baz", "foo.first", "foo.second", "foobar", "use_sim_time"
263274
};
264275
EXPECT_EQ(parameters_and_prefixes.names.size(), all_names.size());
265276
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
@@ -66,6 +66,7 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), to_string) {
6666

6767
TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_synchronous) {
6868
auto node = rclcpp::Node::make_shared("test_parameters_local_synchronous");
69+
declare_test_parameters(node);
6970
auto parameters_client = std::make_shared<rclcpp::SyncParametersClient>(node);
7071
if (!parameters_client->wait_for_service(20s)) {
7172
ASSERT_TRUE(false) << "service not available after waiting";
@@ -76,6 +77,7 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_synchronous) {
7677

7778
TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_synchronous_repeated) {
7879
auto node = rclcpp::Node::make_shared("test_parameters_local_synchronous_repeated");
80+
declare_test_parameters(node);
7981
auto parameters_client = std::make_shared<rclcpp::SyncParametersClient>(node);
8082
if (!parameters_client->wait_for_service(20s)) {
8183
ASSERT_TRUE(false) << "service not available after waiting";
@@ -89,6 +91,7 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_synchronous_rep
8991

9092
TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_asynchronous) {
9193
auto node = rclcpp::Node::make_shared(std::string("test_parameters_local_asynchronous"));
94+
declare_test_parameters(node);
9295
auto parameters_client = std::make_shared<rclcpp::AsyncParametersClient>(node);
9396
if (!parameters_client->wait_for_service(20s)) {
9497
ASSERT_TRUE(false) << "service not available after waiting";
@@ -103,6 +106,13 @@ class ParametersAsyncNode : public rclcpp::Node
103106
ParametersAsyncNode()
104107
: Node("test_local_parameters_async_with_callback")
105108
{
109+
this->create_parameter("foo");
110+
this->create_parameter("bar");
111+
this->create_parameter("barstr");
112+
this->create_parameter("baz");
113+
this->create_parameter("foobar");
114+
this->create_parameter("barfoo");
115+
106116
parameters_client_ =
107117
std::make_shared<rclcpp::AsyncParametersClient>(this);
108118
}
@@ -151,6 +161,13 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_async_with_call
151161

152162
TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), helpers) {
153163
auto node = rclcpp::Node::make_shared("test_parameters_local_helpers");
164+
node->create_parameter("foo");
165+
node->create_parameter("bar");
166+
node->create_parameter("barstr");
167+
node->create_parameter("baz");
168+
node->create_parameter("foobar");
169+
node->create_parameter("barfoo");
170+
154171
auto parameters_client = std::make_shared<rclcpp::SyncParametersClient>(node);
155172
if (!parameters_client->wait_for_service(20s)) {
156173
ASSERT_TRUE(false) << "service not available after waiting";
@@ -260,6 +277,13 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), helpers) {
260277

261278
TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), get_from_node_primitive_type) {
262279
auto node = rclcpp::Node::make_shared("test_parameters_local_helpers");
280+
node->create_parameter("foo");
281+
node->create_parameter("bar");
282+
node->create_parameter("barstr");
283+
node->create_parameter("baz");
284+
node->create_parameter("foobar");
285+
node->create_parameter("barfoo");
286+
263287
auto parameters_client = std::make_shared<rclcpp::SyncParametersClient>(node);
264288
if (!parameters_client->wait_for_service(20s)) {
265289
ASSERT_TRUE(false) << "service not available after waiting";
@@ -325,6 +349,13 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), get_from_node_variant
325349
using rclcpp::Parameter;
326350

327351
auto node = rclcpp::Node::make_shared("test_parameters_local_helpers");
352+
node->create_parameter("foo");
353+
node->create_parameter("bar");
354+
node->create_parameter("barstr");
355+
node->create_parameter("baz");
356+
node->create_parameter("foobar");
357+
node->create_parameter("barfoo");
358+
328359
auto parameters_client = std::make_shared<rclcpp::SyncParametersClient>(node);
329360
if (!parameters_client->wait_for_service(20s)) {
330361
ASSERT_TRUE(false) << "service not available after waiting";
@@ -382,6 +413,7 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), get_parameter_or) {
382413
using rclcpp::Parameter;
383414

384415
auto node = rclcpp::Node::make_shared("test_parameters_get_parameter_or");
416+
node->create_parameter("foo");
385417
auto set_parameters_results = node->set_parameters({
386418
Parameter("foo", 2),
387419
});
@@ -418,6 +450,9 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), set_parameter_if_not_
418450
using rclcpp::Parameter;
419451

420452
auto node = rclcpp::Node::make_shared("test_parameters_set_parameter_if_not_set");
453+
node->create_parameter("foo");
454+
node->create_parameter("bar");
455+
421456
auto set_parameters_results = node->set_parameters({
422457
Parameter("foo", 2),
423458
});

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)