Skip to content

SharedFuture from async_send_request never becomes valid #2039

@jefferyyjhsu

Description

@jefferyyjhsu

Bug report

Required Info:

  • Operating System:
    • Ubuntu 22.04.1 LTS (osrf/ros:humble-desktop docker image)
  • Installation type:
    • from source
  • Version or commit hash:
  • DDS implementation:
    • both fastrtps and cyclonedds
  • Client library (if applicable):
    • rclcpp

Steps to reproduce issue

Build and run the unit test below

#include <gtest/gtest.h>
#include <rclcpp/rclcpp.hpp>

#include <std_srvs/srv/set_bool.hpp>

#include <string>

using namespace std::chrono;

class TestRegularService : public ::testing::Test
{
public:
    void SetUp() override
    {
        rclcpp::init(0, nullptr);

        m_node_executor = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();

        // Create a node
        auto opt = rclcpp::NodeOptions();
        auto node = rclcpp::Node::make_shared("server_node", opt);
        m_nodes.push_back(node);
        m_node_executor->add_node(node->get_node_base_interface());
        m_service = rclcpp::create_service<std_srvs::srv::SetBool>(
            node->get_node_base_interface(),
            node->get_node_services_interface(),
            "example_service",
            [node](const std::shared_ptr<std_srvs::srv::SetBool::Request> request, 
                const std::shared_ptr<std_srvs::srv::SetBool::Response> response) {
                static unsigned int serial_num = 1;
                (void)request;
                RCLCPP_INFO(node->get_logger(), "Received service client request... Sending response: %d", serial_num);
                response->success = true;
                response->message = std::to_string(serial_num++);
            },
            rclcpp::ServicesQoS().get_rmw_qos_profile(),
            nullptr);

        node = rclcpp::Node::make_shared("client_node", opt);
        m_nodes.push_back(node);
        m_node_executor->add_node(node);
        m_client = node->create_client<std_srvs::srv::SetBool>("example_service");

        

        m_node_thread = std::thread(std::bind([this]()
        {
            this->m_node_executor->spin();
        }));
    }

    ~TestRegularService()
    {
        if (rclcpp::ok())
        {
            rclcpp::shutdown();
        }
        m_node_thread.join();
    }

    std::vector<std::shared_ptr<rclcpp::Node>> m_nodes;
    std::shared_ptr<rclcpp::executors::SingleThreadedExecutor> m_node_executor;
    rclcpp::ServiceBase::SharedPtr m_service;
    rclcpp::Client<std_srvs::srv::SetBool>::SharedPtr m_client;
    std::thread m_node_thread;

};

TEST_F(TestRegularService, test_regular_service)
{
    auto request = std::make_shared<std_srvs::srv::SetBool::Request>();
    request->data = true;

    while (!m_client->wait_for_service(1s)) {
        if (!rclcpp::ok()) {
        RCLCPP_ERROR(m_nodes.front()->get_logger(), "Interrupted while waiting for the service. Exiting.");
        return;
        }
        RCLCPP_INFO(m_nodes.front()->get_logger(), "service not available, waiting again...");
    }
    uint counter = 1;
    do {
        RCLCPP_INFO(m_nodes.front()->get_logger(), "Sending request: %d" , counter);
        auto result = m_client->async_send_request(request);
        RCLCPP_INFO(m_nodes.front()->get_logger(), "Waiting for response: %d" , counter);
        auto answer = result.get();
        ASSERT_TRUE(answer->success);
        RCLCPP_INFO(m_nodes.front()->get_logger(), "Got response: %s", answer->message.c_str());
    }while(++counter<1000000);
}

int main(int argc, char **argv)
{
    ::testing::InitGoogleTest(&argc, argv);
    return RUN_ALL_TESTS();
}

Expected behavior

The unit test is expected to send an async request and a valid result will be retrieved with SharedFuture::get() later. The unit should repeat the process 1000000 times without issues.

Actual behavior

The unit test hangs randomly regardless of the underline DDS.
Example snippet:

