Skip to content

Add first_rclrs_node example and update documentation links #467

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Open
wants to merge 23 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
23 commits
Select commit Hold shift + click to select a range
92edc21
Add first_rclrs_node example and update documentation links
roboticswithjulia Mar 25, 2025
942e310
Refactor first_rclrs_node example for improved clarity and structure
roboticswithjulia Mar 26, 2025
6af4824
Update first_rclrs_node example for improved clarity and functionality
roboticswithjulia Mar 26, 2025
4569882
build: use tokusumi/markdown-embed-code@main action to synchronize Ma…
esteve Apr 2, 2025
913fbe3
build: reference example in tutorial
esteve Apr 2, 2025
30418ff
build: use fork for the sync action, upstream has not been updated in…
esteve Apr 2, 2025
e7514df
fix
esteve Apr 2, 2025
90a34a9
test
esteve Apr 2, 2025
aa261b8
test
esteve Apr 2, 2025
1b065a3
build: update checkout action configuration for better token handling…
roboticswithjulia Apr 2, 2025
231cab0
build: update ref handling in workflow files for improved compatibility
roboticswithjulia Apr 2, 2025
6f56274
build: remove ref handling from workflow files for improved compatibi…
roboticswithjulia Apr 2, 2025
52b326c
build: add ref handling in workflow files for improved pull request s…
roboticswithjulia Apr 2, 2025
18b25ef
build: update ref handling in workflow files for improved pull reques…
roboticswithjulia Apr 2, 2025
6d62e9f
build: update ref handling in workflow files for improved clarity and…
roboticswithjulia Apr 2, 2025
b5da0d5
build: downgrade actions/checkout version for improved compatibility
roboticswithjulia Apr 2, 2025
11392bc
build: update workflows to use markdown-autodocs for improved documen…
roboticswithjulia Apr 3, 2025
324cdff
build: update markdown-autodocs usage in workflow files for consistency
roboticswithjulia Apr 3, 2025
ed8f33b
build: add branch reference to action-ros-ci in workflow files for im…
roboticswithjulia Apr 3, 2025
df637e0
build: update branch reference in markdown-autodocs usage for consist…
roboticswithjulia Apr 3, 2025
bfc5680
build: update actions/checkout version to v4 in workflow files for im…
roboticswithjulia Apr 3, 2025
2642898
refactor: reorganize RepublisherNode in lib.rs implementation and upd…
roboticswithjulia Apr 3, 2025
f672bbb
docs: improve documentation formatting and remove unnecessary whitesp…
roboticswithjulia Apr 3, 2025
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 8 additions & 0 deletions .github/workflows/rust-minimal.yml
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,14 @@ jobs:
image: ${{ matrix.docker_image }}
steps:
- uses: actions/checkout@v4

- name: Markdown autodocs
uses: dineshsonachalam/[email protected]
with:
commit_message: Synchronizing Markdown files
branch: ${{ github.base_ref }}
output_file_paths: '[./docs/writing-your-first-rclrs-node.md]'
categories: '[code-block]'

- name: Search packages in this repository
id: list_packages
Expand Down
8 changes: 8 additions & 0 deletions .github/workflows/rust-stable.yml
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,14 @@ jobs:
image: ${{ matrix.docker_image }}
steps:
- uses: actions/checkout@v4

- name: Markdown autodocs
uses: dineshsonachalam/[email protected]
with:
commit_message: Synchronizing Markdown files
branch: ${{ github.base_ref }}
output_file_paths: '[./docs/writing-your-first-rclrs-node.md]'
categories: '[code-block]'

