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

ROS Threading, AsyncSpinners and Control

asked 2016-08-11 09:26:09 -0500

alecive gravatar image

updated 2016-08-17 11:04:52 -0500

Hello everybody,

I am a relatively new ROS user (but I've spent years working with other middlewares), and up to now I am generally happy about it. I have a doubt related to my software framework I would like to clarify. To this end, I will describe the framework I have, so that some more experienced ROS user can tell me where I am doing wrong:

  • I have a node that is composed of two controllers (one for each of the Baxter's arms). Each controller subscribes to a variety of topics and publishes to a variety of topics. They are implemented as classes, and they both use an AsyncSpinner.
  • This is a pseudo-code of my framework. In the main:

    int main()
    {
        Controller c1("left");
        Controller c2("right");
    
        ros::spin();
    }
    

    in the constructors:

    Controller::Controller(string limb): _limb(limb), spinner(4)
    {
        ...
    
        spinner.start();
    }
    

    Question 1: is this a correct initialization of an AsyncSpinner? Right now I have two AsyncSpinners that are initialized in the same process/node. Question 2: Do they share the same 4 threads? I am not using custom callback queues.

  • A part from subscribing to topics, both controllers have a main control loop that I implemented as a pthread, which runs in parallel with everything else. It is crucial for my pthreads to have a constant control rate of at least 100Hz, but at the same time I would like to update the information coming from the subscribers while the thread is doing its job. What I did to this end was the following pseudo code related to the run() of the thread:

    pthread_run()
    {
        while(ros::ok())
        {
            ...
    
            ros::spinOnce();
            ros::Rate(100).sleep();
        }
    }
    

    Question 3: with the presence of an AsyncSpinner, is the ros::spinOnce() necessary, or can I remove it? As far as I understood I should not need a ros::spinOnce(), because my callback queue is guaranteed to be emptied in the other three threads I fed the spinner with. Is it correct?

  • No matter what I try, some times I experience dropped frames in my pthreads, which negatively affect my control loop. The reasons for this might be multiple (delays in the network, etc), but here is my Question 4: is this issue related to how I implemented my code? As a matter of fact, this is the main reason for which created this question. I am sure it is not a CPU load problem.
  • I was thinking of dropping altogether the pthreads and implementing the control loops as callbacks that I would then add to the ros::getGlobalCallbackQueue() so that I do not have to take care of the threading at all. Question 5: does this make any sense, or is it going to solve my problem?

Thank you for your help. I know that some of this questions might seems stupid, but I didn't find anything useful online, and I would like to use ROS to the best of its capabilities.

Answer to kramer: thank you for ... (more)

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
2

answered 2016-08-11 18:30:56 -0500

kramer gravatar image

I think this is much more complicated than it needs to be, particularly since you're not using custom callback queue(s). As I see it, the key concept to latch onto here is that all received messages go through a callback queue, each processed when a spin occurs. The primary simplifying factor here is that you only have a single callback queue (the global callback queue), with the result that a single ros::spin(), MultiThreadedSpinner::spin(), or AsyncSpinner.start() will process all queued messages as quickly as possible (that is, when a thread is available; not spinOnce).

One minor digression: it's not clear to me what dropped frames means here (in the pthreads loop). I'm guessing it means the loop sometimes runs slower than 100Hz, but it could mean you're occasionally dropping or missing message data. I think either might be the case:

  1. The former makes some sense to me, as a spinOnce will block while a callback is performed; if the callback takes longer than 10ms, it'll throw off your timing. Actually, as your code is written, I'm pretty sure it will throw off you timing, since you instantiate a new ros::Rate inside the loop. If I have this right, the time for a given loop iteration will be the sum of the time to process a callback, assuming there is one, plus a 10ms sleep.
  2. The latter also seems possible to me, as a callback handled by one of the AsyncSpinner threads in its entirety while blocked on the spinOnce might appear to be lost (depending on your data handling).

Pulling back out of the digression, it seems to me you might be better served by using a MultiThreadedSpinner, removing the AsyncSpinner from the Controller class, like so:

int main() {
    Controller c1("left");
    Controller c2("right");
    // start controller threads
    ros::MultiThreadedSpinner spinner(8); // 8 = 4 per controller
    spinner.spin();
}

The Controller class can retain its thread (which would need to be started prior to calling spinner.spin()), but modified like so:

pthread_run() {
    ros::Rate r(100);
    while(ros::ok()) {
        ...
        r.sleep();
    }
}

You might also want to look at (recommended) using Timers instead of ros::Rate (which utilize the callback queue -- see (5) below). Now, to your questions:

  1. Yes, correct initialization (as described, maybe not as desired)
  2. No, they use different threads
  3. The spinOnce can be removed
  4. I think item (1) in my discussion of dropped frames is the issue; if so, then yes, it's your implementation
  5. Since I don't know what is in your control loops, I don't know if it makes sense to put that functionality in callbacks. But it's plausible -- for instance, it could be done with a Timer's callback method.

Honestly, though, I think just moving the ros::Rate instantiation outside the loop will solve your most important issue.

edit flag offensive delete link more

Comments

Hello kramer, thank you for the reply! I answered to you by editing my first post.

alecive gravatar image alecive  ( 2016-08-17 11:05:11 -0500 )edit

I'll try to get back to this later, but I wanted to explain: having the ros::Rate instantiation inside the loop will always sleep ~10ms; having it outside the loop will cause the sleep to be ~10ms minus the prior time in the loop. Inside: 10ms+callback (callback may be ~0); outside: ~10ms.

kramer gravatar image kramer  ( 2016-08-17 23:49:20 -0500 )edit

I should say that I expected there to be maybe an extra 10ms in your loop (dependent, of course, on what the ... represents). I didn't expect up to 1s delays, which seems...odd, to say the least.

kramer gravatar image kramer  ( 2016-08-17 23:57:29 -0500 )edit

Without seeing actual code, I'm not able to add much. I now think your pthread execution operates differently than I expected, so can't help more.

kramer gravatar image kramer  ( 2016-08-19 09:37:56 -0500 )edit

kramer, sorry for the delay: I wanted to perform some more testing before coming back to you. I'm starting to think that the 1s delays are caused by spikes in the network usage that top up the bandwidth. I am changing my code in order to address this. I'll answer you when I will have more info.

alecive gravatar image alecive  ( 2016-08-19 18:34:18 -0500 )edit

@kramer , I dug deeper into the issue. Apparently, it was not an issue in my code, nor the network: rather, the service request I was asking (that is, an IK call for the Baxter robot), some times got stuck into its computation. Changing the IK solver solved the issue altogether. Thank you!

alecive gravatar image alecive  ( 2016-12-05 11:06:57 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2016-08-11 09:26:09 -0500

Seen: 2,567 times

Last updated: Aug 17 '16