Skip to content

Commit

Permalink
Fixes for tests.
Browse files Browse the repository at this point in the history
Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>
  • Loading branch information
clalancette committed Feb 17, 2023
1 parent 5c44ae1 commit af3fa82
Show file tree
Hide file tree
Showing 4 changed files with 45 additions and 33 deletions.
31 changes: 20 additions & 11 deletions rclcpp/src/rclcpp/node_interfaces/node_service_introspection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,22 +31,23 @@ void NodeServiceIntrospection::declare_introspection_parameter(
{
rclcpp::ParameterValue publish_events_param;
if (!node_parameters->has_parameter(parameter_name)) {
publish_events_param = node_parameters->declare_parameter(parameter_name, rclcpp::ParameterValue("off"));
publish_events_param =
node_parameters->declare_parameter(parameter_name, rclcpp::ParameterValue("off"));
} else {
publish_events_param = node_parameters->get_parameter(parameter_name).get_parameter_value();
}

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

const std::string publish_events_value = publish_events_param.get<std::string>();
if (publish_events_value != "off" && publish_events_value != "metadata"
&& publish_events_value != "contents")
if (publish_events_value != "off" && publish_events_value != "metadata" &&
publish_events_value != "contents")
{
throw std::invalid_argument(
"Parameter '" + parameter_name + "' must be one of 'off', 'metadata', or 'contents'");
"Parameter '" + parameter_name + "' must be one of 'off', 'metadata', or 'contents'");
}
}

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