- name: Search packages in this repository
id: list_packages
Expand Down
120 changes: 53 additions & 67 deletions docs/writing-your-first-rclrs-node.md
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,6 @@ impl RepublisherNode {
let data = None;
let _subscription = node.create_subscription(
"in_topic",
rclrs::QOS_PROFILE_DEFAULT,
|msg: StringMsg| { todo!("Assign msg to self.data") },
)?;
Ok(Self {
Expand All @@ -74,9 +73,13 @@ Next, add a main function to launch it:

```rust
fn main() -> Result<(), rclrs::RclrsError> {
let context = rclrs::Context::new(std::env::args())?;
let republisher = RepublisherNode::new(&context)?;
rclrs::spin(republisher.node)
let context = Context::default_from_env()?;
let mut executor = context.create_basic_executor();
let _republisher = RepublisherNode::new(&executor)?;
executor
.spin(SpinOptions::default())
.first_error()
.map_err(|err| err.into())
}
```

Expand Down Expand Up @@ -110,37 +113,31 @@ So, to store the received data in the struct, the following things have to chang
4. Make the closure `move`, and inside it, lock the `Mutex` and store the message

```rust
use rclrs::*;
use std::sync::{Arc, Mutex}; // (1)
use std_msgs::msg::String as StringMsg;

struct RepublisherNode {
node: Arc<rclrs::Node>,
_subscription: Arc<rclrs::Subscription<StringMsg>>,
data: Arc<Mutex<Option<StringMsg>>>, // (2)
_node: Arc<rclrs::Node>,
_subscription: Arc<rclrs::Subscription<StringMsg>>,
_data: Arc<Mutex<Option<StringMsg>>>, // (2)
}

impl RepublisherNode {
fn new(context: &rclrs::Context) -> Result<Self, rclrs::RclrsError> {
let node = rclrs::Node::new(context, "republisher")?;
let data = Arc::new(Mutex::new(None)); // (3)
let data_cb = Arc::clone(&data);
let _subscription = {
// Create a new shared pointer instance that will be owned by the closure
node.create_subscription(
"in_topic",
rclrs::QOS_PROFILE_DEFAULT,
move |msg: StringMsg| {
// This subscription now owns the data_cb variable
*data_cb.lock().unwrap() = Some(msg); // (4)
},
)?
};
Ok(Self {
node,
_subscription,
data,
})
}
fn new(executor: &rclrs::Executor) -> Result<Self, rclrs::RclrsError> {
let _node = executor.create_node("republisher")?;
let _data = Arc::new(Mutex::new(None)); // (3)
let data_cb = Arc::clone(&_data);
let _subscription = _node.create_subscription(
"in_topic".keep_last(10).transient_local(), // (4)
move |msg: StringMsg| {
*data_cb.lock().unwrap() = Some(msg);
},
)?;
Ok(Self {
_node,
_subscription,
_data,
})
}
}
```

Expand All @@ -152,45 +149,45 @@ If you couldn't follow the explanation involving borrowing, closures etc. above,

The node still doesn't republish the received messages. First, let's add a publisher to the node:

```rust
// Add this new field to the RepublisherNode struct, after the subscription:
publisher: Arc<rclrs::Publisher<StringMsg>>,

// Change the end of RepublisherNode::new() to this:
let publisher = node.create_publisher("out_topic", rclrs::QOS_PROFILE_DEFAULT)?;
Ok(Self {
node,
_subscription,
publisher,
data,
})
```
<!-- MARKDOWN-AUTO-DOCS:START (CODE:src=../rclrs/src/lib.rs&lines=78-83) -->
<!-- MARKDOWN-AUTO-DOCS:END -->
```

Create a publisher and add it to the newly instantiated `RepublisherNode`:

```
<!-- MARKDOWN-AUTO-DOCS:START (CODE:src=../rclrs/src/lib.rs&lines=96-102) -->
<!-- MARKDOWN-AUTO-DOCS:END -->
```


Then, let's add a `republish()` function to the `RepublisherNode` that publishes the latest message received, or does nothing if none was received:

```rust
fn republish(&self) -> Result<(), rclrs::RclrsError> {
if let Some(s) = &*self.data.lock().unwrap() {
self.publisher.publish(s)?;
}
Ok(())
}
```
<!-- MARKDOWN-AUTO-DOCS:START (CODE:src=../rclrs/src/lib.rs&lines=105-110) -->
<!-- MARKDOWN-AUTO-DOCS:END -->
```


What's left to do is to call this function every second. `rclrs` doesn't yet have ROS timers, which run a function at a fixed interval, but it's easy enough to achieve with a thread, a loop, and the sleep function. Change your main function to spawn a separate thread:

```rust
fn main() -> Result<(), rclrs::RclrsError> {
let context = rclrs::Context::new(std::env::args())?;
let republisher = RepublisherNode::new(&context)?;
let context = Context::default_from_env()?;
let mut executor = context.create_basic_executor();
let _republisher = RepublisherNode::new(&executor)?;
std::thread::spawn(|| -> Result<(), rclrs::RclrsError> {
loop {
use std::time::Duration;
std::thread::sleep(Duration::from_millis(1000));
republisher.republish()?;
_republisher.republish()?;
}
});
rclrs::spin(republisher.node)
executor
.spin(SpinOptions::default())
.first_error()
.map_err(|err| err.into())
}
```

Expand All @@ -200,20 +197,9 @@ But wait, this doesn't work – there is an error about the thread closure needi

The solution is also the same as above: Shared ownership with `Arc`. Only this time, `Mutex` isn't needed since both the `rclcpp::spin()` and the `republish()` function only require a shared reference:

```rust
fn main() -> Result<(), rclrs::RclrsError> {
let context = rclrs::Context::new(std::env::args())?;
let republisher = Arc::new(RepublisherNode::new(&context)?);
let republisher_other_thread = Arc::clone(&republisher);
std::thread::spawn(move || -> Result<(), rclrs::RclrsError> {
loop {
use std::time::Duration;
std::thread::sleep(Duration::from_millis(1000));
republisher_other_thread.republish()?;
}
});
rclrs::spin(Arc::clone(&republisher.node))
}
```
<!-- MARKDOWN-AUTO-DOCS:START (CODE:src=../rclrs/src/lib.rs&lines=113-128) -->
<!-- MARKDOWN-AUTO-DOCS:END -->
```


Expand Down
5 changes: 5 additions & 0 deletions rclrs/Cargo.toml
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,11 @@ rosidl_runtime_rs = "0.4"
serde = { version = "1", optional = true, features = ["derive"] }
serde-big-array = { version = "0.5.1", optional = true }

# Needed for the examples in lib.rs
[dependencies.std_msgs]
version = "*"


[dev-dependencies]
# Needed for e.g. writing yaml files in tests
tempfile = "3.3.0"
Expand Down
2 changes: 2 additions & 0 deletions rclrs/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,8 @@
<depend>rcl_interfaces</depend>
<depend>rosgraph_msgs</depend>

<build_depend>std_msgs</build_depend>

<test_depend>test_msgs</test_depend>

<export>
Expand Down
76 changes: 76 additions & 0 deletions rclrs/src/lib.rs
Original file line number Diff line number Diff line change
Expand Up @@ -48,3 +48,79 @@ pub use subscription::*;
pub use time::*;
use time_source::*;
pub use wait::*;

/// # rclrs - ROS 2 Client Library for Rust
///
/// `rclrs` provides Rust bindings and idiomatic wrappers for ROS 2 (Robot Operating System).
/// It enables writing ROS 2 nodes, publishers, subscribers, services and clients in Rust.
///
/// ## Features
///
/// - Native Rust implementation of core ROS 2 concepts
/// - Safe wrappers around rcl C API
/// - Support for publishers, subscribers, services, clients
/// - Async/await support for services and clients
/// - Quality of Service (QoS) configuration
/// - Parameter services
/// - Logging integration
///
/// ## Example
/// Here's a simple publisher-subscriber node:
use std::sync::{Arc, Mutex};
use std_msgs::msg::String as StringMsg;

/// ## Write the basic node structure
/// Since Rust doesn't have inheritance, it's not possible to inherit from `Node` as is common practice in `rclcpp` or `rclpy`.
///
/// Instead, you can store the node as a regular member. Let's use a struct that contains the node, a subscription, and a field for the last message that was received to `main.rs`:
pub struct RepublisherNode {
_node: Arc<Node>,
_subscription: Arc<Subscription<StringMsg>>,
_publisher: Arc<Publisher<StringMsg>>,
_data: Arc<Mutex<Option<StringMsg>>>,
}

impl RepublisherNode {
fn _new(executor: &Executor) -> Result<Self, RclrsError> {
let _node = executor.create_node("republisher")?;
let _data = Arc::new(Mutex::new(None));
let data_cb = Arc::clone(&_data);
let _subscription = _node.create_subscription(
"in_topic".keep_last(10).transient_local(),
move |msg: StringMsg| {
*data_cb.lock().unwrap() = Some(msg);
},
)?;
let _publisher = _node.create_publisher::<std_msgs::msg::String>("out_topic")?;
Ok(Self {
_node,
_subscription,
_publisher,
_data,
})
}

fn _republish(&self) -> Result<(), RclrsError> {
if let Some(s) = &*self._data.lock().unwrap() {
self._publisher.publish(s)?;
}
Ok(())
}
}

fn _main() -> Result<(), RclrsError> {
let context = Context::default_from_env()?;
let mut executor = context.create_basic_executor();
let republisher = RepublisherNode::_new(&executor)?;
std::thread::spawn(move || -> Result<(), RclrsError> {
loop {
use std::time::Duration;
std::thread::sleep(Duration::from_millis(1000));
republisher._republish()?;
}
});
executor
.spin(SpinOptions::default())
.first_error()
.map_err(|err| err.into())
}