@@ -51,14 +51,14 @@ colcon build --packages-select rclcpp_async
5151rclcpp_async::Task<void > run (rclcpp_async::CoContext & ctx)
5252{
5353 co_await ctx.sleep(std::chrono::seconds(1));
54- RCLCPP_INFO(ctx.node()-> get_logger(), "Hello from coroutine!");
54+ RCLCPP_INFO(ctx.node(). get_logger(), "Hello from coroutine!");
5555}
5656
5757int main(int argc, char * argv[ ] )
5858{
5959 rclcpp::init(argc, argv);
6060 auto node = std::make_shared< rclcpp::Node > ("hello");
61- rclcpp_async::CoContext ctx(node);
61+ rclcpp_async::CoContext ctx(* node);
6262
6363 auto task = ctx.create_task(run(ctx));
6464
@@ -110,7 +110,7 @@ Task<void> listen(CoContext & ctx, std::string topic)
110110 if (!msg.has_value()) {
111111 break;
112112 }
113- RCLCPP_INFO(ctx.node()-> get_logger(), "Heard: %s", (* msg)->data.c_str());
113+ RCLCPP_INFO(ctx.node(). get_logger(), "Heard: %s", (* msg)->data.c_str());
114114 }
115115}
116116```
@@ -133,12 +133,12 @@ using SetBool = std_srvs::srv::SetBool;
133133
134134Task<void > call_service (CoContext & ctx)
135135{
136- auto client = ctx.node()-> create_client<SetBool >("set_bool");
136+ auto client = ctx.node(). create_client<SetBool >("set_bool");
137137
138138 // Wait for the service to become available
139139 auto wait_result = co_await ctx.wait_for_service(client, std::chrono::seconds(10));
140140 if (!wait_result.ok()) {
141- RCLCPP_ERROR(ctx.node()-> get_logger(), "Service not available");
141+ RCLCPP_ERROR(ctx.node(). get_logger(), "Service not available");
142142 co_return;
143143 }
144144
@@ -147,7 +147,7 @@ Task<void> call_service(CoContext & ctx)
147147 req->data = true;
148148
149149 auto resp = co_await ctx.send_request<SetBool >(client, req);
150- RCLCPP_INFO(ctx.node()-> get_logger(), "Response: %s", resp->message.c_str());
150+ RCLCPP_INFO(ctx.node(). get_logger(), "Response: %s", resp->message.c_str());
151151}
152152```
153153
@@ -163,7 +163,7 @@ Task<void> tick(CoContext & ctx)
163163
164164 while (true) {
165165 co_await timer->next();
166- RCLCPP_INFO(ctx.node()-> get_logger(), "Tick %d", count++);
166+ RCLCPP_INFO(ctx.node(). get_logger(), "Tick %d", count++);
167167 }
168168}
169169```
@@ -273,7 +273,7 @@ Send a goal and iterate over feedback with `GoalStream`:
273273``` cpp
274274Task<void > send_action (CoContext & ctx)
275275{
276- auto client = rclcpp_action::create_client<Fibonacci >(ctx.node(), "fibonacci");
276+ auto client = rclcpp_action::create_client<Fibonacci >(& ctx.node(), "fibonacci");
277277
278278 auto wait_result = co_await ctx.wait_for_action(client, std::chrono::seconds(10));
279279 if (!wait_result.ok()) { co_return; }
@@ -293,13 +293,13 @@ Task<void> send_action(CoContext & ctx)
293293 break;
294294 }
295295 auto & seq = (* feedback)->sequence;
296- RCLCPP_INFO(ctx.node()-> get_logger(), "Feedback: last=%d", seq.back());
296+ RCLCPP_INFO(ctx.node(). get_logger(), "Feedback: last=%d", seq.back());
297297 }
298298
299299 // Get final result
300300 auto result = stream->result();
301301 auto & seq = result.result->sequence;
302- RCLCPP_INFO(ctx.node()-> get_logger(), "Result: last=%d", seq.back());
302+ RCLCPP_INFO(ctx.node(). get_logger(), "Result: last=%d", seq.back());
303303}
304304```
305305
@@ -313,7 +313,7 @@ rclcpp_async::Event event(ctx);
313313// Task 1: wait for the event
314314auto waiter = ctx.create_task([&]() -> Task<void> {
315315 co_await event.wait();
316- RCLCPP_INFO(ctx.node()-> get_logger(), "Event received!");
316+ RCLCPP_INFO(ctx.node(). get_logger(), "Event received!");
317317});
318318
319319// Task 2: signal the event
@@ -340,7 +340,7 @@ rclcpp_async::Mutex mutex(ctx);
340340Task<void > critical_section(CoContext & ctx, Mutex & mutex, const std::string & name)
341341{
342342 co_await mutex.lock();
343- RCLCPP_INFO(ctx.node()-> get_logger(), "%s: acquired lock", name.c_str());
343+ RCLCPP_INFO(ctx.node(). get_logger(), "%s: acquired lock", name.c_str());
344344 co_await ctx.sleep(std::chrono::seconds(1));
345345 mutex.unlock();
346346}
@@ -364,7 +364,7 @@ Task<void> run(CoContext & ctx)
364364 // Sync lookup (latest) -- returns nullopt if not yet available
365365 auto opt = tf.lookup_transform("map", "base_link");
366366 if (opt) {
367- RCLCPP_INFO(ctx.node()-> get_logger(), "x=%.2f", opt->transform.translation.x);
367+ RCLCPP_INFO(ctx.node(). get_logger(), "x=%.2f", opt->transform.translation.x);
368368 }
369369
370370 // Async lookup -- suspends until the transform becomes available
@@ -403,7 +403,7 @@ auto task = ctx.create_task([&]() -> Task<void> {
403403 if (!val.has_value()) {
404404 break; // Channel closed
405405 }
406- RCLCPP_INFO(ctx.node()-> get_logger(), "Received: %d", * val);
406+ RCLCPP_INFO(ctx.node(). get_logger(), "Received: %d", * val);
407407 }
408408});
409409```
@@ -483,14 +483,14 @@ Task<void> run(CoContext & ctx)
483483```cpp
484484Task<void> run(CoContext & ctx)
485485{
486- auto client = ctx.node()-> create_client<SetBool>("set_bool");
486+ auto client = ctx.node(). create_client<SetBool>("set_bool");
487487
488488 // Race an awaitable against a timeout
489489 auto req = std::make_shared<SetBool::Request>();
490490 req->data = true;
491491 auto resp = co_await ctx.wait_for(ctx.send_request<SetBool>(client, req), 5s);
492492 if (resp.ok()) {
493- RCLCPP_INFO(ctx.node()-> get_logger(), "Response: %s", resp.value->message.c_str());
493+ RCLCPP_INFO(ctx.node(). get_logger(), "Response: %s", resp.value->message.c_str());
494494 }
495495}
496496```
@@ -546,7 +546,7 @@ Task<void> run(CoContext & ctx)
546546 try {
547547 co_await ctx.sleep(std::chrono::seconds(10));
548548 } catch (const CancelledException &) {
549- RCLCPP_INFO(ctx.node()-> get_logger(), "Cancelled!");
549+ RCLCPP_INFO(ctx.node(). get_logger(), "Cancelled!");
550550 }
551551}
552552```
@@ -579,7 +579,7 @@ See [`nested_demo.cpp`](rclcpp_async_example/src/nested_demo.cpp) for a full dem
579579| `when_all(awaitables...)` | *awaitable* `tuple<Ts...>` | Await all tasks/awaitables concurrently |
580580| `when_any(awaitables...)` | *awaitable* `variant<Ts...>` | Race tasks/awaitables, return first result |
581581| `post(fn)` | `void` | Post a callback to the executor thread (thread-safe) |
582- | `node()` | `Node::SharedPtr ` | Access the underlying node |
582+ | `node()` | `Node& ` | Access the underlying node |
583583
584584### TfBuffer
585585
0 commit comments