Robot's hardware interface as node or plugin

363 views
Skip to first unread message

Mike Purvis

unread,
Jul 16, 2014, 4:55:57 PM7/16/14
to ros-sig-ro...@googlegroups.com
Hi all,

I'm just getting started with ros_control and attempting to understand a bit better how things are expected to be done, and had a quick question about the diffbot example/tests supplied with diff_drive_controller.

Specifically, is this AsyncSpinner business idiomatic ros_control? Given that diff_drive_controller is really only closing the loop around one input (encoders), I'd prefer to trigger the controller update right from that callback, rather than having the callback message cached and consumed in a separate asynchronous rate-loop (thus introducing an unknown and variable delay between data-in and command-out).

Even if it were going to be an asynchronous loop, wouldn't you just call the update from a Timer callback and spin as usual?

Adolfo Rodríguez Tsouroukdissian

unread,
Jul 17, 2014, 4:50:24 AM7/17/14
to Mike Purvis, ros-sig-ro...@googlegroups.com
On Wed, Jul 16, 2014 at 10:55 PM, Mike Purvis <mpu...@clearpathrobotics.com> wrote:
Hi all,

I'm just getting started with ros_control and attempting to understand a bit better how things are expected to be done, and had a quick question about the diffbot example/tests supplied with diff_drive_controller.

Specifically, is this AsyncSpinner business idiomatic ros_control? Given that diff_drive_controller is really only closing the loop around one input (encoders), I'd prefer to trigger the controller update right from that callback, rather than having the callback message cached and consumed in a separate asynchronous rate-loop (thus introducing an unknown and variable delay between data-in and command-out).

Hey Mike,

There's two aspects to your question,

1. Tests:

The AsyncSpinners in the tests are there to service test-specific callbacks. When we call gtest's RUN_ALL_TESTS() we lose control of the main thread, so a separate thread is needed for spinning. You'll see that most tests of the diff_drive_controller package include the "test_common.h" header, which defines a class containing a Subscriber, hence the need of a spinner thread.

2. How the controller_manager works, and how RobotHW specializations are implemented:

The control loop managed by the controller_manager runs in a periodic and potentially realtime thread. That is, at a fixed periodic sequence, the controller_manager will call update(...) on all running controllers. OTOH, callbacks such as those coming from subscribers, service servers and action servers are asynchronous and non-realtime. The general approach when implementing a RobotHW specialization is then to setup a (realtime) thread for updating the controller_manager, and a separate non-realtime thread for callback processing. Note that controllers are not explicitly aware of this: Their update(...) method is called by 'someone', who just happens to be a realtime thread, and the controller's subscribers and action/service servers are registered to NodeHandles that are passed along the init(...) method, which just happen to be associated to an AsyncSpinner or similar.

One of the reasons why the controller_manager is synchronous, is that all controller updates are serialized in a single thread, in sequence, which results in a simpler implementation where no (realtime) concurrency needs to be handled. A fully asynchronous model does have its merits, but implies a more complex implementation.


Cheers,

Adolfo.


Even if it were going to be an asynchronous loop, wouldn't you just call the update from a Timer callback and spin as usual?

--
You received this message because you are subscribed to the Google Groups "ROS/Orocos Robot Control Special Interest Group" group.
To unsubscribe from this group and stop receiving emails from it, send an email to ros-sig-robot-co...@googlegroups.com.
For more options, visit https://groups.google.com/d/optout.



--
Adolfo Rodríguez Tsouroukdissian
Senior robotics engineer
adolfo.r...@pal-robotics.com
http://www.pal-robotics.com

PAL ROBOTICS S.L
c/ Pujades 77-79, 4º4ª
08005 Barcelona, Spain.
Tel. +34.93.414.53.47
Fax.+34.93.209.11.09
Skype: adolfo.pal-robotics
Facebook - Twitter - PAL Robotics YouTube Channel

AVISO DE CONFIDENCIALIDAD: Este mensaje y sus documentos adjuntos, pueden contener información privilegiada y/o confidencial que está dirigida exclusivamente a su destinatario. Si usted recibe este mensaje y no es el destinatario indicado, o el empleado encargado de su entrega a dicha persona, por favor, notifíquelo inmediatamente y remita el mensaje original a la dirección de correo electrónico indicada. Cualquier copia, uso o distribución no autorizados de esta comunicación queda estrictamente prohibida.

CONFIDENTIALITY NOTICE: This e-mail and the accompanying document(s) may contain confidential information which is privileged and intended only for the individual or entity to whom they are addressed.  If you are not the intended recipient, you are hereby notified that any disclosure, copying, distribution or use of this e-mail and/or accompanying document(s) is strictly prohibited.  If you have received this e-mail in error, please immediately notify the sender at the above e-mail address.

Mike Purvis

unread,
Jul 17, 2014, 8:37:20 AM7/17/14
to Adolfo Rodríguez Tsouroukdissian, ros-sig-ro...@googlegroups.com
HI Adolfo,

This is helpful to understand, thanks.

In my particular case, the telemetry is coming in at 50Hz from a single source (USB-connected microcontroller). Given that, I'd prefer to just trigger the global controller update right from my telemetry callback. It doesn't sound like it really matters where the update() method is called from, so long as it's regular.

If I decide to go to the realtime thread approach in the future, you'd recommend SCHED_FIFO plus a pam_limits setting for the ros user?

Mike

Adolfo Rodríguez Tsouroukdissian

