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

Attempt to spin a callback queue from two spinners, one of them being single-threaded

asked 2019-01-24 04:29:38 -0600

updated 2019-01-24 04:30:20 -0600

Hello, I followed this guide to implement a controller for my rotary stage. Everything works just fine, but when I launch my controller, I get the following error (which does not impair the functionality of my controller btw.):

[ERROR] [1548319318.740806716]: SpinnerMonitor: single-threaded spinner after multi-threaded one(s).Attempt to spin a callback queue from two spinners, one of them being single-threaded. In the future this will throw an exception! Only allowed for backwards compatibility.

The error is probably caused, when executing my controller executable of my hardware interface. The code, where I create my hardware interface looks like this:

#include "urs100_hardware_interface/urs100_hardware_interface.h"

int main(int argc, char** argv)
{
ros::init(argc, argv, "urs100_hardware_interface");
ros::NodeHandle nh;
ros::AsyncSpinner spinner(1);
spinner.start();
urs100_hardware_interface::Urs100HardwareInterface Urs100Stage(nh);
ros::spin();
return 0;
}

Does anyone know how I can get rid of that error? I already tried to get rid of the ros::spin() and put the spinner.start() right before the return. Would really like to know how to implement this spinning functionality properly.

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
2

answered 2019-01-24 05:04:02 -0600

gvdhoorn gravatar image

You have:

int main(int argc, char** argv)
{
  [..]
  ros::AsyncSpinner spinner(1);
  spinner.start();
  [..]
  ros::spin();
  return 0;
}

That ros::spin() should not be used here, as AsyncSpinner is already processing your queues (that's what the error message also tells you).

If you don't have some other blocking action in your control flow of the node, you can use ros::waitForShutdown().

See the comments on ros::AsyncSpinner on the ROS wiki: roscpp/Overview/Callbacks and Spinning: Multi-threaded Spinning.

edit flag offensive delete link more

Comments

Thanks for your answer. The following code worked for me:

ros::init(argc, argv, "urs100_hardware_interface");
ros::NodeHandle nh;
ros::AsyncSpinner spinner(2);
urs100_hardware_i
nmelchert gravatar image nmelchert  ( 2019-01-24 06:26:34 -0600 )edit

Your last comment confuses me: that is not a typical flow of control I would expect with a hw interface.

gvdhoorn gravatar image gvdhoorn  ( 2019-01-24 06:42:24 -0600 )edit

When I writing the hardware interface, I implemented a blocking method and a non blocking method to move the stage. I know that blocking functions are not supposed to be in the hw interface since it harms the sampling time of the controller, but this just worked fine for me.

nmelchert gravatar image nmelchert  ( 2019-01-24 06:46:47 -0600 )edit

As long as you're aware that you're breaking the (implicit) contract between you and whatever is loading and spinning your hw interface implementation.

gvdhoorn gravatar image gvdhoorn  ( 2019-01-24 11:40:55 -0600 )edit

Excuse me sir, did you manage to make it works? I'm trying the same process but got this message error: Segmentation fault (core dumped) Also i changed the ros::spin() for ros::waitForShutdown(), so i'll appreciate if you could help me

Jose_M gravatar image Jose_M  ( 2019-02-20 20:54:58 -0600 )edit

Hi, this is, what worked for me:

ros::init(argc, argv, "urs100_hardware_interface");
ros::NodeHandle nh;
ros::AsyncSpinner spinner(2);
urs100_hardware_interface::Urs100HardwareInterface Urs100Stage(nh);
spinner.start();
ros::waitForShutdown();
nmelchert gravatar image nmelchert  ( 2019-02-21 02:03:00 -0600 )edit

You might have to adjust the thread count depending on your needs.

nmelchert gravatar image nmelchert  ( 2019-02-21 02:07:05 -0600 )edit

Question Tools

2 followers

Stats

Asked: 2019-01-24 04:29:38 -0600

Seen: 2,796 times

Last updated: Jan 24 '19