Skip to content

Commit

Permalink
Properly test get_service_names_and_types_by_node in rclcpp_lifecycle (
Browse files Browse the repository at this point in the history
…#2599)

The current
`TestLifecycleServiceClient.get_service_names_and_types_by_node` test
was using `LifecycleServiceClient`, which is just a normal
`rclcpp::Node` with some `rclcpp::Client`s, to test
`NodeGraph::get_service_names_and_types_by_node()`. However,
`NodeGraph::get_service_names_and_types_by_node()` is for service
servers, not clients. The test just ended up checking the built-in
services of an `rclcpp::Node`, since it wasn't actually checking the
names of the services, and not checking the clients of the
`LifecycleServiceClient` or the built-in services of a
`rclcpp_lifecycle::LifecycleNode`. I believe this was probably not the
intention, since this is an `rclcpp_lifecycle` test.

Instead, use an actual `rclcpp_lifecycle::LifecycleNode` and check its
service servers by calling
`NodeGraph::get_service_names_and_types_by_node()` through
`LifecycleNode::get_service_names_and_types_by_node()`.

Signed-off-by: Christophe Bedard <[email protected]>
  • Loading branch information
christophebedard authored Aug 8, 2024
1 parent 496c455 commit ab7cf87
Showing 1 changed file with 25 additions and 14 deletions.
39 changes: 25 additions & 14 deletions rclcpp_lifecycle/test/test_lifecycle_service_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,11 +18,14 @@
*/

#include <gtest/gtest.h>
#include <algorithm>
#include <array>
#include <chrono>
#include <memory>
#include <mutex>
#include <string>
#include <thread>
#include <utility>
#include <vector>

#include "lifecycle_msgs/msg/state.hpp"
Expand Down Expand Up @@ -368,26 +371,34 @@ TEST_F(TestLifecycleServiceClient, lifecycle_transitions) {

TEST_F(TestLifecycleServiceClient, get_service_names_and_types_by_node)
{
auto node1 = std::make_shared<LifecycleServiceClient>("client1");
auto node2 = std::make_shared<LifecycleServiceClient>("client2");

auto node_graph = node1->get_node_graph_interface();
ASSERT_NE(nullptr, node_graph);

EXPECT_THROW(
node_graph->get_service_names_and_types_by_node("not_a_node", "not_absolute_namespace"),
lifecycle_node()->get_service_names_and_types_by_node("not_a_node", "not_absolute_namespace"),
std::runtime_error);
auto service_names_and_types1 = node_graph->get_service_names_and_types_by_node("client1", "/");
auto service_names_and_types2 = node_graph->get_service_names_and_types_by_node("client2", "/");
auto service_names_and_types =
lifecycle_node()->get_service_names_and_types_by_node(lifecycle_node_name, "/");
auto start = std::chrono::steady_clock::now();
while (0 == service_names_and_types1.size() ||
service_names_and_types1.size() != service_names_and_types2.size() ||
while (0 == service_names_and_types.size() ||
(std::chrono::steady_clock::now() - start) < std::chrono::seconds(1))
{
service_names_and_types1 = node_graph->get_service_names_and_types_by_node("client1", "/");
service_names_and_types2 = node_graph->get_service_names_and_types_by_node("client2", "/");
service_names_and_types =
lifecycle_node()->get_service_names_and_types_by_node(lifecycle_node_name, "/");
}
const std::array services = {
std::make_pair(node_get_state_topic, "lifecycle_msgs/srv/GetState"),
std::make_pair(node_change_state_topic, "lifecycle_msgs/srv/ChangeState"),
std::make_pair(node_get_available_states_topic, "lifecycle_msgs/srv/GetAvailableStates"),
std::make_pair(
node_get_available_transitions_topic, "lifecycle_msgs/srv/GetAvailableTransitions"),
std::make_pair(node_get_transition_graph_topic, "lifecycle_msgs/srv/GetAvailableTransitions"),
};
for (const auto & [service_name, service_type] : services) {
ASSERT_TRUE(service_names_and_types.find(service_name) != service_names_and_types.end())
<< service_name;
const auto service_types = service_names_and_types.at(service_name);
EXPECT_TRUE(
std::find(service_types.cbegin(), service_types.cend(), service_type) != service_types.cend())
<< service_name;
}
EXPECT_EQ(service_names_and_types1.size(), service_names_and_types2.size());
}

TEST_F(TestLifecycleServiceClient, declare_parameter_with_no_initial_values)
Expand Down

0 comments on commit ab7cf87

Please sign in to comment.