Skip to content

Commit 2642898

Browse files
refactor: reorganize RepublisherNode in lib.rs implementation and update example references for clarity
1 parent bfc5680 commit 2642898

File tree

6 files changed

+91
-65
lines changed

6 files changed

+91
-65
lines changed

docs/writing-your-first-rclrs-node.md

Lines changed: 6 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -138,7 +138,8 @@ impl RepublisherNode {
138138
_data,
139139
})
140140
}
141-
}```
141+
}
142+
```
142143

143144
If that seems needlessly complicated – maybe it is, in the sense that `rclrs` could potentially introduce new abstractions to improve the ergonomics of this use case. This is to be discussed.
144145

@@ -149,22 +150,22 @@ If you couldn't follow the explanation involving borrowing, closures etc. above,
149150
The node still doesn't republish the received messages. First, let's add a publisher to the node:
150151

151152
```
152-
<!-- MARKDOWN-AUTO-DOCS:START (CODE:src=../examples/minimal_pub_sub/src/first_rclrs_node.rs&lines=5-10) -->
153+
<!-- MARKDOWN-AUTO-DOCS:START (CODE:src=../rclrs/src/lib.rs&lines=78-83) -->
153154
<!-- MARKDOWN-AUTO-DOCS:END -->
154155
```
155156

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

158159
```
159-
<!-- MARKDOWN-AUTO-DOCS:START (CODE:src=../examples/minimal_pub_sub/src/first_rclrs_node.rs&lines=23-29) -->
160+
<!-- MARKDOWN-AUTO-DOCS:START (CODE:src=../rclrs/src/lib.rs&lines=96-102) -->
160161
<!-- MARKDOWN-AUTO-DOCS:END -->
161162
```
162163

163164

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

166167
```
167-
<!-- MARKDOWN-AUTO-DOCS:START (CODE:src=../examples/minimal_pub_sub/src/first_rclrs_node.rs&lines=32-37) -->
168+
<!-- MARKDOWN-AUTO-DOCS:START (CODE:src=../rclrs/src/lib.rs&lines=105-110) -->
168169
<!-- MARKDOWN-AUTO-DOCS:END -->
169170
```
170171

@@ -197,7 +198,7 @@ But wait, this doesn't work – there is an error about the thread closure needi
197198
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:
198199

199200
```
200-
<!-- MARKDOWN-AUTO-DOCS:START (CODE:src=../examples/minimal_pub_sub/src/first_rclrs_node.rs&lines=40-55) -->
201+
<!-- MARKDOWN-AUTO-DOCS:START (CODE:src=../rclrs/src/lib.rs&lines=113-128) -->
201202
<!-- MARKDOWN-AUTO-DOCS:END -->
202203
```
203204

examples/minimal_pub_sub/Cargo.toml

Lines changed: 0 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -25,11 +25,6 @@ path = "src/zero_copy_subscriber.rs"
2525
name = "zero_copy_publisher"
2626
path = "src/zero_copy_publisher.rs"
2727

28-
[[bin]]
29-
name = "first_rclrs_node"
30-
path = "src/first_rclrs_node.rs"
31-
32-
3328
[dependencies]
3429
anyhow = {version = "1", features = ["backtrace"]}
3530

examples/minimal_pub_sub/src/first_rclrs_node.rs

Lines changed: 0 additions & 55 deletions
This file was deleted.

rclrs/Cargo.toml

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,11 @@ rosidl_runtime_rs = "0.4"
3333
serde = { version = "1", optional = true, features = ["derive"] }
3434
serde-big-array = { version = "0.5.1", optional = true }
3535

36+
# Needed for the examples in lib.rs
37+
[dependencies.std_msgs]
38+
version = "*"
39+
40+
3641
[dev-dependencies]
3742
# Needed for e.g. writing yaml files in tests
3843
tempfile = "3.3.0"

rclrs/package.xml

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,8 @@
2020
<depend>rcl_interfaces</depend>
2121
<depend>rosgraph_msgs</depend>
2222

23+
<build_depend>std_msgs</build_depend>
24+
2325
<test_depend>test_msgs</test_depend>
2426

2527
<export>

rclrs/src/lib.rs

Lines changed: 78 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -48,3 +48,81 @@ pub use subscription::*;
4848
pub use time::*;
4949
use time_source::*;
5050
pub use wait::*;
51+
52+
53+
/// # rclrs - ROS 2 Client Library for Rust
54+
///
55+
/// `rclrs` provides Rust bindings and idiomatic wrappers for ROS 2 (Robot Operating System).
56+
/// It enables writing ROS 2 nodes, publishers, subscribers, services and clients in Rust.
57+
///
58+
/// ## Features
59+
///
60+
/// - Native Rust implementation of core ROS 2 concepts
61+
/// - Safe wrappers around rcl C API
62+
/// - Support for publishers, subscribers, services, clients
63+
/// - Async/await support for services and clients
64+
/// - Quality of Service (QoS) configuration
65+
/// - Parameter services
66+
/// - Logging integration
67+
///
68+
/// ## Example
69+
/// Here's a simple publisher-subscriber node:
70+
71+
use std::sync::{Arc, Mutex};
72+
use std_msgs::msg::String as StringMsg;
73+
74+
/// ## Write the basic node structure
75+
/// Since Rust doesn't have inheritance, it's not possible to inherit from `Node` as is common practice in `rclcpp` or `rclpy`.
76+
///
77+
/// 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`:
78+
pub struct RepublisherNode {
79+
_node: Arc<Node>,
80+
_subscription: Arc<Subscription<StringMsg>>,
81+
_publisher: Arc<Publisher<StringMsg>>,
82+
_data: Arc<Mutex<Option<StringMsg>>>,
83+
}
84+
85+
impl RepublisherNode {
86+
fn _new(executor: &Executor) -> Result<Self, RclrsError> {
87+
let _node = executor.create_node("republisher")?;
88+
let _data = Arc::new(Mutex::new(None));
89+
let data_cb = Arc::clone(&_data);
90+
let _subscription = _node.create_subscription(
91+
"in_topic".keep_last(10).transient_local(),
92+
move |msg: StringMsg| {
93+
*data_cb.lock().unwrap() = Some(msg);
94+
},
95+
)?;
96+
let _publisher = _node.create_publisher::<std_msgs::msg::String>("out_topic")?;
97+
Ok(Self {
98+
_node,
99+
_subscription,
100+
_publisher,
101+
_data,
102+
})
103+
}
104+
105+
fn _republish(&self) -> Result<(), RclrsError> {
106+
if let Some(s) = &*self._data.lock().unwrap() {
107+
self._publisher.publish(s)?;
108+
}
109+
Ok(())
110+
}
111+
}
112+
113+
fn _main() -> Result<(), RclrsError> {
114+
let context = Context::default_from_env()?;
115+
let mut executor = context.create_basic_executor();
116+
let republisher = RepublisherNode::_new(&executor)?;
117+
std::thread::spawn(move || -> Result<(), RclrsError> {
118+
loop {
119+
use std::time::Duration;
120+
std::thread::sleep(Duration::from_millis(1000));
121+
republisher._republish()?;
122+
}
123+
});
124+
executor
125+
.spin(SpinOptions::default())
126+
.first_error()
127+
.map_err(|err| err.into())
128+
}

0 commit comments

Comments
 (0)