Skip to content

Commit af3fa82

Browse files
committed
Fixes for tests.
Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>
1 parent 5c44ae1 commit af3fa82

4 files changed

Lines changed: 45 additions & 33 deletions

File tree

rclcpp/src/rclcpp/node_interfaces/node_service_introspection.cpp

Lines changed: 20 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -31,22 +31,23 @@ void NodeServiceIntrospection::declare_introspection_parameter(
3131
{
3232
rclcpp::ParameterValue publish_events_param;
3333
if (!node_parameters->has_parameter(parameter_name)) {
34-
publish_events_param = node_parameters->declare_parameter(parameter_name, rclcpp::ParameterValue("off"));
34+
publish_events_param =
35+
node_parameters->declare_parameter(parameter_name, rclcpp::ParameterValue("off"));
3536
} else {
3637
publish_events_param = node_parameters->get_parameter(parameter_name).get_parameter_value();
3738
}
3839

3940
if (publish_events_param.get_type() != rclcpp::PARAMETER_STRING) {
4041
throw std::invalid_argument(
41-
"Invalid type for parameter '" + parameter_name + "', should be 'string'");
42+
"Invalid type for parameter '" + parameter_name + "', should be 'string'");
4243
}
4344

4445
const std::string publish_events_value = publish_events_param.get<std::string>();
45-
if (publish_events_value != "off" && publish_events_value != "metadata"
46-
&& publish_events_value != "contents")
46+
if (publish_events_value != "off" && publish_events_value != "metadata" &&
47+
publish_events_value != "contents")
4748
{
4849
throw std::invalid_argument(
49-
"Parameter '" + parameter_name + "' must be one of 'off', 'metadata', or 'contents'");
50+
"Parameter '" + parameter_name + "' must be one of 'off', 'metadata', or 'contents'");
5051
}
5152
}
5253