for (std::vector<rclcpp::ServiceBase::WeakPtr>::iterator srvit = services_.begin(); srvit != services_.end(); ++srvit) {
for (std::vector<rclcpp::ServiceBase::WeakPtr>::iterator srvit = services_.begin();
srvit != services_.end(); ++srvit)
{
rclcpp::ServiceBase::SharedPtr srv = srvit->lock();
if (!srv) {
srvit = services_.erase(srvit);
Expand All @@ -117,19 +120,23 @@ NodeServiceIntrospection::NodeServiceIntrospection(
this->node_base_->get_rcl_node_handle(),
should_enable_service_events);
if (RCL_RET_OK != ret) {
rclcpp::exceptions::throw_from_rcl_error(ret, "Failed to configure service introspection events");
rclcpp::exceptions::throw_from_rcl_error(
ret, "Failed to configure service introspection events");
}

ret = rcl_service_introspection_configure_server_service_event_message_payload(
srv->get_service_handle().get(), should_enable_contents);
if (RCL_RET_OK != ret) {
rclcpp::exceptions::throw_from_rcl_error(ret, "Failed to configure service introspection payload");
rclcpp::exceptions::throw_from_rcl_error(
ret, "Failed to configure service introspection payload");
}
}
} else if (param.get_name() == "publish_client_events") {
const std::string value = param.get_value<std::string>();

for (std::vector<rclcpp::ClientBase::WeakPtr>::iterator cliit = clients_.begin(); cliit != clients_.end(); ++cliit) {
for (std::vector<rclcpp::ClientBase::WeakPtr>::iterator cliit = clients_.begin();
cliit != clients_.end(); ++cliit)
{
rclcpp::ClientBase::SharedPtr cli = cliit->lock();
if (!cli) {
cliit = clients_.erase(cliit);
Expand All @@ -154,13 +161,15 @@ NodeServiceIntrospection::NodeServiceIntrospection(
this->node_base_->get_rcl_node_handle(),
should_enable_client_events);
if (RCL_RET_OK != ret) {
rclcpp::exceptions::throw_from_rcl_error(ret, "Failed to configure client introspection events");
rclcpp::exceptions::throw_from_rcl_error(
ret, "Failed to configure client introspection events");
}

ret = rcl_service_introspection_configure_client_service_event_message_payload(
cli->get_client_handle().get(), should_enable_contents);
if (RCL_RET_OK != ret) {
rclcpp::exceptions::throw_from_rcl_error(ret, "Failed to configure client introspection payload");
rclcpp::exceptions::throw_from_rcl_error(
ret, "Failed to configure client introspection payload");
}
}
}
Expand Down
7 changes: 5 additions & 2 deletions rclcpp/test/rclcpp/node_interfaces/test_node_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,9 +77,12 @@ TEST_F(TestNodeParameters, list_parameters)
std::vector<std::string> prefixes;
const auto list_result = node_parameters->list_parameters(prefixes, 1u);

// Currently the only default parameter is 'use_sim_time', but that may change.
// Currently the default parameters are:
// * 'use_sim_time'
// * 'publish_client_events'
// * 'publish_service_events'
size_t number_of_parameters = list_result.names.size();
EXPECT_GE(1u, number_of_parameters);
EXPECT_GE(3u, number_of_parameters);

const std::string parameter_name = "new_parameter";
const rclcpp::ParameterValue value(true);
Expand Down
8 changes: 4 additions & 4 deletions rclcpp/test/rclcpp/test_parameter_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -944,7 +944,7 @@ TEST_F(TestParameterClient, async_parameter_load_parameters) {
auto list_parameters = asynchronous_client->list_parameters({}, 3);
rclcpp::spin_until_future_complete(
load_node, list_parameters, std::chrono::milliseconds(100));
ASSERT_EQ(list_parameters.get().names.size(), static_cast<uint64_t>(5));
ASSERT_EQ(list_parameters.get().names.size(), static_cast<uint64_t>(7));
}
/*
Coverage for sync load_parameters
Expand All @@ -964,7 +964,7 @@ TEST_F(TestParameterClient, sync_parameter_load_parameters) {
ASSERT_EQ(load_future[0].successful, true);
// list parameters
auto list_parameters = synchronous_client->list_parameters({}, 3);
ASSERT_EQ(list_parameters.names.size(), static_cast<uint64_t>(5));
ASSERT_EQ(list_parameters.names.size(), static_cast<uint64_t>(7));
}

/*
Expand All @@ -990,7 +990,7 @@ TEST_F(TestParameterClient, async_parameter_load_parameters_complicated_regex) {
auto list_parameters = asynchronous_client->list_parameters({}, 3);
rclcpp::spin_until_future_complete(
load_node, list_parameters, std::chrono::milliseconds(100));
ASSERT_EQ(list_parameters.get().names.size(), static_cast<uint64_t>(6));
ASSERT_EQ(list_parameters.get().names.size(), static_cast<uint64_t>(8));
// to check the parameter "a_value"
std::string param_name = "a_value";
auto param = load_node->get_parameter(param_name);
Expand Down Expand Up @@ -1068,7 +1068,7 @@ TEST_F(TestParameterClient, async_parameter_load_parameters_from_map) {
auto list_parameters = asynchronous_client->list_parameters({}, 3);
rclcpp::spin_until_future_complete(
load_node, list_parameters, std::chrono::milliseconds(100));
ASSERT_EQ(list_parameters.get().names.size(), static_cast<uint64_t>(6));
ASSERT_EQ(list_parameters.get().names.size(), static_cast<uint64_t>(8));
// to check the parameter "a_value"
std::string param_name = "a_value";
auto param = load_node->get_parameter(param_name);
Expand Down
32 changes: 16 additions & 16 deletions rclcpp/test/rclcpp/test_service_introspection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -166,8 +166,8 @@ TEST_F(TestServiceIntrospection, service_introspection_nominal)

TEST_F(TestServiceIntrospection, service_introspection_enable_disable_events)
{
node->set_parameter(rclcpp::Parameter("publish_service_events", false));
node->set_parameter(rclcpp::Parameter("publish_client_events", false));
node->set_parameter(rclcpp::Parameter("publish_service_events", "off"));
node->set_parameter(rclcpp::Parameter("publish_client_events", "off"));

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

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


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

events.clear();
node->set_parameter(rclcpp::Parameter("publish_service_events", true));
node->set_parameter(rclcpp::Parameter("publish_client_events", true));
node->set_parameter(rclcpp::Parameter("publish_service_events", "metadata"));
node->set_parameter(rclcpp::Parameter("publish_client_events", "metadata"));
future = client->async_send_request(request);
ASSERT_EQ(
rclcpp::FutureReturnCode::SUCCESS,
Expand All @@ -225,8 +225,8 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_events)

TEST_F(TestServiceIntrospection, service_introspection_enable_disable_event_content)
{
node->set_parameter(rclcpp::Parameter("publish_service_content", false));
node->set_parameter(rclcpp::Parameter("publish_client_content", false));
node->set_parameter(rclcpp::Parameter("publish_service_events", "metadata"));
node->set_parameter(rclcpp::Parameter("publish_client_events", "metadata"));

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


events.clear();
node->set_parameter(rclcpp::Parameter("publish_service_content", false));
node->set_parameter(rclcpp::Parameter("publish_client_content", true));
node->set_parameter(rclcpp::Parameter("publish_service_events", "metadata"));
node->set_parameter(rclcpp::Parameter("publish_client_events", "contents"));
future = client->async_send_request(request);
ASSERT_EQ(
rclcpp::FutureReturnCode::SUCCESS,
Expand Down Expand Up @@ -276,8 +276,8 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_event_cont
}

events.clear();
node->set_parameter(rclcpp::Parameter("publish_service_content", true));
node->set_parameter(rclcpp::Parameter("publish_client_content", false));
node->set_parameter(rclcpp::Parameter("publish_service_events", "contents"));
node->set_parameter(rclcpp::Parameter("publish_client_events", "metadata"));
future = client->async_send_request(request);
ASSERT_EQ(
rclcpp::FutureReturnCode::SUCCESS,
Expand Down Expand Up @@ -305,8 +305,8 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_event_cont
}

events.clear();
node->set_parameter(rclcpp::Parameter("publish_service_content", true));
node->set_parameter(rclcpp::Parameter("publish_client_content", true));
node->set_parameter(rclcpp::Parameter("publish_service_events", "contents"));
node->set_parameter(rclcpp::Parameter("publish_client_events", "contents"));
future = client->async_send_request(request);
ASSERT_EQ(
rclcpp::FutureReturnCode::SUCCESS,
Expand Down

0 comments on commit af3fa82

Please sign in to comment.