ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

why MultiThreadedExecutor act as SingleThreaded?

asked 2020-09-22 05:16:55 -0500

erinliu gravatar image

updated 2020-09-22 20:53:16 -0500

Hi

I'm testing rclcpp::executors::MultiThreadedExecutor. I wrote two Subscription in a node, and at each callback function sleep for 10 seconds. I thought those two callback funcs would be executed at the same time, but in fact, one of them would not be executed until 10 seconds after the other started. here is the code. Does anyone have any ideas? Thank for your time

#include <rclcpp/rclcpp.hpp> 
#include <std_msgs/msg/int32.hpp>
using namespace std::chrono_literals;
std::string getTime(){
    time_t tick = (time_t)(rclcpp::Clock().now().seconds());
    struct tm tm;
    char s[100];
    tm = *localtime(&tick);
    strftime(s, sizeof(s), "%Y-%m-%d %H:%M:%S", &tm);
    return std::string(s);
}
class MyNode: public rclcpp::Node{
public:
    MyNode(const rclcpp::NodeOptions & options);
    ~MyNode(){}
    void int1Sub(std_msgs::msg::Int32::SharedPtr msg);
    void int2Sub(std_msgs::msg::Int32::SharedPtr msg);

private:
    rclcpp::Subscription<std_msgs::msg::Int32>::SharedPtr int_sub1_;
    rclcpp::Subscription<std_msgs::msg::Int32>::SharedPtr int_sub2_;
}
MyNode::MyNode(const rclcpp::NodeOptions & options):
    rclcpp::Node("my_node",options){
int_sub1_ = nh_->create_subscription<std_msgs::msg::Int32>("int1",10,
        std::bind(&MyNode::int1Sub,this,std::placeholders::_1));
int_sub2_ = nh_->create_subscription<std_msgs::msg::Int32>("int2",10,
        std::bind(&MyNode::int2Sub,this,std::placeholders::_1));
}
void MyNode::int1Sub(std_msgs::msg::Int32::SharedPtr msg){
    printf("int1 sub time:%s\n",getTime().c_str());
    rclcpp::sleep_for(10s);
    printf("int1 sub time:%s\n",getTime().c_str());
}
void MyNode::int2Sub(std_msgs::msg::Int32::SharedPtr msg){
    printf("int2 sub time:%s\n",getTime().c_str());
    rclcpp::sleep_for(10s);
    printf("int2 sub time:%s\n",getTime().c_str());
}
int main(int argc, char **argv) {
    rclcpp::init(argc, argv);
    rclcpp::executors::MultiThreadedExecutor executor(rclcpp::executor::ExecutorArgs(),5,true);

    auto node = std::make_shared<MyNode>(rclcpp::NodeOptions());
    executor.add_node(node);
    printf("threads   %d\n",executor.get_number_of_threads());
    executor.spin();
    rclcpp::shutdown();
    return EXIT_SUCCESS;
}
edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
1

answered 2020-09-22 06:28:20 -0500

allenh1 gravatar image

I believe you need to create callback groups in order to leverage the MultiThreadedExecutor.

You must explicitly state which callbacks are mutually exclusive.

You can find an example here.

edit flag offensive delete link more

Comments

In the question there are two nodes. But in your link there is only one node. How to transfer callback groups between nodes? Anyway thank you for your answer.

rrrand gravatar image rrrand  ( 2020-09-22 08:04:39 -0500 )edit

Thank you very much!Your answer solved my problem.

erinliu gravatar image erinliu  ( 2020-09-22 21:32:40 -0500 )edit
1

@rrrand I am confused as to what you mean. I only see one node in the question with two callbacks.

allenh1 gravatar image allenh1  ( 2020-09-25 07:04:38 -0500 )edit

@allenh1 Thank you for pointing it. My fault.

rrrand gravatar image rrrand  ( 2020-09-25 07:46:52 -0500 )edit

Question Tools

4 followers

Stats

Asked: 2020-09-22 05:16:55 -0500

Seen: 588 times

Last updated: Sep 22 '20