Skip to content

Commit a75cd24

Browse files
committed
Introduce CreateBasicExecutor trait
Signed-off-by: Michael X. Grey <[email protected]>
1 parent 4de816a commit a75cd24

21 files changed

+75
-69
lines changed

examples/message_demo/src/message_demo.rs

+8-8
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@ use std::convert::TryInto;
33
use anyhow::{Error, Result};
44
use rosidl_runtime_rs::{seq, BoundedSequence, Message, Sequence};
55

6-
use rclrs::RclrsErrorFilter;
6+
use rclrs::*;
77

88
fn check_default_values() {
99
let msg = rclrs_example_msgs::msg::rmw::VariousTypes::default();
@@ -140,41 +140,41 @@ fn demonstrate_sequences() {
140140
fn demonstrate_pubsub() -> Result<(), Error> {
141141
println!("================== Interoperability demo ==================");
142142
// Demonstrate interoperability between idiomatic and RMW-native message types
143-
let mut executor = rclrs::Context::default_from_env()?.create_basic_executor();
143+
let mut executor = Context::default_from_env()?.create_basic_executor();
144144
let node = executor.create_node("message_demo")?;
145145

146146
let idiomatic_publisher = node.create_publisher::<rclrs_example_msgs::msg::VariousTypes>(
147147
"topic",
148-
rclrs::QOS_PROFILE_DEFAULT,
148+
QOS_PROFILE_DEFAULT,
149149
)?;
150150
let direct_publisher = node.create_publisher::<rclrs_example_msgs::msg::rmw::VariousTypes>(
151151
"topic",
152-
rclrs::QOS_PROFILE_DEFAULT,
152+
QOS_PROFILE_DEFAULT,
153153
)?;
154154

155155
let _idiomatic_subscription = node
156156
.create_subscription::<rclrs_example_msgs::msg::VariousTypes, _>(
157157
"topic",
158-
rclrs::QOS_PROFILE_DEFAULT,
158+
QOS_PROFILE_DEFAULT,
159159
move |_msg: rclrs_example_msgs::msg::VariousTypes| println!("Got idiomatic message!"),
160160
)?;
161161
let _direct_subscription = node
162162
.create_subscription::<rclrs_example_msgs::msg::rmw::VariousTypes, _>(
163163
"topic",
164-
rclrs::QOS_PROFILE_DEFAULT,
164+
QOS_PROFILE_DEFAULT,
165165
move |_msg: rclrs_example_msgs::msg::rmw::VariousTypes| {
166166
println!("Got RMW-native message!")
167167
},
168168
)?;
169169
println!("Sending idiomatic message.");
170170
idiomatic_publisher.publish(rclrs_example_msgs::msg::VariousTypes::default())?;
171171
executor
172-
.spin(rclrs::SpinOptions::spin_once())
172+
.spin(SpinOptions::spin_once())
173173
.first_error()?;
174174
println!("Sending RMW-native message.");
175175
direct_publisher.publish(rclrs_example_msgs::msg::rmw::VariousTypes::default())?;
176176
executor
177-
.spin(rclrs::SpinOptions::spin_once())
177+
.spin(SpinOptions::spin_once())
178178
.first_error()?;
179179

180180
Ok(())

examples/minimal_client_service/src/minimal_client.rs

+3-3
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,8 @@
11
use anyhow::{Error, Result};
2-
use rclrs::RclrsErrorFilter;
2+
use rclrs::*;
33

44
fn main() -> Result<(), Error> {
5-
let mut executor = rclrs::Context::default_from_env()?.create_basic_executor();
5+
let mut executor = Context::default_from_env()?.create_basic_executor();
66

77
let node = executor.create_node("minimal_client")?;
88

@@ -30,7 +30,7 @@ fn main() -> Result<(), Error> {
3030

3131
println!("Waiting for response");
3232
executor
33-
.spin(rclrs::SpinOptions::default())
33+
.spin(SpinOptions::default())
3434
.first_error()
3535
.map_err(|err| err.into())
3636
}

examples/minimal_client_service/src/minimal_client_async.rs

+3-2
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,9 @@
11
use anyhow::{Error, Result};
2+
use rclrs::*;
23

34
#[tokio::main]
45
async fn main() -> Result<(), Error> {
5-
let mut executor = rclrs::Context::default_from_env()?.create_basic_executor();
6+
let mut executor = Context::default_from_env()?.create_basic_executor();
67

78
let node = executor.create_node("minimal_client")?;
89

@@ -21,7 +22,7 @@ async fn main() -> Result<(), Error> {
2122
println!("Waiting for response");
2223

2324
let rclrs_spin =
24-
tokio::task::spawn_blocking(move || executor.spin(rclrs::SpinOptions::default()));
25+
tokio::task::spawn_blocking(move || executor.spin(SpinOptions::default()));
2526

2627
let response = future.await?;
2728
println!(

examples/minimal_client_service/src/minimal_service.rs

+3-3
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
use anyhow::{Error, Result};
2-
use rclrs::RclrsErrorFilter;
2+
use rclrs::*;
33

44
fn handle_service(
55
_request_header: &rclrs::rmw_request_id_t,
@@ -12,7 +12,7 @@ fn handle_service(
1212
}
1313

1414
fn main() -> Result<(), Error> {
15-
let mut executor = rclrs::Context::default_from_env()?.create_basic_executor();
15+
let mut executor = Context::default_from_env()?.create_basic_executor();
1616

1717
let node = executor.create_node("minimal_service")?;
1818

@@ -21,7 +21,7 @@ fn main() -> Result<(), Error> {
2121

2222
println!("Starting server");
2323
executor
24-
.spin(rclrs::SpinOptions::default())
24+
.spin(SpinOptions::default())
2525
.first_error()
2626
.map_err(|err| err.into())
2727
}

examples/minimal_pub_sub/src/minimal_publisher.rs

+3-2
Original file line numberDiff line numberDiff line change
@@ -1,13 +1,14 @@
11
use anyhow::{Error, Result};
2+
use rclrs::*;
23

34
fn main() -> Result<(), Error> {
4-
let context = rclrs::Context::default_from_env()?;
5+
let context = Context::default_from_env()?;
56
let executor = context.create_basic_executor();
67

78
let node = executor.create_node("minimal_publisher")?;
89

910
let publisher =
10-
node.create_publisher::<std_msgs::msg::String>("topic", rclrs::QOS_PROFILE_DEFAULT)?;
11+
node.create_publisher::<std_msgs::msg::String>("topic", QOS_PROFILE_DEFAULT)?;
1112

1213
let mut message = std_msgs::msg::String::default();
1314

Original file line numberDiff line numberDiff line change
@@ -1,8 +1,8 @@
11
use anyhow::{Error, Result};
2-
use rclrs::RclrsErrorFilter;
2+
use rclrs::*;
33

44
fn main() -> Result<(), Error> {
5-
let context = rclrs::Context::default_from_env()?;
5+
let context = Context::default_from_env()?;
66
let mut executor = context.create_basic_executor();
77

88
let node = executor.create_node("minimal_subscriber")?;
@@ -11,7 +11,7 @@ fn main() -> Result<(), Error> {
1111

1212
let _subscription = node.create_subscription::<std_msgs::msg::String, _>(
1313
"topic",
14-
rclrs::QOS_PROFILE_DEFAULT,
14+
QOS_PROFILE_DEFAULT,
1515
move |msg: std_msgs::msg::String| {
1616
num_messages += 1;
1717
println!("I heard: '{}'", msg.data);
@@ -20,7 +20,7 @@ fn main() -> Result<(), Error> {
2020
)?;
2121

2222
executor
23-
.spin(rclrs::SpinOptions::default())
23+
.spin(SpinOptions::default())
2424
.first_error()
2525
.map_err(|err| err.into())
2626
}

examples/minimal_pub_sub/src/minimal_two_nodes.rs

+10-10
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
use rclrs::RclrsErrorFilter;
1+
use rclrs::*;
22
use std::sync::{
33
atomic::{AtomicU32, Ordering},
44
Arc, Mutex,
@@ -8,16 +8,16 @@ use anyhow::{Error, Result};
88

99
struct MinimalSubscriber {
1010
num_messages: AtomicU32,
11-
node: Arc<rclrs::Node>,
12-
subscription: Mutex<Option<Arc<rclrs::Subscription<std_msgs::msg::String>>>>,
11+
node: Arc<Node>,
12+
subscription: Mutex<Option<Arc<Subscription<std_msgs::msg::String>>>>,
1313
}
1414

1515
impl MinimalSubscriber {
1616
pub fn new(
17-
executor: &rclrs::Executor,
17+
executor: &Executor,
1818
name: &str,
1919
topic: &str,
20-
) -> Result<Arc<Self>, rclrs::RclrsError> {
20+
) -> Result<Arc<Self>, RclrsError> {
2121
let node = executor.create_node(name)?;
2222
let minimal_subscriber = Arc::new(MinimalSubscriber {
2323
num_messages: 0.into(),
@@ -30,7 +30,7 @@ impl MinimalSubscriber {
3030
.node
3131
.create_subscription::<std_msgs::msg::String, _>(
3232
topic,
33-
rclrs::QOS_PROFILE_DEFAULT,
33+
QOS_PROFILE_DEFAULT,
3434
move |msg: std_msgs::msg::String| {
3535
minimal_subscriber_aux.callback(msg);
3636
},
@@ -51,7 +51,7 @@ impl MinimalSubscriber {
5151
}
5252

5353
fn main() -> Result<(), Error> {
54-
let mut executor = rclrs::Context::default_from_env()?.create_basic_executor();
54+
let mut executor = Context::default_from_env()?.create_basic_executor();
5555
let publisher_node = executor.create_node("minimal_publisher")?;
5656

5757
let _subscriber_node_one =
@@ -60,9 +60,9 @@ fn main() -> Result<(), Error> {
6060
MinimalSubscriber::new(&executor, "minimal_subscriber_two", "topic")?;
6161

6262
let publisher = publisher_node
63-
.create_publisher::<std_msgs::msg::String>("topic", rclrs::QOS_PROFILE_DEFAULT)?;
63+
.create_publisher::<std_msgs::msg::String>("topic", QOS_PROFILE_DEFAULT)?;
6464

65-
std::thread::spawn(move || -> Result<(), rclrs::RclrsError> {
65+
std::thread::spawn(move || -> Result<(), RclrsError> {
6666
let mut message = std_msgs::msg::String::default();
6767
let mut publish_count: u32 = 1;
6868
loop {
@@ -75,7 +75,7 @@ fn main() -> Result<(), Error> {
7575
});
7676

7777
executor
78-
.spin(rclrs::SpinOptions::default())
78+
.spin(SpinOptions::default())
7979
.first_error()
8080
.map_err(|err| err.into())
8181
}

examples/minimal_pub_sub/src/zero_copy_publisher.rs

+3-2
Original file line numberDiff line numberDiff line change
@@ -1,13 +1,14 @@
11
use anyhow::{Error, Result};
2+
use rclrs::*;
23

34
fn main() -> Result<(), Error> {
4-
let context = rclrs::Context::default_from_env()?;
5+
let context = Context::default_from_env()?;
56
let executor = context.create_basic_executor();
67

78
let node = executor.create_node("minimal_publisher")?;
89

910
let publisher =
10-
node.create_publisher::<std_msgs::msg::rmw::UInt32>("topic", rclrs::QOS_PROFILE_DEFAULT)?;
11+
node.create_publisher::<std_msgs::msg::rmw::UInt32>("topic", QOS_PROFILE_DEFAULT)?;
1112

1213
let mut publish_count: u32 = 1;
1314

Original file line numberDiff line numberDiff line change
@@ -1,25 +1,25 @@
11
use anyhow::{Error, Result};
2-
use rclrs::RclrsErrorFilter;
2+
use rclrs::*;
33

44
fn main() -> Result<(), Error> {
5-
let mut executor = rclrs::Context::default_from_env()?.create_basic_executor();
5+
let mut executor = Context::default_from_env()?.create_basic_executor();
66

77
let node = executor.create_node("minimal_subscriber")?;
88

99
let mut num_messages: usize = 0;
1010

1111
let _subscription = node.create_subscription::<std_msgs::msg::UInt32, _>(
1212
"topic",
13-
rclrs::QOS_PROFILE_DEFAULT,
14-
move |msg: rclrs::ReadOnlyLoanedMessage<'_, std_msgs::msg::UInt32>| {
13+
QOS_PROFILE_DEFAULT,
14+
move |msg: ReadOnlyLoanedMessage<'_, std_msgs::msg::UInt32>| {
1515
num_messages += 1;
1616
println!("I heard: '{}'", msg.data);
1717
println!("(Got {} messages so far)", num_messages);
1818
},
1919
)?;
2020

2121
executor
22-
.spin(rclrs::SpinOptions::default())
22+
.spin(SpinOptions::default())
2323
.first_error()
2424
.map_err(|err| err.into())
2525
}

examples/rust_pubsub/src/simple_publisher.rs

+1-3
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,4 @@
1-
use rclrs::{
2-
Context, Executor, Publisher, RclrsError, RclrsErrorFilter, SpinOptions, QOS_PROFILE_DEFAULT,
3-
};
1+
use rclrs::*;
42
use std::{sync::Arc, thread, time::Duration};
53
use std_msgs::msg::String as StringMsg;
64

examples/rust_pubsub/src/simple_subscriber.rs

+1-3
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,4 @@
1-
use rclrs::{
2-
Context, Executor, RclrsError, RclrsErrorFilter, SpinOptions, Subscription, QOS_PROFILE_DEFAULT,
3-
};
1+
use rclrs::*;
42
use std::{
53
sync::{Arc, Mutex},
64
thread,

rclrs/src/context.rs

+1-6
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,7 @@ use std::{
66
vec::Vec,
77
};
88

9-
use crate::{rcl_bindings::*, Executor, LoggingLifecycle, RclrsError, ToResult};
9+
use crate::{rcl_bindings::*, LoggingLifecycle, RclrsError, ToResult};
1010

1111
/// This is locked whenever initializing or dropping any middleware entity
1212
/// because we have found issues in RCL and some RMW implementations that
@@ -183,11 +183,6 @@ impl Context {
183183
Self::new(std::env::args(), InitOptions::default())
184184
}
185185

186-
/// Create a basic executor that comes built into rclrs.
187-
pub fn create_basic_executor(&self) -> Executor {
188-
Executor::new(Arc::clone(&self.handle))
189-
}
190-
191186
/// Returns the ROS domain ID that the context is using.
192187
///
193188
/// The domain ID controls which nodes can send messages to each other, see the [ROS 2 concept article][1].

rclrs/src/executor.rs

+14-1
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,6 @@
11
use crate::{
2-
rcl_bindings::rcl_context_is_valid, ContextHandle, IntoNodeOptions, Node, RclrsError, WaitSet,
2+
rcl_bindings::rcl_context_is_valid, Context, ContextHandle, IntoNodeOptions, Node, RclrsError,
3+
WaitSet,
34
};
45
use std::{
56
sync::{Arc, Mutex, Weak},
@@ -128,3 +129,15 @@ impl SpinOptions {
128129
self
129130
}
130131
}
132+
133+
/// This trait allows [`Context`] to create a basic executor.
134+
pub trait CreateBasicExecutor {
135+
/// Create a basic executor associated with this [`Context`].
136+
fn create_basic_executor(&self) -> Executor;
137+
}
138+
139+
impl CreateBasicExecutor for Context {
140+
fn create_basic_executor(&self) -> Executor {
141+
Executor::new(Arc::clone(&self.handle))
142+
}
143+
}

rclrs/src/logging.rs

+1-1
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,7 @@ pub use logger::*;
2525
/// # Examples
2626
///
2727
/// ```
28-
/// use rclrs::{log, ToLogParams};
28+
/// use rclrs::*;
2929
/// use std::sync::Mutex;
3030
/// use std::time::Duration;
3131
/// use std::env;

rclrs/src/node.rs

+5-5
Original file line numberDiff line numberDiff line change
@@ -150,7 +150,7 @@ impl Node {
150150
///
151151
/// # Example
152152
/// ```
153-
/// # use rclrs::{Context, InitOptions, RclrsError};
153+
/// # use rclrs::*;
154154
/// // Without remapping
155155
/// let executor = Context::default().create_basic_executor();
156156
/// let node = executor.create_node("my_node")?;
@@ -173,7 +173,7 @@ impl Node {
173173
///
174174
/// # Example
175175
/// ```
176-
/// # use rclrs::{Context, InitOptions, RclrsError, IntoNodeOptions};
176+
/// # use rclrs::*;
177177
/// // Without remapping
178178
/// let executor = Context::default().create_basic_executor();
179179
/// let node = executor.create_node(
@@ -199,7 +199,7 @@ impl Node {
199199
///
200200
/// # Example
201201
/// ```
202-
/// # use rclrs::{Context, RclrsError, IntoNodeOptions};
202+
/// # use rclrs::*;
203203
/// let executor = Context::default().create_basic_executor();
204204
/// let node = executor.create_node(
205205
/// "my_node"
@@ -375,7 +375,7 @@ impl Node {
375375
///
376376
/// # Example
377377
/// ```
378-
/// # use rclrs::{Context, RclrsError};
378+
/// # use rclrs::*;
379379
/// // Set default ROS domain ID to 10 here
380380
/// std::env::set_var("ROS_DOMAIN_ID", "10");
381381
/// let executor = Context::default().create_basic_executor();
@@ -403,7 +403,7 @@ impl Node {
403403
///
404404
/// # Example
405405
/// ```
406-
/// # use rclrs::{Context, ParameterRange, RclrsError};
406+
/// # use rclrs::*;
407407
/// let executor = Context::default().create_basic_executor();
408408
/// let node = executor.create_node("domain_id_node")?;
409409
/// // Set it to a range of 0-100, with a step of 2

0 commit comments

Comments
 (0)