A header-only C++20 coroutine library that brings async/await to ROS 2, inspired by icey.
Write asynchronous ROS 2 code that reads like sequential code -- no callback nesting, no deadlocks, no std::mutex, no state machines -- all on a single-threaded executor.
// Send two service requests in parallel with a 5s timeout
auto result = co_await ctx.wait_for(
when_all(
ctx.send_request<Srv1>(client1, req1),
ctx.send_request<Srv2>(client2, req2)),
5s);
// Both completed within 5s -- get the responses
if (result.ok()) {
auto [resp1, resp2] = *result.value;
}- ROS 2 Jazzy (or later)
- GCC 13+ with C++20 support
rclcpp,rclcpp_action,tf2_ros
Clone into your workspace and build:
cd ~/ros2_ws/src
git clone <repo-url> rclcpp_async
cd ~/ros2_ws
source /opt/ros/jazzy/setup.bash
colcon build --packages-select rclcpp_async#include <rclcpp/rclcpp.hpp>
#include "rclcpp_async/rclcpp_async.hpp"
rclcpp_async::Task<void> run(rclcpp_async::CoContext & ctx)
{
co_await ctx.sleep(std::chrono::seconds(1));
RCLCPP_INFO(ctx.node().get_logger(), "Hello from coroutine!");
}
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
auto node = std::make_shared<rclcpp::Node>("hello");
rclcpp_async::CoContext ctx(*node);
auto task = ctx.create_task(run(ctx));
rclcpp::spin(node);
rclcpp::shutdown();
}Every coroutine returns Task<T> and is launched with ctx.create_task(...). The standard rclcpp::spin() drives execution -- no special executor needed.
- Getting Started -- prerequisites, installation, walkthrough
- Guide -- topics, services, actions, concurrency, cancellation, TF
- API Reference -- full list of public types and methods
See rclcpp_async/test/benchmark/README.md for benchmark results comparing coroutine vs callback performance.
Apache-2.0