ros_control
ros_control copied to clipboard
Examples of realtime hardware interfaces
Assuming I have already changed my Linux kernel with a real time patch like RT_PREEMPT
, does anyone have example hardware interfaces for ros_control that have working real time loops setup that I can use as an example? I'm fairly new to thinking about realtime constraints but have read this article on coding a realtime example.
On a related note, we should add more robots to the examples section of the ros_control wiki documentation.
Thanks!
The example from the article is doing the typical things for a rt task: Specify the scheduler policy and priority, pre-fault the stack and lock memory. I never do this explicitly, as I leverage Orocos RTT, which takes care of this. I don't have examples that I can share :(
On a related note, we should add more robots to the examples section of the ros_control wiki documentation.
Yes, we have two robots that should go there, and they are pretty complete examples: mobile base + humanoid torso, and a biped humanoid. It's in my TODO..., but the task hasn't been woken up by the scheduler yet ;-)
Also re-iterating here that (even a simple) ros_control example using Orocos RTT would be really useful.
Also re-iterating here that (even a simple) ros_control example using Orocos RTT would be really useful.
At it's most basic level, its nothing more than calling update on the controller manager from an RTT component's update method. ros_control's controller manager then takes care of the rest. Here is some stripped down code (removed error checking and some other custom stuff) from what we played around with. First you have to setup everything.. and RTT component's configure method is great for that. Here ControllerExec was our RTT component.
bool ControllerExec::configureHook()
{
// Instantiate hardware interface
robot.reset(new HwRobotInterface );
// Create the ros_control controller manager
controllerMgr.reset( new controller_manager::ControllerManager(robot.get(), node) );
return true;
}
Once ros_control is configured, its just the read/compute/write cycle...
void ControllerExec::updateHook()
{
ros::Time curUpdateTime = ros::Time::now();
ros::Duration duration = curUpdateTime - prevUpdateTime;
prevUpdateTime = curUpdateTime;
// The high-level read-compute-write cycle
robot->read();
controllerMgr->update(curUpdateTime, duration);
robot->write();
}
Of course, you could get a lot more fancy.
Also re-iterating here that (even a simple) ros_control example using Orocos RTT would be really useful.
@yamokosk's example shows how you can opaquely instantiate a ros_control controller manager inside an orocos component, and then use the Orocos scheduler for execution. This does satisfy @davetcoleman's question, but having to use RTT just to create a Xenomai-friendly loop seems like overkill.
@skohlbr, is this the sort of thing you're asking for?
Thanks @yamokosk for the example.
having to use RTT just to create a Xenomai-friendly loop seems like overkill.
Yeah, but it's convenient to get something running fast. We actually do talk to other Orocos components, so we do in fact need a lot of what RTT has to offer.
@jbohren This is the most basic variant of what I´ve been asking for. How some details/intricacies of hard real-time control are solved remains a bit unclear however. Some examples:
- How are ROS subscriber/service callbacks treated (required for ControllerManager services)? I can´t see ROS spinning in the posted example, so maybe a ASyncSpinner is missing?
- If the incoming callbacks are running in a separate ASyncSpinner (thread), is that running at the same priority/scheduler policy (SCHED_FIFO) as the TaskContext? How is it guaranteed that the TaskContext updateHook is fulfilling the desired hard real-time constraints even when ROS callbacks are called and potentially locking mutexes?
- We´re looking at a pretty complex application and would like to be able to change some settings of the HwRobotInterface during run-time. What´s the best way of doing this without breaking hard real-time behavior?
- How are ROS subscriber/service callbacks treated (required for ControllerManager services)? I can´t see ROS spinning in the posted example, so maybe a ASyncSpinner is missing?
I would recommend having a per-component CallbackQueue
, which you spin in a separate (non-realtime) thread. The NodeHandle
you pass to the ControllerManager
would be associated to this CallbackQueue
. You can do this setup in the configureHook()
.
By having separate spinners per component, you protect yourself from scenarios in which there are potentially many components, each of which has its own ROS API, which you don't care about. You'll only process events related to your component's ROS API.
If you use an AsyncSpinner
, beware of https://github.com/ros/ros_comm/issues/277.
- If the incoming callbacks are running in a separate ASyncSpinner (thread), is that running at the same priority/scheduler policy (SCHED_FIFO) as the TaskContext?
No. The ``configureHook()is meant for you to non-realtime setup of your component. The
AsyncSpinner` will create a non-reatime thread.
How is it guaranteed that the TaskContext updateHook is fulfilling the desired hard real-time constraints even when ROS callbacks are called and potentially locking mutexes?
It depends on how you handle concurrency between your (non-rt) callbacks and the (rt) control loop. ros_control has realtime_tools::RealtimeBuffer
for helping here, which should do the job for you. The lock-free alternatives from RTT are more fully-featured, but not available in ros_control (as it does not depend on RTT).
- We´re looking at a pretty complex application and would like to be able to change some settings of the HwRobotInterface during run-time. What´s the best way of doing this without breaking hard real-time behavior?
What kind of settings?.
Two important things to take into account are:
- Those setting changes must not trigger system calls in the realtime thread.
- Avoid the risk of a priority inversion. Non-realtime threads should not lock on a shared resource with the realtime thread.
I made a small (pretty minimal) example showing how RTT can be used with ros_control based on previous comments above: rtt_ros_control_example Everybody is invited to take a look at it and suggest improvements (for example regarding the implementation of the ROS callback queue and the threading approach used).
Few questions I have:
- What is a good, portable monotonic time source for computing the controller update period?
- How can I start things so the TaskContext/node behaves similar to a normal ROS node (e.g. not starting the deployer in the terminal)?
What is a good, portable monotonic time source for computing the controller update period?
Check out http://docs.ros.org/hydro/api/rtt_rosclock/html/rtt__rosclock_8h.html
- monotonic:
rtt_rosclock::rtt_now()
- NTP-adjusted:
rtt_rosclock::host_now()
How can I start things so the TaskContext/node behaves similar to a normal ROS node (e.g. not starting the deployer in the terminal)?
You can use rttscript
instead of deployer
to do this.
Thanks for the heads up. I added use of rtt_rosclock
. From the doc it wasn´t completely clear to me if that was indeed a monotonic source.
Is there some sort of documentation for rttscript
? I tried just substituting #!/usr/bin/env deployer-gnulinux
with #!/usr/bin/env rttscript-gnulinux
in my .ops
file, but that leads to the TaskContext immediately exiting (and also made me aware of it dying because of improper cleanup ;) ).
This discussion and the rtt_ros_control_example
were very helpful while developing hal_ros_control
, a real-time ros_control interface to Machinekit's HAL, built on top of @davetcoleman's boilerplate. HAL resembles RTT in that the package only needs to provide an update function, and the actual RT loop and its timing happen externally. Thanks!
Glad it could help!