Skip to content

Commit c463201

Browse files
authored
Execution structure (spin-off of #427) (#428)
* Migrate Context, Executor, and Node creation to new API Signed-off-by: Michael X. Grey <[email protected]> * Update examples Signed-off-by: Michael X. Grey <[email protected]> * Fix documentation Signed-off-by: Michael X. Grey <[email protected]> * Fix formatting Signed-off-by: Michael X. Grey <[email protected]> * Fix example formatting Signed-off-by: Michael X. Grey <[email protected]> * Implicitly cast &str to NodeOptions Signed-off-by: Michael X. Grey <[email protected]> * Remove debug outputs Signed-off-by: Michael X. Grey <[email protected]> * Fix formatting Signed-off-by: Michael X. Grey <[email protected]> * Return a Vec of errors from spinning Signed-off-by: Michael X. Grey <[email protected]> * update examples Signed-off-by: Michael X. Grey <[email protected]> * Fix example formatting Signed-off-by: Michael X. Grey <[email protected]> * Introduce CreateBasicExecutor trait Signed-off-by: Michael X. Grey <[email protected]> * Fix formatting Signed-off-by: Michael X. Grey <[email protected]> * Add documentation for Context::default Signed-off-by: Michael X. Grey <[email protected]> * Automatically clear dead nodes from the executor Signed-off-by: Michael X. Grey <[email protected]> * Update reference index Signed-off-by: Michael X. Grey <[email protected]> * Fix style Signed-off-by: Michael X. Grey <[email protected]> --------- Signed-off-by: Michael X. Grey <[email protected]> Signed-off-by: Michael X. Grey <[email protected]>
1 parent ab4cb3c commit c463201

28 files changed

+798
-601
lines changed

examples/message_demo/src/message_demo.rs

+12-12
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,10 @@
1-
use std::{convert::TryInto, env, sync::Arc};
1+
use std::convert::TryInto;
22

33
use anyhow::{Error, Result};
44
use rosidl_runtime_rs::{seq, BoundedSequence, Message, Sequence};
55

6+
use rclrs::*;
7+
68
fn check_default_values() {
79
let msg = rclrs_example_msgs::msg::rmw::VariousTypes::default();
810
assert!(msg.bool_member);
@@ -138,38 +140,36 @@ fn demonstrate_sequences() {
138140
fn demonstrate_pubsub() -> Result<(), Error> {
139141
println!("================== Interoperability demo ==================");
140142
// Demonstrate interoperability between idiomatic and RMW-native message types
141-
let context = rclrs::Context::new(env::args())?;
142-
let node = rclrs::create_node(&context, "message_demo")?;
143+
let mut executor = Context::default_from_env()?.create_basic_executor();
144+
let node = executor.create_node("message_demo")?;
143145

144-
let idiomatic_publisher = node.create_publisher::<rclrs_example_msgs::msg::VariousTypes>(
145-
"topic",
146-
rclrs::QOS_PROFILE_DEFAULT,
147-
)?;
146+
let idiomatic_publisher = node
147+
.create_publisher::<rclrs_example_msgs::msg::VariousTypes>("topic", QOS_PROFILE_DEFAULT)?;
148148
let direct_publisher = node.create_publisher::<rclrs_example_msgs::msg::rmw::VariousTypes>(
149149
"topic",
150-
rclrs::QOS_PROFILE_DEFAULT,
150+
QOS_PROFILE_DEFAULT,
151151
)?;
152152

153153
let _idiomatic_subscription = node
154154
.create_subscription::<rclrs_example_msgs::msg::VariousTypes, _>(
155155
"topic",
156-
rclrs::QOS_PROFILE_DEFAULT,
156+
QOS_PROFILE_DEFAULT,
157157
move |_msg: rclrs_example_msgs::msg::VariousTypes| println!("Got idiomatic message!"),
158158
)?;
159159
let _direct_subscription = node
160160
.create_subscription::<rclrs_example_msgs::msg::rmw::VariousTypes, _>(
161161
"topic",
162-
rclrs::QOS_PROFILE_DEFAULT,
162+
QOS_PROFILE_DEFAULT,
163163
move |_msg: rclrs_example_msgs::msg::rmw::VariousTypes| {
164164
println!("Got RMW-native message!")
165165
},
166166
)?;
167167
println!("Sending idiomatic message.");
168168
idiomatic_publisher.publish(rclrs_example_msgs::msg::VariousTypes::default())?;
169-
rclrs::spin_once(Arc::clone(&node), None)?;
169+
executor.spin(SpinOptions::spin_once()).first_error()?;
170170
println!("Sending RMW-native message.");
171171
direct_publisher.publish(rclrs_example_msgs::msg::rmw::VariousTypes::default())?;
172-
rclrs::spin_once(Arc::clone(&node), None)?;
172+
executor.spin(SpinOptions::spin_once()).first_error()?;
173173

174174
Ok(())
175175
}

examples/minimal_client_service/src/minimal_client.rs

+7-5
Original file line numberDiff line numberDiff line change
@@ -1,11 +1,10 @@
1-
use std::env;
2-
31
use anyhow::{Error, Result};
2+
use rclrs::*;
43

54
fn main() -> Result<(), Error> {
6-
let context = rclrs::Context::new(env::args())?;
5+
let mut executor = Context::default_from_env()?.create_basic_executor();
76

8-
let node = rclrs::create_node(&context, "minimal_client")?;
7+
let node = executor.create_node("minimal_client")?;
98

109
let client = node.create_client::<example_interfaces::srv::AddTwoInts>("add_two_ints")?;
1110

@@ -30,5 +29,8 @@ fn main() -> Result<(), Error> {
3029
std::thread::sleep(std::time::Duration::from_millis(500));
3130

3231
println!("Waiting for response");
33-
rclrs::spin(node).map_err(|err| err.into())
32+
executor
33+
.spin(SpinOptions::default())
34+
.first_error()
35+
.map_err(|err| err.into())
3436
}

examples/minimal_client_service/src/minimal_client_async.rs

+4-5
Original file line numberDiff line numberDiff line change
@@ -1,12 +1,11 @@
1-
use std::env;
2-
31
use anyhow::{Error, Result};
2+
use rclrs::*;
43

54
#[tokio::main]
65
async fn main() -> Result<(), Error> {
7-
let context = rclrs::Context::new(env::args())?;
6+
let mut executor = Context::default_from_env()?.create_basic_executor();
87

9-
let node = rclrs::create_node(&context, "minimal_client")?;
8+
let node = executor.create_node("minimal_client")?;
109

1110
let client = node.create_client::<example_interfaces::srv::AddTwoInts>("add_two_ints")?;
1211

@@ -22,7 +21,7 @@ async fn main() -> Result<(), Error> {
2221

2322
println!("Waiting for response");
2423

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

2726
let response = future.await?;
2827
println!(
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,5 @@
1-
use std::env;
2-
31
use anyhow::{Error, Result};
2+
use rclrs::*;
43

54
fn handle_service(
65
_request_header: &rclrs::rmw_request_id_t,
@@ -13,13 +12,16 @@ fn handle_service(
1312
}
1413

1514
fn main() -> Result<(), Error> {
16-
let context = rclrs::Context::new(env::args())?;
15+
let mut executor = Context::default_from_env()?.create_basic_executor();
1716

18-
let node = rclrs::create_node(&context, "minimal_service")?;
17+
let node = executor.create_node("minimal_service")?;
1918

2019
let _server = node
2120
.create_service::<example_interfaces::srv::AddTwoInts, _>("add_two_ints", handle_service)?;
2221

2322
println!("Starting server");
24-
rclrs::spin(node).map_err(|err| err.into())
23+
executor
24+
.spin(SpinOptions::default())
25+
.first_error()
26+
.map_err(|err| err.into())
2527
}

examples/minimal_pub_sub/src/minimal_publisher.rs

+5-6
Original file line numberDiff line numberDiff line change
@@ -1,14 +1,13 @@
1-
use std::env;
2-
31
use anyhow::{Error, Result};
2+
use rclrs::*;
43

54
fn main() -> Result<(), Error> {
6-
let context = rclrs::Context::new(env::args())?;
5+
let context = Context::default_from_env()?;
6+
let executor = context.create_basic_executor();
77

8-
let node = rclrs::create_node(&context, "minimal_publisher")?;
8+
let node = executor.create_node("minimal_publisher")?;
99

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

1312
let mut message = std_msgs::msg::String::default();
1413

Original file line numberDiff line numberDiff line change
@@ -1,23 +1,26 @@
1-
use std::env;
2-
31
use anyhow::{Error, Result};
2+
use rclrs::*;
43

54
fn main() -> Result<(), Error> {
6-
let context = rclrs::Context::new(env::args())?;
5+
let context = Context::default_from_env()?;
6+
let mut executor = context.create_basic_executor();
77

8-
let node = rclrs::create_node(&context, "minimal_subscriber")?;
8+
let node = executor.create_node("minimal_subscriber")?;
99

1010
let mut num_messages: usize = 0;
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);
1818
println!("(Got {} messages so far)", num_messages);
1919
},
2020
)?;
2121

22-
rclrs::spin(node).map_err(|err| err.into())
22+
executor
23+
.spin(SpinOptions::default())
24+
.first_error()
25+
.map_err(|err| err.into())
2326
}
Original file line numberDiff line numberDiff line change
@@ -1,23 +1,20 @@
1-
use std::{
2-
env,
3-
sync::{
4-
atomic::{AtomicU32, Ordering},
5-
Arc, Mutex,
6-
},
1+
use rclrs::*;
2+
use std::sync::{
3+
atomic::{AtomicU32, Ordering},
4+
Arc, Mutex,
75
};
86

97
use anyhow::{Error, Result};
108

119
struct MinimalSubscriber {
1210
num_messages: AtomicU32,
13-
node: Arc<rclrs::Node>,
14-
subscription: Mutex<Option<Arc<rclrs::Subscription<std_msgs::msg::String>>>>,
11+
node: Arc<Node>,
12+
subscription: Mutex<Option<Arc<Subscription<std_msgs::msg::String>>>>,
1513
}
1614

1715
impl MinimalSubscriber {
18-
pub fn new(name: &str, topic: &str) -> Result<Arc<Self>, rclrs::RclrsError> {
19-
let context = rclrs::Context::new(env::args())?;
20-
let node = rclrs::create_node(&context, name)?;
16+
pub fn new(executor: &Executor, name: &str, topic: &str) -> Result<Arc<Self>, RclrsError> {
17+
let node = executor.create_node(name)?;
2118
let minimal_subscriber = Arc::new(MinimalSubscriber {
2219
num_messages: 0.into(),
2320
node,
@@ -29,7 +26,7 @@ impl MinimalSubscriber {
2926
.node
3027
.create_subscription::<std_msgs::msg::String, _>(
3128
topic,
32-
rclrs::QOS_PROFILE_DEFAULT,
29+
QOS_PROFILE_DEFAULT,
3330
move |msg: std_msgs::msg::String| {
3431
minimal_subscriber_aux.callback(msg);
3532
},
@@ -50,16 +47,18 @@ impl MinimalSubscriber {
5047
}
5148

5249
fn main() -> Result<(), Error> {
53-
let publisher_context = rclrs::Context::new(env::args())?;
54-
let publisher_node = rclrs::create_node(&publisher_context, "minimal_publisher")?;
50+
let mut executor = Context::default_from_env()?.create_basic_executor();
51+
let publisher_node = executor.create_node("minimal_publisher")?;
5552

56-
let subscriber_node_one = MinimalSubscriber::new("minimal_subscriber_one", "topic")?;
57-
let subscriber_node_two = MinimalSubscriber::new("minimal_subscriber_two", "topic")?;
53+
let _subscriber_node_one =
54+
MinimalSubscriber::new(&executor, "minimal_subscriber_one", "topic")?;
55+
let _subscriber_node_two =
56+
MinimalSubscriber::new(&executor, "minimal_subscriber_two", "topic")?;
5857

59-
let publisher = publisher_node
60-
.create_publisher::<std_msgs::msg::String>("topic", rclrs::QOS_PROFILE_DEFAULT)?;
58+
let publisher =
59+
publisher_node.create_publisher::<std_msgs::msg::String>("topic", QOS_PROFILE_DEFAULT)?;
6160

62-
std::thread::spawn(move || -> Result<(), rclrs::RclrsError> {
61+
std::thread::spawn(move || -> Result<(), RclrsError> {
6362
let mut message = std_msgs::msg::String::default();
6463
let mut publish_count: u32 = 1;
6564
loop {
@@ -71,11 +70,8 @@ fn main() -> Result<(), Error> {
7170
}
7271
});
7372

74-
let executor = rclrs::SingleThreadedExecutor::new();
75-
76-
executor.add_node(&publisher_node)?;
77-
executor.add_node(&subscriber_node_one.node)?;
78-
executor.add_node(&subscriber_node_two.node)?;
79-
80-
executor.spin().map_err(|err| err.into())
73+
executor
74+
.spin(SpinOptions::default())
75+
.first_error()
76+
.map_err(|err| err.into())
8177
}

examples/minimal_pub_sub/src/zero_copy_publisher.rs

+5-5
Original file line numberDiff line numberDiff line change
@@ -1,14 +1,14 @@
1-
use std::env;
2-
31
use anyhow::{Error, Result};
2+
use rclrs::*;
43

54
fn main() -> Result<(), Error> {
6-
let context = rclrs::Context::new(env::args())?;
5+
let context = Context::default_from_env()?;
6+
let executor = context.create_basic_executor();
77

8-
let node = rclrs::create_node(&context, "minimal_publisher")?;
8+
let node = executor.create_node("minimal_publisher")?;
99

1010
let publisher =
11-
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)?;
1212

1313
let mut publish_count: u32 = 1;
1414

Original file line numberDiff line numberDiff line change
@@ -1,23 +1,25 @@
1-
use std::env;
2-
31
use anyhow::{Error, Result};
2+
use rclrs::*;
43

54
fn main() -> Result<(), Error> {
6-
let context = rclrs::Context::new(env::args())?;
5+
let mut executor = Context::default_from_env()?.create_basic_executor();
76

8-
let node = rclrs::create_node(&context, "minimal_subscriber")?;
7+
let node = executor.create_node("minimal_subscriber")?;
98

109
let mut num_messages: usize = 0;
1110

1211
let _subscription = node.create_subscription::<std_msgs::msg::UInt32, _>(
1312
"topic",
14-
rclrs::QOS_PROFILE_DEFAULT,
15-
move |msg: rclrs::ReadOnlyLoanedMessage<'_, std_msgs::msg::UInt32>| {
13+
QOS_PROFILE_DEFAULT,
14+
move |msg: ReadOnlyLoanedMessage<'_, std_msgs::msg::UInt32>| {
1615
num_messages += 1;
1716
println!("I heard: '{}'", msg.data);
1817
println!("(Got {} messages so far)", num_messages);
1918
},
2019
)?;
2120

22-
rclrs::spin(node).map_err(|err| err.into())
21+
executor
22+
.spin(SpinOptions::default())
23+
.first_error()
24+
.map_err(|err| err.into())
2325
}
+14-13
Original file line numberDiff line numberDiff line change
@@ -1,36 +1,37 @@
1-
use rclrs::{create_node, Context, Node, Publisher, RclrsError, QOS_PROFILE_DEFAULT};
1+
use rclrs::*;
22
use std::{sync::Arc, thread, time::Duration};
33
use std_msgs::msg::String as StringMsg;
4-
struct SimplePublisherNode {
5-
node: Arc<Node>,
6-
_publisher: Arc<Publisher<StringMsg>>,
4+
5+
struct SimplePublisher {
6+
publisher: Arc<Publisher<StringMsg>>,
77
}
8-
impl SimplePublisherNode {
9-
fn new(context: &Context) -> Result<Self, RclrsError> {
10-
let node = create_node(context, "simple_publisher").unwrap();
11-
let _publisher = node
8+
9+
impl SimplePublisher {
10+
fn new(executor: &Executor) -> Result<Self, RclrsError> {
11+
let node = executor.create_node("simple_publisher").unwrap();
12+
let publisher = node
1213
.create_publisher("publish_hello", QOS_PROFILE_DEFAULT)
1314
.unwrap();
14-
Ok(Self { node, _publisher })
15+
Ok(Self { publisher })
1516
}
1617

1718
fn publish_data(&self, increment: i32) -> Result<i32, RclrsError> {
1819
let msg: StringMsg = StringMsg {
1920
data: format!("Hello World {}", increment),
2021
};
21-
self._publisher.publish(msg).unwrap();
22+
self.publisher.publish(msg).unwrap();
2223
Ok(increment + 1_i32)
2324
}
2425
}
2526

2627
fn main() -> Result<(), RclrsError> {
27-
let context = Context::new(std::env::args()).unwrap();
28-
let publisher = Arc::new(SimplePublisherNode::new(&context).unwrap());
28+
let mut executor = Context::default_from_env().unwrap().create_basic_executor();
29+
let publisher = Arc::new(SimplePublisher::new(&executor).unwrap());
2930
let publisher_other_thread = Arc::clone(&publisher);
3031
let mut count: i32 = 0;
3132
thread::spawn(move || loop {
3233
thread::sleep(Duration::from_millis(1000));
3334
count = publisher_other_thread.publish_data(count).unwrap();
3435
});
35-
rclrs::spin(publisher.node.clone())
36+
executor.spin(SpinOptions::default()).first_error()
3637
}

0 commit comments

Comments
 (0)