Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Maximum number of entities per node #563

Closed
alsora opened this issue Oct 1, 2021 · 3 comments
Closed

Maximum number of entities per node #563

alsora opened this issue Oct 1, 2021 · 3 comments

Comments

@alsora
Copy link
Contributor

alsora commented Oct 1, 2021

Bug report

Required Info:

  • Operating System:
    • Ubuntu 20.04
  • Installation type:
    • Binaries
  • Version or commit hash:
    • ROS 2 Galactic
  • DDS implementation:
    • Fast-RTPS
  • Client library (if applicable):
    • rclcpp

Steps to reproduce issue

The following snippet creates and spins a ROS 2 node with a bunch of dummy entities.
In total it has 1 action server, 2 action clients, 1 parameters client, 5 subscriptions.
For the sake of testing, all entities use the same type of message (Fibonacci actions and Odometry messages) but the problem is present even if they would all use different types.

#include <memory>

#include "example_interfaces/action/fibonacci.hpp"
#include "nav_msgs/msg/odometry.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_action/rclcpp_action.hpp"

using std::placeholders::_1;
using std::placeholders::_2;

class TestNode : public rclcpp::Node
{
public:
    TestNode()
    : rclcpp::Node("test_node")
    {
        m_impossible_action_server = rclcpp_action::create_server<FibonacciAction>(
            this->get_node_base_interface(),
            this->get_node_clock_interface(),
            this->get_node_logging_interface(),
            this->get_node_waitables_interface(),
            "impossible_action",
            std::bind(&TestNode::handle_goal, this, _1, _2),
            std::bind(&TestNode::handle_cancel, this, _1),
            std::bind(&TestNode::handle_accepted, this, _1));

        m_action_client1 = rclcpp_action::create_client<FibonacciAction>(
            this->get_node_base_interface(),
            this->get_node_graph_interface(),
            this->get_node_logging_interface(),
            this->get_node_waitables_interface(),
            "dummy_action1");

        m_action_client2 = rclcpp_action::create_client<FibonacciAction>(
            this->get_node_base_interface(),
            this->get_node_graph_interface(),
            this->get_node_logging_interface(),
            this->get_node_waitables_interface(),
            "dummy_action2");
                
        m_param_client = std::make_shared<rclcpp::AsyncParametersClient>(
            this->get_node_base_interface(),
            this->get_node_topics_interface(),
            this->get_node_graph_interface(),
            this->get_node_services_interface(),
            "dummy_remote_node",
            rmw_qos_profile_parameters);

        m_sub1 = this->create_subscription<OdometryMsg>(
            "dummy_topic_sub1",
            rclcpp::SensorDataQoS(),
            [](OdometryMsg::ConstSharedPtr msg) { (void)msg; });

        m_sub2 = this->create_subscription<OdometryMsg>(
            "dummy_topic_sub2",
            rclcpp::SensorDataQoS(),
            [](OdometryMsg::ConstSharedPtr msg) { (void)msg; });

        m_sub3 = this->create_subscription<OdometryMsg>(
            "dummy_topic_sub3",
            rclcpp::SensorDataQoS(),
            [](OdometryMsg::ConstSharedPtr msg) { (void)msg; });

        m_sub4 = this->create_subscription<OdometryMsg>(
            "dummy_topic_sub4",
            rclcpp::SensorDataQoS(),
            [](OdometryMsg::ConstSharedPtr msg) { (void)msg; });

        m_sub5 = this->create_subscription<OdometryMsg>(
            "dummy_topic_sub5",
            rclcpp::SensorDataQoS(),
            [](OdometryMsg::ConstSharedPtr msg) { (void)msg; });

        RCLCPP_INFO(this->get_logger(), "Node created!");
    }

private:
    using FibonacciAction = example_interfaces::action::Fibonacci;
    using GoalHandleFibonacci = rclcpp_action::ServerGoalHandle<FibonacciAction>;
    using OdometryMsg = nav_msgs::msg::Odometry;

    rclcpp_action::GoalResponse
    handle_goal(
        const rclcpp_action::GoalUUID& uuid,
        std::shared_ptr<const FibonacciAction::Goal> goal)
    {
        (void)uuid;
        (void)goal;

        RCLCPP_INFO(this->get_logger(), "Accepting goal request");
        return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
    }

    rclcpp_action::CancelResponse
    handle_cancel(
        const std::shared_ptr<GoalHandleFibonacci> goal_handle)
    {
        (void)goal_handle;

        RCLCPP_INFO(this->get_logger(), "Received request to cancel goal");
        return rclcpp_action::CancelResponse::ACCEPT;
    }


    void handle_accepted(const std::shared_ptr<GoalHandleFibonacci> goal_handle)
    {
        RCLCPP_INFO(this->get_logger(), "Executing goal");

        auto result = std::make_shared<FibonacciAction::Result>();
        goal_handle->succeed(result);
    }

    rclcpp_action::Server<FibonacciAction>::SharedPtr m_impossible_action_server;

    rclcpp_action::Client<FibonacciAction>::SharedPtr m_action_client1;
    rclcpp_action::Client<FibonacciAction>::SharedPtr m_action_client2;

    rclcpp::AsyncParametersClient::SharedPtr m_param_client;

    rclcpp::Subscription<OdometryMsg>::SharedPtr m_sub1;
    rclcpp::Subscription<OdometryMsg>::SharedPtr m_sub2;
    rclcpp::Subscription<OdometryMsg>::SharedPtr m_sub5;
    rclcpp::Subscription<OdometryMsg>::SharedPtr m_sub4;
    rclcpp::Subscription<OdometryMsg>::SharedPtr m_sub3;
};

int main(int argc, char ** argv)
{
    rclcpp::init(argc, argv);
    auto node = std::make_shared<TestNode>();
    rclcpp::spin(node);
    rclcpp::shutdown();

    return 0;
}

Actual behavior

With this configuration, an action client is not able to communicate with the action server created by this node.
Running the aforementioned node and then, in a separate terminal running

$ ros2 action send_goal /impossible_action example_interfaces/action/Fibonacci "{}"
Waiting for an action server to become available...

Additional notes

Removing any of the entities (e.g. 1 subscription or 1 action client) fixes the problem
Indeed I noticed it because after adding the fifth subscription the server stopped working.

This example works with cyclonedds.

@MiguelCompany
Copy link
Collaborator

I could reproduce this with the osrf/ros:galactic-desktop docker image. After an apt upgrade everything worked fine, though.

I guess it could have been fixed on #547. Most probably the RTPS alignment issue was responsible.

@alsora
Copy link
Contributor Author

alsora commented Oct 4, 2021

Thank you, I confirm that the issue is fixed after upgrading the repositories.
Do you know which rmw_fastrtps versions contain the fix?

@MiguelCompany
Copy link
Collaborator

Galactic: 5.0.1 onwards
Rolling: 5.2.2 onwards

I think foxy still needs a backport of #550

@alsora alsora closed this as completed Oct 4, 2021
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

2 participants