[ros2][humble] Service callback blocks subscriber with MultiThreadedExecutor

asked 2023-04-03 05:22:40 -0500

lem2300 gravatar image
  • Operating System: Ubuntu 22.04
  • Installation type: binary
  • Version or commit hash: humble
  • DDS implementation: default
  • Client library (if applicable): rclcpp

Steps to reproduce issue

  1. Create a node with a subscriber and a service.
  2. Either use two MutuallyExclusive or one Reentrant callback group.
  3. Spin the node in a MultiThreadedExecutor

#include <chrono>
#include <functional>
#include <memory>
#include <string>

#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
#include "std_srvs/srv/empty.hpp"

using namespace std::placeholders;

class MultiThreadedNode : public rclcpp::Node
{
public:
    MultiThreadedNode()
    : Node("multi_threaded_node")
    {
        auto default_qos = rclcpp::QoS(10);
        cb_group_1_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
        cb_group_2_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
        cb_group_3_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);

        rclcpp::SubscriptionOptions sub_options;
        sub_options.callback_group = cb_group_1_;

        subscriber_ = create_subscription<std_msgs::msg::String>(
            "chatter",
            default_qos, 
            std::bind(&MultiThreadedNode::subscriber_callback, this, _1),
            sub_options);

        service_ = create_service<std_srvs::srv::Empty>(
            "service",
            std::bind(&MultiThreadedNode::service_callback, this, _1, _2),
            rmw_qos_profile_default,
            cb_group_2_);

        timer_ = create_wall_timer(
            std::chrono::seconds(2),
            std::bind(&MultiThreadedNode::timer_callback, this),
            cb_group_3_);
    }
private:
    void subscriber_callback(const std_msgs::msg::String::SharedPtr msg)
    {
        (void)msg;
        RCLCPP_INFO(get_logger(), ".");
    }

    void service_callback(
        const std_srvs::srv::Empty::Request::SharedPtr req,
        const std_srvs::srv::Empty::Response::SharedPtr res)
    {
        (void)req;
        (void)res;
        RCLCPP_INFO(this->get_logger(), "enter service callback");
        for (size_t i = 0; i < 10; i++)
        {
            RCLCPP_INFO(this->get_logger(), "#");
            std::this_thread::sleep_for(std::chrono::milliseconds(100));
        }
        RCLCPP_INFO(this->get_logger(), "exit service callback");
    }

    void timer_callback()
    {
        RCLCPP_INFO(this->get_logger(), "enter timer callback");
        for (int i = 0; i < 10; ++i) {
            RCLCPP_INFO(this->get_logger(), "+");
            std::this_thread::sleep_for(std::chrono::milliseconds(100));
        }
        RCLCPP_INFO(this->get_logger(), "exit timer callback");
    }

    rclcpp::CallbackGroup::SharedPtr cb_group_1_;
    rclcpp::CallbackGroup::SharedPtr cb_group_2_;
    rclcpp::CallbackGroup::SharedPtr cb_group_3_;

    rclcpp::Subscription<std_msgs::msg::String>::SharedPtr subscriber_;
    rclcpp::Service<std_srvs::srv::Empty>::SharedPtr service_;
    rclcpp::TimerBase::SharedPtr timer_;

};

int main(int argc, char * argv[])
{
    rclcpp::init(argc, argv);

    auto node = std::make_shared<MultiThreadedNode>();
    rclcpp::executors::MultiThreadedExecutor executor;
    executor.add_node(node);
    executor.spin();

    rclcpp::shutdown();
    return 0;
}

Expected behavior

Calling the service should not block the subscriber or the timer.

Actual behavior

Calling the service blocks the subscriber but not the timer.

[INFO] [1680471757.115031455] [multi_threaded_node]: .
[INFO] [1680471757.314653746] [multi_threaded_node]: .
[INFO] [1680471757.514849401] [multi_threaded_node]: .
[INFO] [1680471757.714504254] [multi_threaded_node]: .
[INFO] [1680471757.807676140] [multi_threaded_node]: enter timer callback
[INFO] [1680471757.807809920] [multi_threaded_node]: +
[INFO] [1680471757.908003562] [multi_threaded_node]: +
[INFO] [1680471757.915152829] [multi_threaded_node]: .
[INFO] [1680471758.008272385] [multi_threaded_node]: +
[INFO] [1680471758.108555032] [multi_threaded_node]: +
[INFO] [1680471758.114981067] [multi_threaded_node]: .
[INFO] [1680471758.208821078] [multi_threaded_node]: +
[INFO] [1680471758.296828261] [multi_threaded_node]: enter service callback
[INFO] [1680471758.296945886] [multi_threaded_node]: #
[INFO] [1680471758.309048233] [multi_threaded_node]: +
[INFO] [1680471758.397140516] [multi_threaded_node]: #
[INFO] [1680471758.409268071] [multi_threaded_node]: +
[INFO] [1680471758.497408827] [multi_threaded_node]: #
[INFO] [1680471758.509478168] [multi_threaded_node]: +
[INFO] [1680471758.597679190] [multi_threaded_node]: #
[INFO] [1680471758.609651464] [multi_threaded_node]: +
[INFO] [1680471758.697816595] [multi_threaded_node]: #
[INFO] [1680471758.709744064] [multi_threaded_node]: +
[INFO] [1680471758.797935812] [multi_threaded_node]: #
[INFO] [1680471758.809839482] [multi_threaded_node]: exit timer callback
[INFO] [1680471758.898066940] [multi_threaded_node]: #
[INFO] [1680471758.998168237] [multi_threaded_node]: #
[INFO] [1680471759.098295381] [multi_threaded_node]: #
[INFO] [1680471759.198418182] [multi_threaded_node]: #
[INFO] [1680471759.298543627] [multi_threaded_node]: exit service callback
[INFO] [1680471759.305546736] [multi_threaded_node]: .
[INFO] [1680471759.514772973] [multi_threaded_node]: .
[INFO] [1680471759.714968133] [multi_threaded_node]: .
[INFO] [1680471759.807685939] [multi_threaded_node]: enter timer callback
[INFO] [1680471759.807810022] [multi_threaded_node]: +
[INFO] [1680471759.908048993] [multi_threaded_node]: +
[INFO] [1680471759.914723904] [multi_threaded_node]: .
[INFO] [1680471760.008308786] [multi_threaded_node]: +
[INFO] [1680471760.108570934] [multi_threaded_node]: +
[INFO] [1680471760.114304442] [multi_threaded_node]: .
[INFO] [1680471760.208807294] [multi_threaded_node]: +
[INFO] [1680471760.309081122 ...
(more)
edit retag flag offensive close merge delete