I want to write some integration tests for my ROS2 node (Humble) that provides an service which in turn calls a service. While during runtime this works perfectly fine, when I try to create a unit test it does not work.
A simplified example of the problem is below. We have 3 nodes.
- A caller, which triggers the cascade
- A server, which provides a trigger service
- A passthrough node, that provides a trigger service, and calls the server trigger in its callback
The expected behavior would be that this would work just fine. Each node has its own callback group, and we are using a multithreaded executor.
However, the ctest output is:
[INFO] [1693924977.374938724] [passthrough]: Passthrough service called
<redacted>:74: Failure
Expected equality of these values:
rclcpp::FutureReturnCode::SUCCESS
Which is: SUCCESS (0)
future_ret
Which is: TIMEOUT (2)
[INFO] [1693924977.475530284] [server]: Server service called
Which seems to indicate that in fact one callback is waiting for the other.
I have been shooting in the dark with some attempts:
- Creating a callback group for every interface (clients & services)
- Creating multiple executors
- Changing callback groups between MutualExclusive and Reentrant
But, it does not seem to solve the issue. Is this related to gtest/ctest, or is there something else I might be missing?
Below the code to reproduce.
#include <gtest/gtest.h>
#include <chrono>
#include <rclcpp/rclcpp.hpp>
#include <std_srvs/srv/trigger.hpp>
// Chrono literals
using namespace std::chrono_literals;
// Test Cases
// We expect the node to throw on construction when no parameters are set
TEST(CascadedServiceTest, SimpleTriggerPassthrough)
{
std::string const kTriggerNamePassthrough = "passthrough_trigger";
std::string const kTriggerNameServer = "server_trigger";
// Create nodes
auto node_caller = rclcpp::Node::make_shared("caller");
auto node_passthrough = rclcpp::Node::make_shared("passthrough");
auto node_server = rclcpp::Node::make_shared("server");
// Create service clients
auto client_caller = node_caller->create_client<std_srvs::srv::Trigger>(kTriggerNamePassthrough);
auto client_passthrough = node_passthrough->create_client<std_srvs::srv::Trigger>(kTriggerNameServer);
// Create service servers
// We specify a special callback group for the service, as to not conflict with the client.
auto callback_group_passthrough = node_passthrough->create_callback_group(rclcpp::CallbackGroupType::Reentrant);
auto srv_passthrough = node_passthrough->create_service<std_srvs::srv::Trigger>(
kTriggerNamePassthrough,
[this, &client_passthrough, &node_passthrough](std::shared_ptr<std_srvs::srv::Trigger::Request> const request,
std::shared_ptr<std_srvs::srv::Trigger::Response> const response)
{
RCLCPP_INFO(node_passthrough->get_logger(), "Passthrough service called");
auto future_result = client_passthrough->async_send_request(request).future.share();
auto future_status = future_result.wait_for(100ms);
if(future_status != std::future_status::ready)
{
response->success = false;
}
},
rmw_qos_profile_services_default, callback_group_passthrough);
// Server does not require new callback as it the only one handling callbacks in node
auto srv_server = node_server->create_service<std_srvs::srv::Trigger>(
kTriggerNameServer,
[this, &node_server](std::shared_ptr<std_srvs::srv::Trigger::Request> const,
std::shared_ptr<std_srvs::srv::Trigger::Response> const response)
{
RCLCPP_INFO(node_server->get_logger(), "Server service called");
response->success = true;
});
// Create executor and add nodes
rclcpp::executors::MultiThreadedExecutor exec;
exec.add_node(node_caller);
exec.add_node(node_passthrough);
exec.add_node(node_server);
// Make initial trigger request
auto initial_request = std::make_shared<std_srvs::srv::Trigger::Request>();
// Spin until we receive message or timeout
auto f = client_caller->async_send_request(initial_request).future.share();
rclcpp::FutureReturnCode future_ret = exec.spin_until_future_complete(f, 100ms);
EXPECT_EQ(rclcpp::FutureReturnCode::SUCCESS, future_ret);
// Now we will see the server callback triggered
exec.spin_some();
}
int main(int argc, char** argv)
{
rclcpp::init(argc, argv);
::testing::InitGoogleTest(&argc, argv);
auto res = RUN_ALL_TESTS();
rclcpp::shutdown();
return res;
}
```