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

getMTNodeHandle doesn't result in more callbacks in parallel on a single topic #77

Closed
lucasw opened this issue Jul 28, 2018 · 2 comments

Comments

@lucasw
Copy link
Contributor

lucasw commented Jul 28, 2018

From https://answers.ros.org/question/298750/getmtnodehandlegetmtprivatenodehandle-doesnt-result-in-additional-callbacks-but-does-take-more-cpu/

I assumed from the line "getMTNodeHandle() and getMTPrivateNodeHandle() callbacks will be distributed over the thread pool of the manager" from http://wiki.ros.org/nodelet#Threading_Model that switching a subscriber in a nodelet from using getNodeHandle() would result in callbacks on a single topic distributed over threads available in the nodelet manager pool and would result in a higher callback rate when a single thread can't keep up.

What I've found in https://github.com/lucasw/nodelet_demo is that there are no additional callbacks, but I can see a huge increase in cpu.

Does a single topic callback still only get one thread, but multiple callbacks for multiple topics could take as many threads as there are topics? I'll test this out.

Are there additional steps to make a nodelet multi-threaded?

A possible limited workaround would be to have a generic demultiplexer nodelet (which ought to be nearly zero cost with no copies or deserializations) and multiple instances of the nodelet subscribing to 1/n of the upstream topic rate. Or if the above comment about a given topic being single thread is true, a single nodelet could have multiple subscribers to the multiple topics that the demux distributed.

Related to #25

@lucasw lucasw changed the title getMTNodeHandle doesn't result in more callbacks in parallel getMTNodeHandle doesn't result in more callbacks in parallel on a single topic Jul 28, 2018
lucasw added a commit to lucasw/nodelet_demo that referenced this issue Jul 28, 2018
… callback topic is still single threaded, the multi threading is only across different subscribers ros/nodelet_core#77
@drjsmith
Copy link

By default, concurrent callbacks by the same Subscriber are not allowed. However, you can enable them by setting the allow_concurrent_callbacks field of the SubscribeOptions to true.

This issue explains the increase in cpu.

lucasw added a commit to lucasw/nodelet_demo that referenced this issue Sep 23, 2021
@lucasw
Copy link
Contributor Author

lucasw commented Sep 23, 2021

Thanks, I got that working like this and I can see the concurrency happening correctly:

ros::Subscriber sub1_;
...
ros::SubscribeOptions so1;
so1.init<std_msgs::Float32>(
      "input1",
      input_queue_size,
      boost::bind(&NodeletDemo::callback, this, _1));

so1.allow_concurrent_callbacks = true;

sub1_ = nh.subscribe(so1);

https://github.com/lucasw/nodelet_demo/blob/6160a2f28b351ee4da76ed48111a2927cb05972f/nodelet_demo/src/nodelet_demo.cpp#L127

@lucasw lucasw closed this as completed Sep 23, 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