| Requirements | Compatibility | Tests |
|---|---|---|
The Asyncio For Robotics (afor) library makes asyncio usable with ROS 2, Zenoh and more, letting you write linear, testable, and non-blocking Python code.
- Better syntax.
- Only native python: Better docs and support.
- Simplifies testing.
Will this make my code slower? No.
Will this make my code faster? No. However asyncio will help YOU write
better, faster code.
Does it replace ROS 2? Is this a wrapper? No. It is a tool adding async capabilities. It gives you more choices, not less.
Compatible with ROS 2 (jazzy,humble and newer) out of the box. This library is pure python (>=3.10), so it installs easily.
pip install asyncio_for_roboticspip install asyncio_for_robotics[zenoh]- Detailed ROS 2 tutorial
- Detailed examples
- Usage for software testing
- Implement your own protocol
- Cross-Platform deployment even with ROS
Syntax is identical between ROS 2 and Zenoh.
Application:
- Get the latest sensor data
- Get clock value
- Wait for trigger
- Wait for system to be operational
sub = afor.Sub(...)
# get the latest message
latest = await sub.wait_for_value()
# get a new message
new = await sub.wait_for_new()
# get the next message received
next = await sub.wait_for_next()Application:
- Process a whole data stream
- React to changes in sensor data
# Continuously process the latest messages
async for msg in sub.listen():
status = foo(msg)
if status == DONE:
break
# Continuously process all incoming messages
async for msg in sub.listen_reliable():
status = foo(msg)
if status == DONE:
breakApplication:
- Periodic updates and actions
# Rate is simply a subscriber triggering on every tick
rate = afor.Rate(frequency=0.01, time_source=time.time_ns)
# Wait for the next tick
await rate.wait_for_new()
# Executes after a tick
async for _ in rate.listen():
foo(...)
# Reliably executes for every tick
async for _ in sub.listen_reliable():
foo(...)Services are needlessly convoluted in ROS 2 and intrinsically not async
(because the server callback function MUST return a response). afor overrides
the ROS behavior, allowing for the response to be sent later. Implementing
similar systems for other transport protocol should be very easy: The server is just a
asyncio_for_robotics.core.BaseSub generating responder objects.
Application:
- Client request reply from a server.
- Servers can delay their response without blocking (not possible in ROS 2)
# Server is once again a afor subscriber, but generating responder objects
server = afor.Server(...)
# processes all requests.
# listen_reliable method is recommanded as it cannot skip requests
async for responder in server.listen_reliable():
if responder.request == "PING!":
reponder.response = "PONG!"
await asyncio.sleep(...) # reply can be differed
reponder.send()
else:
... # reply is not necessary# the client implements a async call method
client = afor.Client(...)
response = await client.call("PING!")Application:
- Test if the system is responding as expected
- Run small tasks with small and local code
# Listen with a timeout
data = await afor.soft_wait_for(sub.wait_for_new(), timeout=1)
if isinstance(data, TimeoutError):
pytest.fail(f"Failed to get new data in under 1 second")
# Process a codeblock with a timeout
async with afor.soft_timeout(1):
sum = 0
total = 0
async for msg in sub.listen_reliable():
number = process(msg)
sum += number
total += 1
last_second_average = sum/total
assert last_second_average == pytest.approx(expected_average)The inevitable question: “But isn’t this slower than the ROS 2 executor? ROS 2 is the best!”
In short: rclpy's executor is the bottleneck.
- Comparing to the best ROS 2 Jazzy can do (
SingleThreadedExecutor),aforincreases latency from 110us to 150us. - Comparing to other execution methods,
aforis equivalent if not faster. - If you find it slow, you should use C++ or Zenoh (or contribute to this repo?).
Benchmark code is available in ./tests/bench/, it consists in two pairs of pub/sub infinitely echoing a message (using one single node). The messaging rate, thus measures the request to response latency.
With afor |
Transport | Executor | Frequency (kHz) | Latency (ms) | |
|---|---|---|---|---|---|
| ✔️ | Zenoh | None | 95 | 0.01 | |
| ✔️ | ROS 2 | Experimental Asyncio | 17 | 0.06 | |
| ❌ | ROS 2 | Experimental Asyncio | 13 | 0.08 | |
| ❌ | ROS 2 | SingleThreaded | 9 | 0.11 | |
| ✔️ | ROS 2 | SingleThreaded | 7 | 0.15 | |
| ✔️ | ROS 2 | MultiThreaded | 3 | 0.3 | |
| ❌ | ROS 2 | MultiThreaded | 3 | 0.3 | |
| ✔️ | ROS 2 | ros_loop Method |
3 | 0.3 |
Details:
uvloopwas used, replacing the asyncio executor (more or less doubles the performances for Zenoh)- RMW was set to
rmw_zenoh_cpp - ROS2 benchmarks uses
afor'sros2.ThreadedSession(the default inafor). - Only the Benchmark of the
ros_loopmethod usesafor's second type of session:ros2.SynchronousSession. - ROS 2 executors can easily be changed in
aforwhen creating a session. - The experimental
AsyncioExecutorPR on ros rolling by nadavelkabets is incredible ros2/rclpy#1399. Maybe I will add proper support for it (but only a few will want to use an unmerged experimental PR of ROS 2 rolling). - If there is interest in those benchmarks I will improve them, so others can run them all easily.
Analysis:
- Zenoh is extremely fast, proving that
aforis not the bottleneck. - This
AsyncioExecutorhaving better perf when usingaforis interesting, becauseafordoes not bypass code.- I think this is due to
AsyncioExecutorhaving some overhead that affects its own callback. - Without
aforthe ROS 2 callback executes some code and publishes. - With
aforthe ROS 2 callback returns immediately, and fully delegates execution toasyncio.
- I think this is due to
- The increase of latency on the
SingleThreadedexecutors proves that getting data in and out of therclpyexecutor and thread is the main bottleneck.AsyncioExecutordoes not have such thread, thus can directly communicate.- Zenoh has its own thread, however it is built exclusively for multi-thread operations, without any executor. Thus achieves far superior performances.
MultiThreadedExecutoris just famously slow.- Very surprisingly, the well known
ros_loopmethod detailed here https://github.com/m2-farzan/ros2-asyncio is slow.