Skip to content

Commit 6af4824

Browse files
Update first_rclrs_node example for improved clarity and functionality
1 parent 942e310 commit 6af4824

File tree

1 file changed

+14
-7
lines changed

1 file changed

+14
-7
lines changed

examples/minimal_pub_sub/src/first_rclrs_node.rs

Lines changed: 14 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -61,7 +61,8 @@
6161
//! _data,
6262
//! })
6363
//! }
64-
//!}```
64+
//!}
65+
//! ```
6566
//! Next, add a main function to launch it:
6667
6768
//! ```rust
@@ -73,7 +74,8 @@
7374
//! .spin(SpinOptions::default())
7475
//! .first_error()
7576
//! .map_err(|err| err.into())
76-
//! }```
77+
//! }
78+
//! ```
7779
7880
//! ## Run the node
7981
//! You should now be able to run this node with `cargo build` and then `cargo run`. However, the subscription callback still has a `todo!` in it, so it will exit with an error when it receives a message.
@@ -105,9 +107,9 @@
105107
//! 4. Make the closure `move`, and inside it, lock the `Mutex` and store the message
106108
107109
//! ```rust
110+
//! use rclrs::*;
108111
//! use std::sync::{Arc, Mutex}; // (1)
109112
//! use std_msgs::msg::String as StringMsg;
110-
//! use rclrs::*;
111113
112114
//! struct RepublisherNode {
113115
//! _node: Arc<rclrs::Node>,
@@ -175,7 +177,7 @@
175177
//! let context = Context::default_from_env()?;
176178
//! let mut executor = context.create_basic_executor();
177179
//! let _republisher = RepublisherNode::new(&executor)?;
178-
//! std::thread::spawn(move || -> Result<(), rclrs::RclrsError> {
180+
//! std::thread::spawn(|| -> Result<(), rclrs::RclrsError> {
179181
//! loop {
180182
//! use std::time::Duration;
181183
//! std::thread::sleep(Duration::from_millis(1000));
@@ -194,7 +196,7 @@
194196
//! because the function that the variable is coming from might return before the thread that borrows the variable ends.
195197
//! > 💡 Of course, you could argue that this cannot really happen here, because returning from `main()` will also terminate the other threads, but Rust isn't that smart.
196198
//!
197-
//! The solution is also the same as above: Shared ownership with `Arc`. Only this time, `Mutex` isn't needed since both the `rclcpp::spin()`
199+
//! The solution is also the same as above: Shared ownership with `Arc`. Only this time, `Mutex` isn't needed since both the `executor::spin()`
198200
//! and the `republish()` function only require a shared reference:
199201
//! ```rust
200202
//! fn main() -> Result<(), rclrs::RclrsError> {
@@ -216,8 +218,13 @@
216218
//!```
217219
218220
//! ## Try it out
219-
//! In separate terminals, run `cargo run --bin first_rclrs_node` if running the current node or `cargo run` otherwise and `ros2 topic echo /out_topic`. Nothing will be shown yet, since our node hasn't received any data yet.
220-
//!
221+
//! ### Terminal 1:
222+
//! In a first terminal, in the workspace root, run:
223+
//! 1. `colcon build --packages-select examples_rclrs_minimal_pub_sub` to build the node.
224+
//! 2. `ros2 run examples_rclrs_minimal_pub_sub first_rclrs_node` to run the node.
225+
//! ### Terminal 2:
226+
//! In another terminal, run `ros2 topic echo /out_topic`. Nothing will be shown yet, since our node hasn't received any data yet.
227+
//! ### Terminal 3:
221228
//! In another terminal, publish a single message with `ros2 topic pub /in_topic std_msgs/msg/String '{data: "Bonjour"}' -1`.
222229
//! The terminal with `ros2 topic echo` should now receive a new `Bonjour` message every second.
223230
//!

0 commit comments

Comments
 (0)