getMTNodeHandle/getMTPrivateNodeHandle doesn't result in additional callbacks, but does take more cpu
I've made an example nodelet https://github.com/lucasw/nodelet_demo that has a callback that takes a lot of time to complete, more time than is available before the next message is received. For non-nodelets in the past I've successfully used asyncspinners to handle that case (TODO make an example of that in same repo above), but with nodelets I see the following behavior:
The MTNodeHandle callback gets called no more often than the regular NodeHandle one. The nodelet manager in my case declares it has 8 worker threads, and in a more complex situation (not shown in the example, TODO add it later) I can see that multiple nodelets do spread across multiple threads.
The cpu usage goes way up (top
show 500% cpu instead of 100%, 800% being the max for my cpu) when using the MTNodeHandle, as if what are otherwise dropped messages for single threads are still eating up cpu somewhere, but there is no external indication- no additional log messages from the callback or publishes from within the callback are seen.
void NodeletDemo::callback(const std_msgs::Float32ConstPtr& msg)
{
ROS_INFO_STREAM("cpu id " << get_cpu_id() << ", count " << msg->data);
// track cpu usage if true
bool busy_wait = true;
if (!busy_wait)
{
ros::Duration(callback_delay_).sleep();
}
else
{
ros::Time t0 = ros::Time::now();
while ((ros::Time::now() - t0).toSec() < callback_delay_)
{
}
}
pub_.publish(msg);
}
...
nh = getMTNodeHandle();
sub_ = nh.subscribe("input", input_queue_size,
&NodeletDemo::callback, this);
The default delay is 1.0 seconds, these launches result in 10 times as many messages being sent as a single threaded callback is able to handle:
roslaunch nodelet_demo demo.launch period:=0.1 mt_callback:=false
roslaunch nodelet_demo demo.launch period:=0.1 mt_callback:=true
Should I instance more nodelets of the same type into the manager subscribing to the same topics, and they will get messages distributed to them properly? This works as long as information doesn't need to be shared between the instances- that could be handled with addtional topics but is more cumbersome than using asyncspinner (though the likely required mutex locks could be equally or more cumbersome). Update Trying this crashes the nodelet manager.
Multiple subs to the same topic within the same nodelet? (I don't think that works elsewhere, but maybe here?) Update Trying this crashes the nodelet manager.
Update Trying to create an async spinner within the nodelet results in the error AsyncSpinnerImpl: Attempt to spin a callback queue from two spinners, one of them being single-threaded.
In the future this will throw an exception!
Which is maybe a clue to what is going wrong- is the nodelet locked in to be single threaded at a higher level?
Is there a good online example of using getMTNodeHandle()?
Created https://github.com/ros/nodelet_core/i...