unread,
Jul 17, 2014, 9:28:02 AM7/17/14
to Mike Purvis, ros-sig-ro...@googlegroups.com
On Thu, Jul 17, 2014 at 2:36 PM, Mike Purvis <mpu...@clearpathrobotics.com> wrote:
HI Adolfo,

This is helpful to understand, thanks.

In my particular case, the telemetry is coming in at 50Hz from a single source (USB-connected microcontroller).

Do you send commands to the controller at 50Hz as well?.

The maximum delay you could have between a command callback being serviced and it getting processed by the update(...) method is one control cycle. Is your setup sensible to such command variations?. If so, would it make sense to push some of the logic that requires tighter integration with the control loop inside a controller?. Considering that commands are sent through ROS interfaces, and are themselves not very deterministic because of the ROS transport, it is typical that they refresh at lower rates than the actual control (e.g., one order of magnitude or more).

Even if your control loop is deterministic, the commands you send will in general come from SCHED_OTHER-scheduled tasks, living potentially in another machine. So, not many guarantees on that end.
 
Given that, I'd prefer to just trigger the global controller update right from my telemetry callback. It doesn't sound like it really matters where the update() method is called from, so long as it's regular.

You could compute actuator commands right in the callback, with no particular gain, but more complexity. The typical control cycle of a RobotHW implementation looks like:

hw.read();
controller_manager.update(time, period);
hw.write();

The current robot state gets refreshed when you hw.read(), so it doesn't matter if your callback is serviced before or after the controller_manager update, it will always use the state from the last read operation. The same goes for hw.write(), you can set command values at any time, but they won't be sent to hardware until hw.write() is called. So no particular gains. The added complexity is that you'd have to now make your code thread-safe, because you're reading and writing joint handles from a different thread than the one used by RobotHW, and hence all other controllers plus the hw.read() and hw.write() methods.
 

If I decide to go to the realtime thread approach in the future, you'd recommend SCHED_FIFO plus a pam_limits setting for the ros user?

I have not done quantitative tests of what can be expected from a stock Linux kernel, or which setting combination works best. We've always used soft- or hard-realtime kernels. For an empirical validation, I'd wreck havoc on the machine from all fronts and measure how latencies behave. The stress(1) command might come in handy here.

HTH,

Adolfo.

Mike Purvis

unread,
Jul 17, 2014, 10:03:53 AM7/17/14
to Adolfo Rodríguez Tsouroukdissian, ros-sig-ro...@googlegroups.com
Do you send commands to the controller at 50Hz as well?.

The maximum delay you could have between a command callback being serviced and it getting processed by the update(...) method is one control cycle. Is your setup sensible to such command variations?. If so, would it make sense to push some of the logic that requires tighter integration with the control loop inside a controller?. Considering that commands are sent through ROS interfaces, and are themselves not very deterministic because of the ROS transport, it is typical that they refresh at lower rates than the actual control (e.g., one order of magnitude or more).

In my scenario, commands to the controller will typically be at 10-20Hz, and it's a ground vehicle, so yes, this line of questioning is borne of curiosity more than actual need.

You could compute actuator commands right in the callback, with no particular gain, but more complexity. The typical control cycle of a RobotHW implementation looks like:

hw.read();
controller_manager.update(time, period);
hw.write();

This is assuming a discrete thread for the hardware/controllers, separate from the ROS thread.

If I want to just call the controller update from a ros::Timer callback, it seems to stall the controller, eg:

void controlCallback(const ros::TimerEvent& te, controller_manager::ControllerManager* cm)
{
  ROS_INFO("up");
  cm->update(te.current_real, te.current_real - te.last_real);
}

int main(int argc, char* argv[])
{
  ros::init(argc, argv, "robot_node");
  ros::NodeHandle nh;
  Robot r;
  controller_manager::ControllerManager cm(&r, nh);
  ros::Timer control_timer = nh.createTimer(ros::Duration(0.02),
      boost::bind(controlCallback, _1, &cm));

  ros::spin()
}

I see a stream of "up" messages until the spawner loads in the controller, then nothing.

Is there something about what the controller manager does which requires it be on a separate thread from ROS?


Adolfo Rodríguez Tsouroukdissian

unread,
Jul 17, 2014, 11:20:05 AM7/17/14
to Mike Purvis, ros-sig-ro...@googlegroups.com
OK, so I initially misunderstood how you wanted to use the timer, that part is fine.

You do need to have two threads, and this is a requirement for not messing up your control loop. From the realtime-friendliness POV, processing ROS callbacks is not realtime safe, so can't be done in the same thread of the control loop. Equally important is the fact that the execution of some callbacks can take arbitrary amounts of time. Take the load_controller service example: it loads a dynamic library, creates a controller instance and then calls the controller's init(...) method. This is all stuff that you don't want messing with your control thread. Even if you don't use a RTOS, a controller's init(...) might take more than one control cycle to initialize a controller. If you've ever loaded a big URDF in init(...) you know how true this is ;-). When there's only one thread, one method blocks all the rest.

So, the control thread should only be concerned about running the control loop, which is the read-update-write cycle, plus starting/stopping controllers (when there is a request for it). If you check the Doxygen docs for the controller base classes, they tell you which methods need to be realtime-safe (in your case, at least finish in a bounded and reasonable amount of time).

Adolfo.

--
You received this message because you are subscribed to the Google Groups "ROS/Orocos Robot Control Special Interest Group" group.
To unsubscribe from this group and stop receiving emails from it, send an email to ros-sig-robot-co...@googlegroups.com.
For more options, visit https://groups.google.com/d/optout.
Reply all
Reply to author
Forward
0 new messages