@@ -92,7 +93,9 @@ NodeServiceIntrospection::NodeServiceIntrospection(
9293
if (param.get_name() == "publish_service_events") {
9394
const std::string value = param.get_value<std::string>();
9495

95-
for (std::vector<rclcpp::ServiceBase::WeakPtr>::iterator srvit = services_.begin(); srvit != services_.end(); ++srvit) {
96+
for (std::vector<rclcpp::ServiceBase::WeakPtr>::iterator srvit = services_.begin();
97+
srvit != services_.end(); ++srvit)
98+
{
9699
rclcpp::ServiceBase::SharedPtr srv = srvit->lock();
97100
if (!srv) {
98101
srvit = services_.erase(srvit);
@@ -117,19 +120,23 @@ NodeServiceIntrospection::NodeServiceIntrospection(
117120
this->node_base_->get_rcl_node_handle(),
118121
should_enable_service_events);
119122
if (RCL_RET_OK != ret) {
120-
rclcpp::exceptions::throw_from_rcl_error(ret, "Failed to configure service introspection events");
123+
rclcpp::exceptions::throw_from_rcl_error(
124+
ret, "Failed to configure service introspection events");
121125
}
122126

123127
ret = rcl_service_introspection_configure_server_service_event_message_payload(
124128
srv->get_service_handle().get(), should_enable_contents);
125129
if (RCL_RET_OK != ret) {
126-
rclcpp::exceptions::throw_from_rcl_error(ret, "Failed to configure service introspection payload");
130+
rclcpp::exceptions::throw_from_rcl_error(
131+
ret, "Failed to configure service introspection payload");
127132
}
128133
}
129134
} else if (param.get_name() == "publish_client_events") {
130135
const std::string value = param.get_value<std::string>();
131136

132-
for (std::vector<rclcpp::ClientBase::WeakPtr>::iterator cliit = clients_.begin(); cliit != clients_.end(); ++cliit) {
137+
for (std::vector<rclcpp::ClientBase::WeakPtr>::iterator cliit = clients_.begin();
138+
cliit != clients_.end(); ++cliit)
139+
{
133140
rclcpp::ClientBase::SharedPtr cli = cliit->lock();
134141
if (!cli) {
135142
cliit = clients_.erase(cliit);
@@ -154,13 +161,15 @@ NodeServiceIntrospection::NodeServiceIntrospection(
154161
this->node_base_->get_rcl_node_handle(),
155162
should_enable_client_events);
156163
if (RCL_RET_OK != ret) {
157-
rclcpp::exceptions::throw_from_rcl_error(ret, "Failed to configure client introspection events");
164+
rclcpp::exceptions::throw_from_rcl_error(
165+
ret, "Failed to configure client introspection events");
158166
}
159167

160168
ret = rcl_service_introspection_configure_client_service_event_message_payload(
161169
cli->get_client_handle().get(), should_enable_contents);
162170
if (RCL_RET_OK != ret) {
163-
rclcpp::exceptions::throw_from_rcl_error(ret, "Failed to configure client introspection payload");
171+
rclcpp::exceptions::throw_from_rcl_error(
172+
ret, "Failed to configure client introspection payload");
164173
}
165174
}
166175
}

rclcpp/test/rclcpp/node_interfaces/test_node_parameters.cpp

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -77,9 +77,12 @@ TEST_F(TestNodeParameters, list_parameters)
7777
std::vector<std::string> prefixes;
7878
const auto list_result = node_parameters->list_parameters(prefixes, 1u);
7979

80-
// Currently the only default parameter is 'use_sim_time', but that may change.
80+
// Currently the default parameters are:
81+
// * 'use_sim_time'
82+
// * 'publish_client_events'
83+
// * 'publish_service_events'
8184
size_t number_of_parameters = list_result.names.size();
82-
EXPECT_GE(1u, number_of_parameters);
85+
EXPECT_GE(3u, number_of_parameters);
8386

8487
const std::string parameter_name = "new_parameter";
8588
const rclcpp::ParameterValue value(true);

rclcpp/test/rclcpp/test_parameter_client.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -944,7 +944,7 @@ TEST_F(TestParameterClient, async_parameter_load_parameters) {
944944
auto list_parameters = asynchronous_client->list_parameters({}, 3);
945945
rclcpp::spin_until_future_complete(
946946
load_node, list_parameters, std::chrono::milliseconds(100));
947-
ASSERT_EQ(list_parameters.get().names.size(), static_cast<uint64_t>(5));
947+
ASSERT_EQ(list_parameters.get().names.size(), static_cast<uint64_t>(7));
948948
}
949949
/*
950950
Coverage for sync load_parameters
@@ -964,7 +964,7 @@ TEST_F(TestParameterClient, sync_parameter_load_parameters) {
964964
ASSERT_EQ(load_future[0].successful, true);
965965
// list parameters
966966
auto list_parameters = synchronous_client->list_parameters({}, 3);
967-
ASSERT_EQ(list_parameters.names.size(), static_cast<uint64_t>(5));
967+
ASSERT_EQ(list_parameters.names.size(), static_cast<uint64_t>(7));
968968
}
969969

970970
/*
@@ -990,7 +990,7 @@ TEST_F(TestParameterClient, async_parameter_load_parameters_complicated_regex) {
990990
auto list_parameters = asynchronous_client->list_parameters({}, 3);
991991
rclcpp::spin_until_future_complete(
992992
load_node, list_parameters, std::chrono::milliseconds(100));
993-
ASSERT_EQ(list_parameters.get().names.size(), static_cast<uint64_t>(6));
993+
ASSERT_EQ(list_parameters.get().names.size(), static_cast<uint64_t>(8));
994994
// to check the parameter "a_value"
995995
std::string param_name = "a_value";
996996
auto param = load_node->get_parameter(param_name);
@@ -1068,7 +1068,7 @@ TEST_F(TestParameterClient, async_parameter_load_parameters_from_map) {
10681068
auto list_parameters = asynchronous_client->list_parameters({}, 3);
10691069
rclcpp::spin_until_future_complete(
10701070
load_node, list_parameters, std::chrono::milliseconds(100));
1071-
ASSERT_EQ(list_parameters.get().names.size(), static_cast<uint64_t>(6));
1071+
ASSERT_EQ(list_parameters.get().names.size(), static_cast<uint64_t>(8));
10721072
// to check the parameter "a_value"
10731073
std::string param_name = "a_value";
10741074
auto param = load_node->get_parameter(param_name);

rclcpp/test/rclcpp/test_service_introspection.cpp

Lines changed: 16 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -166,8 +166,8 @@ TEST_F(TestServiceIntrospection, service_introspection_nominal)
166166

167167
TEST_F(TestServiceIntrospection, service_introspection_enable_disable_events)
168168
{
169-
node->set_parameter(rclcpp::Parameter("publish_service_events", false));
170-
node->set_parameter(rclcpp::Parameter("publish_client_events", false));
169+
node->set_parameter(rclcpp::Parameter("publish_service_events", "off"));
170+
node->set_parameter(rclcpp::Parameter("publish_client_events", "off"));
171171

172172
auto request = std::make_shared<BasicTypes::Request>();
173173
request->set__bool_value(true);
@@ -183,8 +183,8 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_events)
183183
EXPECT_EQ(events.size(), 0U);
184184

185185
events.clear();
186-
node->set_parameter(rclcpp::Parameter("publish_service_events", false));
187-
node->set_parameter(rclcpp::Parameter("publish_client_events", true));
186+
node->set_parameter(rclcpp::Parameter("publish_service_events", "off"));
187+
node->set_parameter(rclcpp::Parameter("publish_client_events", "metadata"));
188188
future = client->async_send_request(request);
189189
ASSERT_EQ(
190190
rclcpp::FutureReturnCode::SUCCESS,
@@ -197,8 +197,8 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_events)
197197

198198

199199
events.clear();
200-
node->set_parameter(rclcpp::Parameter("publish_service_events", true));
201-
node->set_parameter(rclcpp::Parameter("publish_client_events", false));
200+
node->set_parameter(rclcpp::Parameter("publish_service_events", "metadata"));
201+
node->set_parameter(rclcpp::Parameter("publish_client_events", "off"));
202202
future = client->async_send_request(request);
203203
ASSERT_EQ(
204204
rclcpp::FutureReturnCode::SUCCESS,
@@ -210,8 +210,8 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_events)
210210
EXPECT_EQ(events.size(), 2U);
211211

212212
events.clear();
213-
node->set_parameter(rclcpp::Parameter("publish_service_events", true));
214-
node->set_parameter(rclcpp::Parameter("publish_client_events", true));
213+
node->set_parameter(rclcpp::Parameter("publish_service_events", "metadata"));
214+
node->set_parameter(rclcpp::Parameter("publish_client_events", "metadata"));
215215
future = client->async_send_request(request);
216216
ASSERT_EQ(
217217
rclcpp::FutureReturnCode::SUCCESS,
@@ -225,8 +225,8 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_events)
225225

226226
TEST_F(TestServiceIntrospection, service_introspection_enable_disable_event_content)
227227
{
228-
node->set_parameter(rclcpp::Parameter("publish_service_content", false));
229-
node->set_parameter(rclcpp::Parameter("publish_client_content", false));
228+
node->set_parameter(rclcpp::Parameter("publish_service_events", "metadata"));
229+
node->set_parameter(rclcpp::Parameter("publish_client_events", "metadata"));
230230

231231
auto request = std::make_shared<BasicTypes::Request>();
232232
request->set__bool_value(true);
@@ -247,8 +247,8 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_event_cont
247247

248248

249249
events.clear();
250-
node->set_parameter(rclcpp::Parameter("publish_service_content", false));
251-
node->set_parameter(rclcpp::Parameter("publish_client_content", true));
250+
node->set_parameter(rclcpp::Parameter("publish_service_events", "metadata"));
251+
node->set_parameter(rclcpp::Parameter("publish_client_events", "contents"));
252252
future = client->async_send_request(request);
253253
ASSERT_EQ(
254254
rclcpp::FutureReturnCode::SUCCESS,
@@ -276,8 +276,8 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_event_cont
276276
}
277277

278278
events.clear();
279-
node->set_parameter(rclcpp::Parameter("publish_service_content", true));
280-
node->set_parameter(rclcpp::Parameter("publish_client_content", false));
279+
node->set_parameter(rclcpp::Parameter("publish_service_events", "contents"));
280+
node->set_parameter(rclcpp::Parameter("publish_client_events", "metadata"));
281281
future = client->async_send_request(request);
282282
ASSERT_EQ(
283283
rclcpp::FutureReturnCode::SUCCESS,
@@ -305,8 +305,8 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_event_cont
305305
}
306306

307307
events.clear();
308-
node->set_parameter(rclcpp::Parameter("publish_service_content", true));
309-
node->set_parameter(rclcpp::Parameter("publish_client_content", true));
308+
node->set_parameter(rclcpp::Parameter("publish_service_events", "contents"));
309+
node->set_parameter(rclcpp::Parameter("publish_client_events", "contents"));
310310
future = client->async_send_request(request);
311311
ASSERT_EQ(
312312
rclcpp::FutureReturnCode::SUCCESS,

0 commit comments

Comments
 (0)