Skip to content

Commit 46f1b67

Browse files
authored
Merge pull request #191 from RosLibRust/topic-provider-improvements
Topic provider improvements
2 parents 074f0d5 + 33d157f commit 46f1b67

File tree

15 files changed

+409
-105
lines changed

15 files changed

+409
-105
lines changed

CHANGELOG.md

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -67,6 +67,11 @@ and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0
6767
### Changed
6868

6969
- ROS1 Node Handle's advertise() now requires a latching argument
70+
- RosBridge ClientHandle [call_service()] is now templated on the service type instead of on both the request and response type.
71+
This is to bring it in line with the ROS1 API.
72+
- RosBridge ClientHandle::Publisher publish() now takes a reference to the message instead of taking ownership.
73+
This is to bring it in line with the ROS1 API.
74+
- The RosServiceType trait used by codegen now requires 'static + Send + Sync this will not affect any generated types, but custom types may have issue.
7075

7176
## 0.10.2 - August 3rd, 2024
7277

roslibrust/examples/basic_publisher.rs

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@ async fn main() -> Result<(), anyhow::Error> {
2121
loop {
2222
let msg = std_msgs::Header::default();
2323
info!("About to publish");
24-
let result = publisher.publish(msg).await;
24+
let result = publisher.publish(&msg).await;
2525
match result {
2626
Ok(()) => {
2727
info!("Published msg!");

roslibrust/examples/calling_service.rs

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,7 @@ async fn main() -> Result<(), anyhow::Error> {
1818
let client = ClientHandle::new("ws://localhost:9090").await?;
1919

2020
let result = client
21-
.call_service::<(), rosapi::GetTimeResponse>("/rosapi/get_time", ())
21+
.call_service::<rosapi::GetTime>("/rosapi/get_time", rosapi::GetTimeRequest {})
2222
.await
2323
.expect("Error while calling get_time service");
2424

roslibrust/examples/generic_client.rs

Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -29,6 +29,7 @@ async fn main() {
2929
name: String,
3030
}
3131

32+
// Basic example of a node that publishes and subscribes to itself
3233
impl<T: TopicProvider> MyNode<T> {
3334
async fn run(self) {
3435
let publisher = self
@@ -37,6 +38,19 @@ async fn main() {
3738
.await
3839
.unwrap();
3940

41+
let mut subscriber = self
42+
.ros
43+
.subscribe::<std_msgs::String>("/chatter")
44+
.await
45+
.unwrap();
46+
47+
tokio::spawn(async move {
48+
loop {
49+
let msg = subscriber.next().await.unwrap();
50+
println!("Got message: {}", msg.data);
51+
}
52+
});
53+
4054
loop {
4155
let msg = std_msgs::String {
4256
data: format!("Hello world from {}", self.name),
Lines changed: 94 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,94 @@
1+
//! Purpose of this example is to show how the ServiceProvider trait can be use
2+
//! to create code that is generic of which communication backend it will use.
3+
4+
#[cfg(feature = "topic_provider")]
5+
#[tokio::main]
6+
async fn main() {
7+
simple_logger::SimpleLogger::new()
8+
.with_level(log::LevelFilter::Debug)
9+
.without_timestamps() // required for running wsl2
10+
.init()
11+
.unwrap();
12+
13+
use roslibrust::topic_provider::*;
14+
15+
roslibrust_codegen_macro::find_and_generate_ros_messages!(
16+
"assets/ros1_common_interfaces/ros_comm_msgs/std_srvs"
17+
);
18+
// TopicProvider cannot be an "Object Safe Trait" due to its generic parameters
19+
// This means we can't do:
20+
21+
// Which specific TopicProvider you are going to use must be known at
22+
// compile time! We can use features to build multiple copies of our
23+
// executable with different backends. Or mix and match within a
24+
// single application. The critical part is to make TopicProvider a
25+
// generic type on you Node.
26+
27+
struct MyNode<T: ServiceProvider + 'static> {
28+
ros: T,
29+
}
30+
31+
// Basic example of a node that publishes and subscribes to itself
32+
impl<T: ServiceProvider> MyNode<T> {
33+
fn handle_service(
34+
_request: std_srvs::SetBoolRequest,
35+
) -> Result<std_srvs::SetBoolResponse, Box<dyn std::error::Error + Send + Sync>> {
36+
// Not actually doing anything here just example
37+
// Note: if we did want to set a bool, we'd probably want to use Arc<Mutex<bool>>
38+
Ok(std_srvs::SetBoolResponse {
39+
success: true,
40+
message: "You set my bool!".to_string(),
41+
})
42+
}
43+
44+
async fn run(self) {
45+
let _handle = self
46+
.ros
47+
.advertise_service::<std_srvs::SetBool, _>("/my_set_bool", Self::handle_service)
48+
.await
49+
.unwrap();
50+
51+
let client = self
52+
.ros
53+
.service_client::<std_srvs::SetBool>("/my_set_bool")
54+
.await
55+
.unwrap();
56+
57+
loop {
58+
tokio::time::sleep(std::time::Duration::from_millis(500)).await;
59+
println!("sleeping");
60+
61+
client
62+
.call(&std_srvs::SetBoolRequest { data: true })
63+
.await
64+
.unwrap();
65+
}
66+
}
67+
}
68+
69+
// create a rosbridge handle and start node
70+
let ros = roslibrust::ClientHandle::new("ws://localhost:9090")
71+
.await
72+
.unwrap();
73+
let node = MyNode { ros };
74+
tokio::spawn(async move { node.run().await });
75+
76+
// create a ros1 handle and start node
77+
let ros = roslibrust::ros1::NodeHandle::new("http://localhost:11311", "/my_node")
78+
.await
79+
.unwrap();
80+
let node = MyNode { ros };
81+
tokio::spawn(async move { node.run().await });
82+
83+
loop {
84+
tokio::time::sleep(std::time::Duration::from_millis(500)).await;
85+
println!("sleeping");
86+
}
87+
88+
// With this executable running
89+
// RUST_LOG=debug cargo run --features ros1,topic_provider --example generic_client_services
90+
// You should see log output from both nodes
91+
}
92+
93+
#[cfg(not(feature = "topic_provider"))]
94+
fn main() {}

roslibrust/examples/ros1_ros2_bridge_example.rs

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -93,7 +93,7 @@ async fn main() -> Result<(), anyhow::Error> {
9393
};
9494

9595
// and re-publish it!
96-
publisher.publish(converted_msg).await?;
96+
publisher.publish(&converted_msg).await?;
9797
info!("Message successfully sent to ros2!");
9898
}
9999
}

roslibrust/src/rosapi/mod.rs

Lines changed: 24 additions & 21 deletions
Original file line numberDiff line numberDiff line change
@@ -100,13 +100,13 @@ trait RosApi {
100100
impl RosApi for ClientHandle {
101101
/// Get the current time
102102
async fn get_time(&self) -> RosLibRustResult<rosapi::GetTimeResponse> {
103-
self.call_service("/rosapi/get_time", rosapi::GetTimeRequest {})
103+
self.call_service::<rosapi::GetTime>("/rosapi/get_time", rosapi::GetTimeRequest {})
104104
.await
105105
}
106106

107107
/// Get the list of topics active
108108
async fn topics(&self) -> RosLibRustResult<rosapi::TopicsResponse> {
109-
self.call_service("/rosapi/topics", rosapi::TopicsRequest {})
109+
self.call_service::<rosapi::Topics>("/rosapi/topics", rosapi::TopicsRequest {})
110110
.await
111111
}
112112

@@ -115,7 +115,7 @@ impl RosApi for ClientHandle {
115115
&self,
116116
topic: impl Into<String> + Send,
117117
) -> RosLibRustResult<rosapi::TopicTypeResponse> {
118-
self.call_service(
118+
self.call_service::<rosapi::TopicType>(
119119
"/rosapi/topic_type",
120120
rosapi::TopicTypeRequest {
121121
topic: topic.into(),
@@ -129,7 +129,7 @@ impl RosApi for ClientHandle {
129129
&self,
130130
topic_type: impl Into<String> + Send,
131131
) -> RosLibRustResult<rosapi::TopicsForTypeResponse> {
132-
self.call_service(
132+
self.call_service::<rosapi::TopicsForType>(
133133
"/rosapi/topics_for_type",
134134
rosapi::TopicsForTypeRequest {
135135
r#type: topic_type.into(),
@@ -140,7 +140,7 @@ impl RosApi for ClientHandle {
140140

141141
/// Returns list of nodes active in a system
142142
async fn get_nodes(&self) -> RosLibRustResult<rosapi::NodesResponse> {
143-
self.call_service("/rosapi/nodes", rosapi::NodesRequest {})
143+
self.call_service::<rosapi::Nodes>("/rosapi/nodes", rosapi::NodesRequest {})
144144
.await
145145
}
146146

@@ -150,7 +150,7 @@ impl RosApi for ClientHandle {
150150
&self,
151151
node: impl Into<String> + Send,
152152
) -> RosLibRustResult<rosapi::NodeDetailsResponse> {
153-
self.call_service(
153+
self.call_service::<rosapi::NodeDetails>(
154154
"/rosapi/node_details",
155155
rosapi::NodeDetailsRequest { node: node.into() },
156156
)
@@ -162,7 +162,7 @@ impl RosApi for ClientHandle {
162162
&self,
163163
service: impl Into<String> + Send,
164164
) -> RosLibRustResult<rosapi::ServiceNodeResponse> {
165-
self.call_service(
165+
self.call_service::<rosapi::ServiceNode>(
166166
"/rosapi/service_node",
167167
rosapi::ServiceNodeRequest {
168168
service: service.into(),
@@ -178,7 +178,7 @@ impl RosApi for ClientHandle {
178178
param_name: impl Into<String> + Send,
179179
param_value: impl Into<String> + Send,
180180
) -> RosLibRustResult<rosapi::SetParamResponse> {
181-
self.call_service(
181+
self.call_service::<rosapi::SetParam>(
182182
"/rosapi/set_param",
183183
rosapi::SetParamRequest {
184184
name: param_name.into(),
@@ -194,7 +194,7 @@ impl RosApi for ClientHandle {
194194
&self,
195195
param_name: impl Into<String> + Send,
196196
) -> RosLibRustResult<rosapi::GetParamResponse> {
197-
self.call_service(
197+
self.call_service::<rosapi::GetParam>(
198198
"/rosapi/get_param",
199199
rosapi::GetParamRequest {
200200
name: param_name.into(),
@@ -206,16 +206,19 @@ impl RosApi for ClientHandle {
206206

207207
/// Gets the list of currently known parameters.
208208
async fn get_param_names(&self) -> RosLibRustResult<rosapi::GetParamNamesResponse> {
209-
self.call_service("/rosapi/get_param_names", rosapi::GetParamNamesRequest {})
210-
.await
209+
self.call_service::<rosapi::GetParamNames>(
210+
"/rosapi/get_param_names",
211+
rosapi::GetParamNamesRequest {},
212+
)
213+
.await
211214
}
212215

213216
/// Checks whether the given parameter is defined.
214217
async fn has_param(
215218
&self,
216219
param: impl Into<String> + Send,
217220
) -> RosLibRustResult<rosapi::HasParamResponse> {
218-
self.call_service(
221+
self.call_service::<rosapi::HasParam>(
219222
"/rosapi/has_param",
220223
rosapi::HasParamRequest { name: param.into() },
221224
)
@@ -227,7 +230,7 @@ impl RosApi for ClientHandle {
227230
&self,
228231
name: impl Into<String> + Send,
229232
) -> RosLibRustResult<rosapi::DeleteParamResponse> {
230-
self.call_service(
233+
self.call_service::<rosapi::DeleteParam>(
231234
"/rosapi/delete_param",
232235
rosapi::DeleteParamRequest { name: name.into() },
233236
)
@@ -239,7 +242,7 @@ impl RosApi for ClientHandle {
239242
&self,
240243
message_name: impl Into<String> + Send,
241244
) -> RosLibRustResult<rosapi::MessageDetailsResponse> {
242-
self.call_service(
245+
self.call_service::<rosapi::MessageDetails>(
243246
"/rosapi/message_details",
244247
rosapi::MessageDetailsRequest {
245248
r#type: message_name.into(),
@@ -253,7 +256,7 @@ impl RosApi for ClientHandle {
253256
&self,
254257
topic: impl Into<String> + Send,
255258
) -> RosLibRustResult<rosapi::PublishersResponse> {
256-
self.call_service(
259+
self.call_service::<rosapi::Publishers>(
257260
"/rosapi/publishers",
258261
rosapi::PublishersRequest {
259262
topic: topic.into(),
@@ -267,7 +270,7 @@ impl RosApi for ClientHandle {
267270
&self,
268271
service: impl Into<String> + Send,
269272
) -> RosLibRustResult<rosapi::ServiceHostResponse> {
270-
self.call_service(
273+
self.call_service::<rosapi::ServiceHost>(
271274
"/rosapi/service_host",
272275
rosapi::ServiceHostRequest {
273276
service: service.into(),
@@ -281,7 +284,7 @@ impl RosApi for ClientHandle {
281284
&self,
282285
service_type: impl Into<String> + Send,
283286
) -> RosLibRustResult<rosapi::ServiceProvidersResponse> {
284-
self.call_service(
287+
self.call_service::<rosapi::ServiceProviders>(
285288
"/rosapi/service_providers",
286289
rosapi::ServiceProvidersRequest {
287290
service: service_type.into(),
@@ -295,7 +298,7 @@ impl RosApi for ClientHandle {
295298
&self,
296299
service_type: impl Into<String> + Send,
297300
) -> RosLibRustResult<rosapi::ServiceRequestDetailsResponse> {
298-
self.call_service(
301+
self.call_service::<rosapi::ServiceRequestDetails>(
299302
"/rosapi/service_request_details",
300303
rosapi::ServiceRequestDetailsRequest {
301304
r#type: service_type.into(),
@@ -309,7 +312,7 @@ impl RosApi for ClientHandle {
309312
&self,
310313
service_type: impl Into<String> + Send,
311314
) -> RosLibRustResult<rosapi::ServiceRequestDetailsResponse> {
312-
self.call_service(
315+
self.call_service::<rosapi::ServiceRequestDetails>(
313316
"/rosapi/service_response_details",
314317
rosapi::ServiceRequestDetailsRequest {
315318
r#type: service_type.into(),
@@ -323,7 +326,7 @@ impl RosApi for ClientHandle {
323326
&self,
324327
service_name: impl Into<String> + Send,
325328
) -> RosLibRustResult<rosapi::ServiceTypeResponse> {
326-
self.call_service(
329+
self.call_service::<rosapi::ServiceType>(
327330
"/rosapi/service_type",
328331
rosapi::ServiceTypeRequest {
329332
service: service_name.into(),
@@ -334,7 +337,7 @@ impl RosApi for ClientHandle {
334337

335338
/// Get the list of services active on the system
336339
async fn get_services(&self) -> RosLibRustResult<rosapi::ServicesResponse> {
337-
self.call_service("/rosapi/services", rosapi::ServicesRequest {})
340+
self.call_service::<rosapi::Services>("/rosapi/services", rosapi::ServicesRequest {})
338341
.await
339342
}
340343

0 commit comments

Comments
 (0)