Update readme, `tokio_raw_subscriber` example, cargo fmt.
This commit is contained in:
parent
3b42626dcb
commit
3518ac9215
|
|
@ -45,6 +45,7 @@ What works?
|
|||
Changelog
|
||||
--------------------
|
||||
#### [Unreleased]
|
||||
- Message (de-)serialization helpers <https://github.com/sequenceplanner/r2r/pull/74>.
|
||||
- Raw message subscribers. <https://github.com/sequenceplanner/r2r/pull/73>
|
||||
|
||||
#### [0.8.2] - 2023-12-11
|
||||
|
|
|
|||
|
|
@ -1,7 +1,7 @@
|
|||
use criterion::{criterion_group, criterion_main, Criterion};
|
||||
use r2r::*;
|
||||
use rand::Rng;
|
||||
use rand::thread_rng;
|
||||
use rand::Rng;
|
||||
|
||||
const NUM_ELEMENTS: usize = 10_000;
|
||||
const NUM_TIMES: usize = 1_000;
|
||||
|
|
@ -15,7 +15,7 @@ fn bench_ros_deserialization() {
|
|||
}
|
||||
let message = std_msgs::msg::Int32MultiArray {
|
||||
layout: std_msgs::msg::MultiArrayLayout::default(),
|
||||
data: numbers
|
||||
data: numbers,
|
||||
};
|
||||
|
||||
let bytes = message.to_serialized_bytes().unwrap();
|
||||
|
|
@ -34,7 +34,7 @@ fn bench_cdr_deserialization() {
|
|||
}
|
||||
let message = std_msgs::msg::Int32MultiArray {
|
||||
layout: std_msgs::msg::MultiArrayLayout::default(),
|
||||
data: numbers
|
||||
data: numbers,
|
||||
};
|
||||
|
||||
let bytes = message.to_serialized_bytes().unwrap();
|
||||
|
|
|
|||
|
|
@ -1,6 +1,7 @@
|
|||
use futures::future;
|
||||
use futures::stream::StreamExt;
|
||||
use r2r::QosProfile;
|
||||
use r2r::WrappedTypesupport;
|
||||
use serde::{Deserialize, Serialize};
|
||||
|
||||
#[tokio::main]
|
||||
|
|
@ -27,21 +28,28 @@ async fn main() -> Result<(), Box<dyn std::error::Error>> {
|
|||
}
|
||||
});
|
||||
|
||||
// Demonstrate that we can deserialize the raw bytes into this
|
||||
// rust struct using the cdr crate.
|
||||
sub.for_each(|msg| {
|
||||
println!("got raw bytes with size: {}. deserialize...", msg.len());
|
||||
|
||||
// We can use the ROS typesupport to perform deserialization.
|
||||
let ros_str = r2r::std_msgs::msg::String::from_serialized_bytes(&msg);
|
||||
|
||||
// Demonstrate that it is possible to also deserialize the raw
|
||||
// bytes into a rust struct using the `cdr` crate.
|
||||
#[derive(Deserialize, Serialize, PartialEq, Debug)]
|
||||
struct OurOwnStdString {
|
||||
data: String, // the field name can be anything...
|
||||
}
|
||||
sub.for_each(|msg| {
|
||||
println!("got raw bytes of length {}.", msg.len());
|
||||
let cdr_str = cdr::deserialize::<OurOwnStdString>(&msg);
|
||||
|
||||
if let Ok(data) = cdr::deserialize::<OurOwnStdString>(&msg) {
|
||||
println!("contents: {:?}", data);
|
||||
} else {
|
||||
println!("Warning: cannot deserialize data.");
|
||||
match (ros_str, cdr_str) {
|
||||
(Ok(s1), Ok(s2)) => {
|
||||
assert!(s1.data == s2.data);
|
||||
println!("... using ros: {:?}", s1);
|
||||
println!("... using cdr: {:?}", s2);
|
||||
}
|
||||
_ => println!("Error: cannot deserialize data."),
|
||||
}
|
||||
|
||||
future::ready(())
|
||||
})
|
||||
.await;
|
||||
|
|
|
|||
|
|
@ -1,15 +1,15 @@
|
|||
use crate::error::*;
|
||||
use r2r_msg_gen::*;
|
||||
use r2r_rcl::{
|
||||
rosidl_action_type_support_t, rosidl_message_type_support_t, rosidl_service_type_support_t,
|
||||
rcl_serialized_message_t,
|
||||
rcl_serialized_message_t, rosidl_action_type_support_t, rosidl_message_type_support_t,
|
||||
rosidl_service_type_support_t,
|
||||
};
|
||||
use serde::{Deserialize, Serialize};
|
||||
use std::boxed::Box;
|
||||
use std::cell::RefCell;
|
||||
use std::convert::TryInto;
|
||||
use std::fmt::Debug;
|
||||
use std::ops::{Deref, DerefMut};
|
||||
use std::cell::RefCell;
|
||||
|
||||
pub mod generated_msgs {
|
||||
#![allow(clippy::all)]
|
||||
|
|
@ -78,7 +78,10 @@ pub trait WrappedTypesupport:
|
|||
|
||||
self.copy_to_native(unsafe { msg.as_mut().expect("not null") });
|
||||
|
||||
let msg_buf: &mut rcl_serialized_message_t = &mut *msg_buf.as_ref().map_err(|err| Error::from_rcl_error(*err))?.borrow_mut();
|
||||
let msg_buf: &mut rcl_serialized_message_t = &mut *msg_buf
|
||||
.as_ref()
|
||||
.map_err(|err| Error::from_rcl_error(*err))?
|
||||
.borrow_mut();
|
||||
|
||||
let result = unsafe {
|
||||
rmw_serialize(
|
||||
|
|
@ -114,7 +117,7 @@ pub trait WrappedTypesupport:
|
|||
buffer_capacity: data.len(),
|
||||
|
||||
// Since its read only, this should never be used ..
|
||||
allocator: unsafe { rcutils_get_default_allocator() }
|
||||
allocator: unsafe { rcutils_get_default_allocator() },
|
||||
};
|
||||
|
||||
// Note From the docs of rmw_deserialize, its not clear whether this reuses
|
||||
|
|
@ -129,7 +132,7 @@ pub trait WrappedTypesupport:
|
|||
};
|
||||
|
||||
let ret_val = if result == RCL_RET_OK as i32 {
|
||||
Ok(Self::from_native(unsafe{ msg.as_ref().expect("not null") }))
|
||||
Ok(Self::from_native(unsafe { msg.as_ref().expect("not null") }))
|
||||
} else {
|
||||
Err(Error::from_rcl_error(result))
|
||||
};
|
||||
|
|
@ -137,7 +140,6 @@ pub trait WrappedTypesupport:
|
|||
Self::destroy_msg(msg);
|
||||
|
||||
ret_val
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
|
|
@ -704,7 +706,7 @@ mod tests {
|
|||
|
||||
#[test]
|
||||
fn test_serialization_fixed_size() {
|
||||
let message = std_msgs::msg::Int32 { data: 10};
|
||||
let message = std_msgs::msg::Int32 { data: 10 };
|
||||
|
||||
let bytes = message.to_serialized_bytes().unwrap();
|
||||
|
||||
|
|
@ -717,14 +719,13 @@ mod tests {
|
|||
|
||||
assert_eq!(bytes, bytes_2);
|
||||
assert_eq!(bytes, bytes_3);
|
||||
|
||||
}
|
||||
|
||||
#[test]
|
||||
fn test_serialization_dynamic_size() {
|
||||
let message = std_msgs::msg::Int32MultiArray {
|
||||
layout: std_msgs::msg::MultiArrayLayout::default(),
|
||||
data: vec![10, 20, 30]
|
||||
data: vec![10, 20, 30],
|
||||
};
|
||||
|
||||
let bytes = message.to_serialized_bytes().unwrap();
|
||||
|
|
@ -738,7 +739,6 @@ mod tests {
|
|||
|
||||
assert_eq!(bytes, bytes_2);
|
||||
assert_eq!(bytes, bytes_3);
|
||||
|
||||
}
|
||||
|
||||
#[cfg(r2r__test_msgs__msg__Defaults)]
|
||||
|
|
|
|||
|
|
@ -707,8 +707,7 @@ pub fn generate_rust_msg(module_: &str, prefix_: &str, name_: &str) -> proc_macr
|
|||
// (see https://github.com/rust-lang/rust/issues/115010)
|
||||
typ.lifetime = Some(syn::Lifetime::new("'static", proc_macro2::Span::call_site()));
|
||||
quote! { pub const #const_name: #typ = #value; }
|
||||
}
|
||||
else if let Ok(typ) = syn::parse_str::<Box<syn::Type>>(typ) {
|
||||
} else if let Ok(typ) = syn::parse_str::<Box<syn::Type>>(typ) {
|
||||
// Value
|
||||
quote! { pub const #const_name: #typ = #value; }
|
||||
} else {
|
||||
|
|
|
|||
Loading…
Reference in New Issue