Start testing: Oct 31 20:35 UTC
----------------------------------------------------------
71/105 Testing: test-regular-ros2-service
71/105 Test: test-regular-ros2-service
Command: "/usr/bin/python3.10" "-u" "/ros2_humble/install/ament_cmake_test/share/ament_cmake_test/cmake/run_test.py" "/ros2_humble/build/rclcpp/test_results/rclcpp/test-regular-ros2-service.gtest.xml" "--package-name" "rclcpp" "--output-file" "/ros2_humble/build/rclcpp/ament_cmake_gtest/test-regular-ros2-service.txt" "--command" "/ros2_humble/build/rclcpp/test/rclcpp/test-regular-ros2-service" "--gtest_output=xml:/ros2_humble/build/rclcpp/test_results/rclcpp/test-regular-ros2-service.gtest.xml"
Directory: /ros2_humble/build/rclcpp/test/rclcpp
"test-regular-ros2-service" start time: Oct 31 20:35 UTC
Output:
----------------------------------------------------------
-- run_test.py: invoking following command in '/ros2_humble/build/rclcpp/test/rclcpp':
 - /ros2_humble/build/rclcpp/test/rclcpp/test-regular-ros2-service --gtest_output=xml:/ros2_humble/build/rclcpp/test_results/rclcpp/test-regular-ros2-service.gtest.xml
[==========] Running 1 test from 1 test suite.
[----------] Global test environment set-up.
[----------] 1 test from TestRegularService
[ RUN      ] TestRegularService.test_regular_service
[INFO] [1667248559.329850983] [server_node]: Sending request: 1
[INFO] [1667248559.329986353] [server_node]: Waiting for response: 1
[INFO] [1667248559.330659463] [server_node]: Received service client request... Sending response: 1
[INFO] [1667248559.330995192] [server_node]: Got response: 1
[INFO] [1667248559.331019237] [server_node]: Sending request: 2
[INFO] [1667248559.331041372] [server_node]: Waiting for response: 2
[INFO] [1667248559.331233045] [server_node]: Received service client request... Sending response: 2
[INFO] [1667248559.331454604] [server_node]: Got response: 2
[INFO] [1667248559.331478869] [server_node]: Sending request: 3
[INFO] [1667248559.331500609] [server_node]: Waiting for response: 3
[INFO] [1667248559.331623666] [server_node]: Received service client request... Sending response: 3
[INFO] [1667248559.331833534] [server_node]: Got response: 3
[INFO] [1667248559.331858362] [server_node]: Sending request: 4
[INFO] [1667248559.331879729] [server_node]: Waiting for response: 4
[INFO] [1667248559.331984129] [server_node]: Received service client request... Sending response: 4
[INFO] [1667248559.332344850] [server_node]: Got response: 4
.......
.......
.......
[INFO] [1667248559.887715670] [server_node]: Sending request: 2704
[INFO] [1667248559.887733614] [server_node]: Waiting for response: 2704
[INFO] [1667248559.887767825] [server_node]: Received service client request... Sending response: 2704
[INFO] [1667248559.887899850] [server_node]: Got response: 2704
[INFO] [1667248559.887913152] [server_node]: Sending request: 2705
[INFO] [1667248559.887931926] [server_node]: Waiting for response: 2705
[INFO] [1667248559.887967492] [server_node]: Received service client request... Sending response: 2705
[INFO] [1667248559.888097595] [server_node]: Got response: 2705
[INFO] [1667248559.888119401] [server_node]: Sending request: 2706
[INFO] [1667248559.888141074] [server_node]: Waiting for response: 2706
<end of output>
Test time =  60.06 sec
----------------------------------------------------------
Test Failed.
"test-regular-ros2-service" end time: Oct 31 20:36 UTC
"test-regular-ros2-service" time elapsed: 00:01:00
----------------------------------------------------------

End testing: Oct 31 20:36 UTC

gtest =  60.06 sec*proc

Metadata

Metadata

Assignees

No one assigned

    Labels

    help wantedExtra attention is needed

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions