diff --git a/rosidl_runtime_rs/Cargo.toml b/rosidl_runtime_rs/Cargo.toml new file mode 100644 index 0000000..4e48916 --- /dev/null +++ b/rosidl_runtime_rs/Cargo.toml @@ -0,0 +1,37 @@ +[package] +name = "rosidl_runtime_rs" +version = "0.4.1" +# This project is not military-sponsored, Jacob's employment contract just requires him to use this email address +authors = ["Esteve Fernandez ", "Nikolai Morin ", "Jacob Hassold "] +edition = "2021" +license = "Apache-2.0" +description = "Message generation code shared by Rust projects in ROS 2" + +[lib] +path = "src/lib.rs" + +# Please keep the list of dependencies alphabetically sorted, +# and also state why each dependency is needed. +[dependencies] +# Optional dependency for making it possible to convert messages to and from +# formats such as JSON, YAML, Pickle, etc. +serde = { version = "1", optional = true } + +[features] +default = [] +# This feature is solely for the purpose of being able to generate documetation without a ROS installation +# The only intended usage of this feature is for docs.rs builders to work, and is not intended to be used by end users +generate_docs = [] + +[dev-dependencies] +# Needed for writing property tests +quickcheck = "1" +# Needed for testing serde support +serde_json = "1" + +[build-dependencies] +# Needed for uploading documentation to docs.rs +cfg-if = "1.0.0" + +[package.metadata.docs.rs] +features = ["generate_docs"] diff --git a/rosidl_runtime_rs/README.md b/rosidl_runtime_rs/README.md new file mode 100644 index 0000000..e391a4c --- /dev/null +++ b/rosidl_runtime_rs/README.md @@ -0,0 +1,5 @@ +# Common types and traits for ROS 2 messages in Rust + +ROS 2 is a popular open source robotics framework, used in a variety of fields (self-driving cars, drones, humanoid robots, etc.). `rosidl_runtime_rs` is a library that is mainly used by generated code for ROS 2 messages. + +Please see the docs in the [`ros2_rust` repo](https://github.com/ros2-rust/ros2_rust). \ No newline at end of file diff --git a/rosidl_runtime_rs/build.rs b/rosidl_runtime_rs/build.rs new file mode 100644 index 0000000..fb98aeb --- /dev/null +++ b/rosidl_runtime_rs/build.rs @@ -0,0 +1,33 @@ +cfg_if::cfg_if! { + if #[cfg(not(feature="generate_docs"))] { + use std::env; + use std::path::Path; + + const AMENT_PREFIX_PATH: &str = "AMENT_PREFIX_PATH"; + + fn get_env_var_or_abort(env_var: &'static str) -> String { + if let Ok(value) = env::var(env_var) { + value + } else { + panic!( + "{} environment variable not set - please source ROS 2 installation first.", + env_var + ); + } + } + } +} + +fn main() { + #[cfg(not(feature = "generate_docs"))] + { + let ament_prefix_path_list = get_env_var_or_abort(AMENT_PREFIX_PATH); + for ament_prefix_path in ament_prefix_path_list.split(':') { + let library_path = Path::new(ament_prefix_path).join("lib"); + println!("cargo:rustc-link-search=native={}", library_path.display()); + } + } + + // Invalidate the built crate whenever this script changes + println!("cargo:rerun-if-changed=build.rs"); +} diff --git a/rosidl_runtime_rs/package.xml b/rosidl_runtime_rs/package.xml new file mode 100644 index 0000000..44e55f3 --- /dev/null +++ b/rosidl_runtime_rs/package.xml @@ -0,0 +1,20 @@ + + + + rosidl_runtime_rs + 0.4.1 + Message generation code shared by Rust projects in ROS 2 + + Jacob Hassold + Nikolai Morin + Apache License 2.0 + Jacob Hassold + Nikolai Morin + + rosidl_runtime_c + + ament_cargo + + diff --git a/rosidl_runtime_rs/src/lib.rs b/rosidl_runtime_rs/src/lib.rs new file mode 100644 index 0000000..7c5bad4 --- /dev/null +++ b/rosidl_runtime_rs/src/lib.rs @@ -0,0 +1,12 @@ +#![warn(missing_docs)] +//! Bindings to `rosidl_runtime_c` and related functionality for messages. + +#[macro_use] +mod sequence; +pub use sequence::{BoundedSequence, Sequence, SequenceExceedsBoundsError}; + +mod string; +pub use string::{BoundedString, BoundedWString, String, StringExceedsBoundsError, WString}; + +mod traits; +pub use traits::{Action, ActionImpl, Message, RmwMessage, SequenceAlloc, Service}; diff --git a/rosidl_runtime_rs/src/sequence.rs b/rosidl_runtime_rs/src/sequence.rs new file mode 100644 index 0000000..3d7cd58 --- /dev/null +++ b/rosidl_runtime_rs/src/sequence.rs @@ -0,0 +1,709 @@ +use std::{ + cmp::Ordering, + fmt::{self, Debug, Display}, + hash::{Hash, Hasher}, + iter::{Extend, FromIterator, FusedIterator}, + ops::{Deref, DerefMut}, +}; + +#[cfg(feature = "serde")] +mod serde; + +use crate::traits::SequenceAlloc; + +/// An unbounded sequence. +/// +/// The layout of a concrete `Sequence` is the same as the corresponding `Sequence` struct +/// generated by `rosidl_generator_c`. For instance, +/// `rosidl_runtime_rs::Sequence` is the same +/// as `std_msgs__msg__String__Sequence`. See the [`Message`](crate::Message) trait for background +/// information on this topic. +/// +/// +/// # Example +/// +/// ``` +/// # use rosidl_runtime_rs::{Sequence, seq}; +/// let mut list = Sequence::::new(3); +/// // Sequences deref to slices +/// assert_eq!(&list[..], &[0, 0, 0]); +/// list[0] = 3; +/// list[1] = 2; +/// list[2] = 1; +/// assert_eq!(&list[..], &[3, 2, 1]); +/// // Alternatively, use the seq! macro +/// list = seq![3, 2, 1]; +/// // The default sequence is empty +/// assert!(Sequence::::default().is_empty()); +/// ``` +#[repr(C)] +pub struct Sequence { + data: *mut T, + size: usize, + capacity: usize, +} + +/// A bounded sequence. +/// +/// The layout of a concrete `BoundedSequence` is the same as the corresponding `Sequence` +/// struct generated by `rosidl_generator_c`. For instance, +/// `rosidl_runtime_rs::BoundedSequence` +/// is the same as `std_msgs__msg__String__Sequence`, which also represents both bounded +/// sequences. See the [`Message`](crate::Message) trait for background information on this +/// topic. +/// +/// # Example +/// +/// ``` +/// # use rosidl_runtime_rs::{BoundedSequence, seq}; +/// let mut list = BoundedSequence::::new(3); +/// // BoundedSequences deref to slices +/// assert_eq!(&list[..], &[0, 0, 0]); +/// list[0] = 3; +/// list[1] = 2; +/// list[2] = 1; +/// assert_eq!(&list[..], &[3, 2, 1]); +/// // Alternatively, use the seq! macro with the length specifier +/// list = seq![5 # 3, 2, 1]; +/// // The default bounded sequence is empty +/// assert!(BoundedSequence::::default().is_empty()); +/// ``` +#[derive(Clone)] +#[repr(transparent)] +pub struct BoundedSequence { + inner: Sequence, +} + +/// Error type for [`BoundedSequence::try_new()`]. +#[derive(Debug)] +pub struct SequenceExceedsBoundsError { + /// The actual length the sequence would have after the operation. + pub len: usize, + /// The upper bound on the sequence length. + pub upper_bound: usize, +} + +/// A by-value iterator created by [`Sequence::into_iter()`] and [`BoundedSequence::into_iter()`]. +pub struct SequenceIterator { + seq: Sequence, + idx: usize, +} + +// ========================= impl for Sequence ========================= + +impl Clone for Sequence { + fn clone(&self) -> Self { + let mut seq = Self::default(); + if T::sequence_copy(self, &mut seq) { + seq + } else { + panic!("Cloning Sequence failed") + } + } +} + +impl Debug for Sequence { + fn fmt(&self, f: &mut fmt::Formatter<'_>) -> Result<(), fmt::Error> { + self.as_slice().fmt(f) + } +} + +impl Default for Sequence { + fn default() -> Self { + Self { + data: std::ptr::null_mut(), + size: 0, + capacity: 0, + } + } +} + +impl Deref for Sequence { + type Target = [T]; + fn deref(&self) -> &Self::Target { + self.as_slice() + } +} + +impl DerefMut for Sequence { + fn deref_mut(&mut self) -> &mut Self::Target { + self.as_mut_slice() + } +} + +impl Drop for Sequence { + fn drop(&mut self) { + T::sequence_fini(self) + } +} + +impl Eq for Sequence {} + +impl Extend for Sequence { + fn extend(&mut self, iter: I) + where + I: IntoIterator, + { + let it = iter.into_iter(); + // The index in the sequence where the next element will be stored + let mut cur_idx = self.size; + // Convenience closure for resizing self + let resize = |seq: &mut Self, new_size: usize| { + let old_seq = std::mem::replace(seq, Sequence::new(new_size)); + for (i, elem) in old_seq.into_iter().enumerate().take(new_size) { + seq[i] = elem; + } + }; + // First, when there is a size hint > 0 (lower bound), make room for + // that many elements. + let num_remaining = it.size_hint().0; + if num_remaining > 0 { + let new_size = self.size.saturating_add(num_remaining); + resize(self, new_size); + } + for item in it { + // If there is no more capacity for the next element, resize to the + // next power of two. + // + // A pedantic implementation would check for usize overflow here, but + // that is hardly possible on real hardware. Also, not the entire + // usize address space is usable for user space programs. + if cur_idx == self.size { + let new_size = (self.size + 1).next_power_of_two(); + resize(self, new_size); + } + self[cur_idx] = item; + cur_idx += 1; + } + // All items from the iterator are stored. Shrink the sequence to fit. + if cur_idx < self.size { + resize(self, cur_idx); + } + } +} + +impl From<&[T]> for Sequence { + fn from(slice: &[T]) -> Self { + let mut seq = Sequence::new(slice.len()); + seq.clone_from_slice(slice); + seq + } +} + +impl From> for Sequence { + fn from(v: Vec) -> Self { + Sequence::from_iter(v) + } +} + +impl FromIterator for Sequence { + fn from_iter(iter: I) -> Self + where + I: IntoIterator, + { + let mut seq = Sequence::new(0); + seq.extend(iter); + seq + } +} + +impl Hash for Sequence { + fn hash(&self, state: &mut H) { + self.as_slice().hash(state) + } +} + +impl IntoIterator for Sequence { + type Item = T; + type IntoIter = SequenceIterator; + fn into_iter(self) -> Self::IntoIter { + SequenceIterator { seq: self, idx: 0 } + } +} + +impl Ord for Sequence { + fn cmp(&self, other: &Self) -> Ordering { + self.as_slice().cmp(other.as_slice()) + } +} + +impl PartialEq for Sequence { + fn eq(&self, other: &Self) -> bool { + self.as_slice().eq(other.as_slice()) + } +} + +impl PartialOrd for Sequence { + fn partial_cmp(&self, other: &Self) -> Option { + self.as_slice().partial_cmp(other.as_slice()) + } +} + +// SAFETY: A sequence is a simple data structure, and therefore not thread-specific. +unsafe impl Send for Sequence {} +// SAFETY: A sequence does not have interior mutability, so it can be shared. +unsafe impl Sync for Sequence {} + +impl Sequence +where + T: SequenceAlloc, +{ + /// Creates a sequence of `len` elements with default values. + pub fn new(len: usize) -> Self { + let mut seq = Self::default(); + if !T::sequence_init(&mut seq, len) { + panic!("Sequence initialization failed"); + } + seq + } + + /// Extracts a slice containing the entire sequence. + /// + /// Equivalent to `&seq[..]`. + pub fn as_slice(&self) -> &[T] { + if self.data.is_null() { + &[] + } else { + // SAFETY: self.data is not null and points to self.size consecutive, + // initialized elements and isn't modified externally. + unsafe { std::slice::from_raw_parts(self.data, self.size) } + } + } + + /// Extracts a mutable slice containing the entire sequence. + /// + /// Equivalent to `&mut seq[..]`. + pub fn as_mut_slice(&mut self) -> &mut [T] { + if self.data.is_null() { + &mut [] + } else { + // SAFETY: self.data is not null and points to self.size consecutive, + // initialized elements and isn't modified externally. + unsafe { std::slice::from_raw_parts_mut(self.data, self.size) } + } + } +} + +// ========================= impl for BoundedSequence ========================= + +impl Debug for BoundedSequence { + fn fmt(&self, f: &mut fmt::Formatter<'_>) -> Result<(), fmt::Error> { + self.as_slice().fmt(f) + } +} + +impl Default for BoundedSequence { + fn default() -> Self { + Self { + inner: Sequence { + data: std::ptr::null_mut(), + size: 0, + capacity: 0, + }, + } + } +} + +impl Deref for BoundedSequence { + type Target = [T]; + fn deref(&self) -> &Self::Target { + self.inner.deref() + } +} + +impl DerefMut for BoundedSequence { + fn deref_mut(&mut self) -> &mut Self::Target { + self.inner.deref_mut() + } +} + +impl Drop for BoundedSequence { + fn drop(&mut self) { + T::sequence_fini(&mut self.inner) + } +} + +impl Eq for BoundedSequence {} + +impl Extend for BoundedSequence { + fn extend(&mut self, iter: I) + where + I: IntoIterator, + { + self.inner + .extend(iter.into_iter().take(N - self.inner.size)); + } +} + +impl TryFrom<&[T]> for BoundedSequence { + type Error = SequenceExceedsBoundsError; + fn try_from(slice: &[T]) -> Result { + let mut seq = BoundedSequence::try_new(slice.len())?; + seq.clone_from_slice(slice); + Ok(seq) + } +} + +impl TryFrom> for BoundedSequence { + type Error = SequenceExceedsBoundsError; + fn try_from(v: Vec) -> Result { + if v.len() > N { + Err(SequenceExceedsBoundsError { + len: v.len(), + upper_bound: N, + }) + } else { + Ok(BoundedSequence::from_iter(v)) + } + } +} + +impl FromIterator for BoundedSequence { + fn from_iter(iter: I) -> Self + where + I: IntoIterator, + { + let mut seq = BoundedSequence::new(0); + seq.extend(iter); + seq + } +} + +impl Hash for BoundedSequence { + fn hash(&self, state: &mut H) { + self.as_slice().hash(state) + } +} + +impl IntoIterator for BoundedSequence { + type Item = T; + type IntoIter = SequenceIterator; + fn into_iter(mut self) -> Self::IntoIter { + let seq = std::mem::replace( + &mut self.inner, + Sequence { + data: std::ptr::null_mut(), + size: 0, + capacity: 0, + }, + ); + SequenceIterator { seq, idx: 0 } + } +} + +impl Ord for BoundedSequence { + fn cmp(&self, other: &Self) -> Ordering { + self.as_slice().cmp(other.as_slice()) + } +} + +impl PartialEq for BoundedSequence { + fn eq(&self, other: &Self) -> bool { + self.as_slice().eq(other.as_slice()) + } +} + +impl PartialOrd for BoundedSequence { + fn partial_cmp(&self, other: &Self) -> Option { + self.as_slice().partial_cmp(other.as_slice()) + } +} + +impl BoundedSequence +where + T: SequenceAlloc, +{ + /// Creates a sequence of `len` elements with default values. + /// + /// If `len` is greater than `N`, this function panics. + pub fn new(len: usize) -> Self { + Self::try_new(len).unwrap() + } + + /// Attempts to create a sequence of `len` elements with default values. + /// + /// If `len` is greater than `N`, this function returns an error. + pub fn try_new(len: usize) -> Result { + if len > N { + return Err(SequenceExceedsBoundsError { + len, + upper_bound: N, + }); + } + let mut seq = Self::default(); + if !T::sequence_init(&mut seq.inner, len) { + panic!("BoundedSequence initialization failed"); + } + Ok(seq) + } + + /// Extracts a slice containing the entire sequence. + /// + /// Equivalent to `&seq[..]`. + pub fn as_slice(&self) -> &[T] { + self.inner.as_slice() + } + + /// Extracts a mutable slice containing the entire sequence. + /// + /// Equivalent to `&mut seq[..]`. + pub fn as_mut_slice(&mut self) -> &mut [T] { + self.inner.as_mut_slice() + } +} + +// ========================= impl for SequenceIterator ========================= + +impl Iterator for SequenceIterator { + type Item = T; + fn next(&mut self) -> Option { + if self.idx >= self.seq.size { + return None; + } + // SAFETY: data + idx is in bounds and points to a valid value + let elem = unsafe { + let ptr = self.seq.data.add(self.idx); + let elem = ptr.read(); + // Need to make sure that dropping the sequence later will not fini() the elements + ptr.write(std::mem::zeroed::()); + elem + }; + self.idx += 1; + Some(elem) + } + + fn size_hint(&self) -> (usize, Option) { + let len = (self.seq.size + 1) - self.idx; + (len, Some(len)) + } +} + +impl ExactSizeIterator for SequenceIterator { + fn len(&self) -> usize { + (self.seq.size + 1) - self.idx + } +} + +impl FusedIterator for SequenceIterator {} + +// ========================= impl for StringExceedsBoundsError ========================= + +impl Display for SequenceExceedsBoundsError { + fn fmt(&self, f: &mut fmt::Formatter<'_>) -> Result<(), fmt::Error> { + write!( + f, + "BoundedSequence with upper bound {} initialized with len {}", + self.upper_bound, self.len + ) + } +} + +impl std::error::Error for SequenceExceedsBoundsError {} + +macro_rules! impl_sequence_alloc_for_primitive_type { + ($rust_type:ty, $init_func:ident, $fini_func:ident, $copy_func:ident) => { + #[link(name = "rosidl_runtime_c")] + extern "C" { + fn $init_func(seq: *mut Sequence<$rust_type>, size: usize) -> bool; + fn $fini_func(seq: *mut Sequence<$rust_type>); + fn $copy_func( + in_seq: *const Sequence<$rust_type>, + out_seq: *mut Sequence<$rust_type>, + ) -> bool; + } + + impl SequenceAlloc for $rust_type { + fn sequence_init(seq: &mut Sequence, size: usize) -> bool { + // SAFETY: There are no special preconditions to the sequence_init function. + unsafe { + // This allocates space and sets seq.size and seq.capacity to size + let ret = $init_func(seq as *mut _, size); + if !seq.data.is_null() { + // Zero memory, since it will be uninitialized if there is no default value + std::ptr::write_bytes(seq.data, 0u8, size); + } + ret + } + } + fn sequence_fini(seq: &mut Sequence) { + // SAFETY: There are no special preconditions to the sequence_fini function. + unsafe { $fini_func(seq as *mut _) } + } + fn sequence_copy(in_seq: &Sequence, out_seq: &mut Sequence) -> bool { + // SAFETY: There are no special preconditions to the sequence_copy function. + unsafe { $copy_func(in_seq as *const _, out_seq as *mut _) } + } + } + }; +} + +// Primitives are not messages themselves, but there can be sequences of them. +// +// See https://github.com/ros2/rosidl/blob/master/rosidl_runtime_c/include/rosidl_runtime_c/primitives_sequence.h +// Long double isn't available in Rust, so it is skipped. +impl_sequence_alloc_for_primitive_type!( + f32, + rosidl_runtime_c__float__Sequence__init, + rosidl_runtime_c__float__Sequence__fini, + rosidl_runtime_c__float__Sequence__copy +); +impl_sequence_alloc_for_primitive_type!( + f64, + rosidl_runtime_c__double__Sequence__init, + rosidl_runtime_c__double__Sequence__fini, + rosidl_runtime_c__double__Sequence__copy +); +impl_sequence_alloc_for_primitive_type!( + bool, + rosidl_runtime_c__boolean__Sequence__init, + rosidl_runtime_c__boolean__Sequence__fini, + rosidl_runtime_c__boolean__Sequence__copy +); +impl_sequence_alloc_for_primitive_type!( + u8, + rosidl_runtime_c__uint8__Sequence__init, + rosidl_runtime_c__uint8__Sequence__fini, + rosidl_runtime_c__uint8__Sequence__copy +); +impl_sequence_alloc_for_primitive_type!( + i8, + rosidl_runtime_c__int8__Sequence__init, + rosidl_runtime_c__int8__Sequence__fini, + rosidl_runtime_c__int8__Sequence__copy +); +impl_sequence_alloc_for_primitive_type!( + u16, + rosidl_runtime_c__uint16__Sequence__init, + rosidl_runtime_c__uint16__Sequence__fini, + rosidl_runtime_c__uint16__Sequence__copy +); +impl_sequence_alloc_for_primitive_type!( + i16, + rosidl_runtime_c__int16__Sequence__init, + rosidl_runtime_c__int16__Sequence__fini, + rosidl_runtime_c__int16__Sequence__copy +); +impl_sequence_alloc_for_primitive_type!( + u32, + rosidl_runtime_c__uint32__Sequence__init, + rosidl_runtime_c__uint32__Sequence__fini, + rosidl_runtime_c__uint32__Sequence__copy +); +impl_sequence_alloc_for_primitive_type!( + i32, + rosidl_runtime_c__int32__Sequence__init, + rosidl_runtime_c__int32__Sequence__fini, + rosidl_runtime_c__int32__Sequence__copy +); +impl_sequence_alloc_for_primitive_type!( + u64, + rosidl_runtime_c__uint64__Sequence__init, + rosidl_runtime_c__uint64__Sequence__fini, + rosidl_runtime_c__uint64__Sequence__copy +); +impl_sequence_alloc_for_primitive_type!( + i64, + rosidl_runtime_c__int64__Sequence__init, + rosidl_runtime_c__int64__Sequence__fini, + rosidl_runtime_c__int64__Sequence__copy +); + +/// Creates a sequence, similar to the `vec!` macro. +/// +/// It's possible to create both [`Sequence`]s and [`BoundedSequence`]s. +/// Unbounded sequences are created by a comma-separated list of values. +/// Bounded sequences are created by additionally specifying the maximum capacity (the `N` type +/// parameter) in the beginning, followed by a `#`. +/// +/// # Example +/// ``` +/// # use rosidl_runtime_rs::{BoundedSequence, Sequence, seq}; +/// let unbounded: Sequence = seq![1, 2, 3]; +/// let bounded: BoundedSequence = seq![5 # 1, 2, 3]; +/// assert_eq!(&unbounded[..], &bounded[..]) +/// ``` +#[macro_export] +macro_rules! seq { + [$( $elem:expr ),*] => { + { + let len = seq!(@count_tts $($elem),*); + let mut seq = Sequence::new(len); + let mut i = 0; + $( + seq[i] = $elem; + #[allow(unused_assignments)] + { i += 1; } + )* + seq + } + }; + [$len:literal # $( $elem:expr ),*] => { + { + let len = seq!(@count_tts $($elem),*); + let mut seq = BoundedSequence::<_, $len>::new(len); + let mut i = 0; + $( + seq[i] = $elem; + #[allow(unused_assignments)] + { i += 1; } + )* + seq + } + }; + // https://danielkeep.github.io/tlborm/book/blk-counting.html + (@replace_expr ($_t:expr, $sub:expr)) => {$sub}; + (@count_tts $($e:expr),*) => {<[()]>::len(&[$(seq!(@replace_expr ($e, ()))),*])}; +} + +#[cfg(test)] +mod tests { + use quickcheck::{quickcheck, Arbitrary, Gen}; + + use super::*; + + impl Arbitrary for Sequence { + fn arbitrary(g: &mut Gen) -> Self { + Vec::arbitrary(g).into() + } + } + + impl Arbitrary for BoundedSequence { + fn arbitrary(g: &mut Gen) -> Self { + let len = u8::arbitrary(g); + (0..len).map(|_| T::arbitrary(g)).collect() + } + } + + #[test] + fn test_empty_sequence() { + assert!(Sequence::::default().is_empty()); + assert!(BoundedSequence::::default().is_empty()); + } + + quickcheck! { + fn test_extend(xs: Vec, ys: Vec) -> bool { + let mut xs_seq = Sequence::new(xs.len()); + xs_seq.copy_from_slice(&xs); + xs_seq.extend(ys.clone()); + if xs_seq.len() != xs.len() + ys.len() { + return false; + } + if xs_seq[..xs.len()] != xs[..] { + return false; + } + if xs_seq[xs.len()..] != ys[..] { + return false; + } + true + } + } + + quickcheck! { + fn test_iteration(xs: Vec) -> bool { + let mut seq_1 = Sequence::new(xs.len()); + seq_1.copy_from_slice(&xs); + let seq_2 = seq_1.clone().into_iter().collect(); + seq_1 == seq_2 + } + } +} diff --git a/rosidl_runtime_rs/src/sequence/serde.rs b/rosidl_runtime_rs/src/sequence/serde.rs new file mode 100644 index 0000000..f3af605 --- /dev/null +++ b/rosidl_runtime_rs/src/sequence/serde.rs @@ -0,0 +1,71 @@ +use serde::{de::Error, ser::SerializeSeq, Deserialize, Deserializer, Serialize, Serializer}; + +use super::{BoundedSequence, Sequence}; +use crate::traits::SequenceAlloc; + +impl<'de, T: Deserialize<'de> + SequenceAlloc> Deserialize<'de> for Sequence { + fn deserialize(deserializer: D) -> Result + where + D: Deserializer<'de>, + { + let v: Vec<_> = Deserialize::deserialize(deserializer)?; + Ok(Self::from(v)) + } +} + +impl Serialize for Sequence { + fn serialize(&self, serializer: S) -> Result + where + S: Serializer, + { + let mut seq = serializer.serialize_seq(Some(self.len()))?; + for element in self.iter() { + seq.serialize_element(element)?; + } + seq.end() + } +} + +impl<'de, T: Deserialize<'de> + SequenceAlloc, const N: usize> Deserialize<'de> + for BoundedSequence +{ + fn deserialize(deserializer: D) -> Result + where + D: Deserializer<'de>, + { + let v: Vec<_> = Deserialize::deserialize(deserializer)?; + Self::try_from(v).map_err(D::Error::custom) + } +} + +impl Serialize for BoundedSequence { + fn serialize(&self, serializer: S) -> Result + where + S: Serializer, + { + self.inner.serialize(serializer) + } +} + +#[cfg(test)] +mod tests { + use quickcheck::quickcheck; + + use crate::{BoundedSequence, Sequence}; + + quickcheck! { + fn test_json_roundtrip_sequence(xs: Sequence) -> bool { + let value = serde_json::to_value(xs.clone()).unwrap(); + let recovered = serde_json::from_value(value).unwrap(); + xs == recovered + } + } + + quickcheck! { + fn test_json_roundtrip_bounded_sequence(xs: BoundedSequence) -> bool { + let value = serde_json::to_value(xs.clone()).unwrap(); + let recovered = serde_json::from_value(value).unwrap(); + xs == recovered + } + } +} diff --git a/rosidl_runtime_rs/src/string.rs b/rosidl_runtime_rs/src/string.rs new file mode 100644 index 0000000..9f0251c --- /dev/null +++ b/rosidl_runtime_rs/src/string.rs @@ -0,0 +1,600 @@ +use std::{ + borrow::Borrow, + cmp::Ordering, + ffi::CStr, + fmt::{self, Debug, Display}, + hash::{Hash, Hasher}, + ops::{Deref, DerefMut}, +}; + +#[cfg(feature = "serde")] +mod serde; + +use crate::{sequence::Sequence, traits::SequenceAlloc}; + +/// A zero-terminated UTF-8 string. +/// +/// The layout of this type is the same as `rosidl_runtime_c__String`. See the +/// [`Message`](crate::Message) trait for background information on this topic. +/// +/// +/// # Example +/// +/// ``` +/// # use rosidl_runtime_rs::String; +/// let mut s = String::from("Grüß Gott!"); +/// // Conversion back to a std::string::String is done with the ToString trait from the standard +/// // library. +/// assert_eq!(&s.to_string(), "Grüß Gott!"); +/// ``` +#[repr(C)] +pub struct String { + /// Dynamic memory in this type is allocated and deallocated by C, but this is a detail that is managed by + /// the relevant functions and trait impls. + data: *mut std::os::raw::c_char, + size: usize, + capacity: usize, +} + +/// A zero-terminated UTF-16 string. +/// +/// The layout of this type is the same as `rosidl_runtime_c__U16String`. See the +/// [`Message`](crate::Message) trait for background information on this topic. +/// +/// # Example +/// +/// ``` +/// # use rosidl_runtime_rs::WString; +/// let mut s = WString::from("Grüß Gott!"); +/// // Conversion back to a std::string::String is done with the ToString trait from the standard +/// // library. +/// assert_eq!(&s.to_string(), "Grüß Gott!"); +/// ``` +#[repr(C)] +pub struct WString { + data: *mut u16, + size: usize, + capacity: usize, +} + +/// A zero-terminated UTF-8 string with a length limit. +/// +/// The same as [`String`], but it cannot be constructed from a string that is too large. +/// The length is measured as the number of bytes. +/// +/// # Example +/// +/// ``` +/// # use rosidl_runtime_rs::BoundedString; +/// let mut maybe_str = BoundedString::<3>::try_from("noo!"); +/// assert!(maybe_str.is_err()); +/// maybe_str = BoundedString::<3>::try_from("ok!"); +/// assert!(maybe_str.is_ok()); +/// let bounded_str = maybe_str.unwrap(); +/// assert_eq!(&bounded_str.to_string(), "ok!"); +/// ``` +#[derive(Clone, Default, Hash, PartialEq, Eq, PartialOrd, Ord)] +#[repr(transparent)] +pub struct BoundedString { + inner: String, +} + +/// A zero-terminated UTF-16 string with a length limit. +/// +/// The same as [`WString`], but it cannot be constructed from a string that is too large. +/// The length is measured as the number of 16-bit words. +/// +/// # Example +/// +/// ``` +/// # use rosidl_runtime_rs::BoundedWString; +/// let mut maybe_wstr = BoundedWString::<3>::try_from("noo!"); +/// assert!(maybe_wstr.is_err()); +/// maybe_wstr = BoundedWString::<3>::try_from("ok!"); +/// assert!(maybe_wstr.is_ok()); +/// let bounded_wstr = maybe_wstr.unwrap(); +/// assert_eq!(&bounded_wstr.to_string(), "ok!"); +/// ``` +#[derive(Clone, Default, Hash, PartialEq, Eq, PartialOrd, Ord)] +#[repr(transparent)] +pub struct BoundedWString { + inner: WString, +} + +/// Error type for [`BoundedString::try_from()`] and [`BoundedWString::try_from()`]. +#[derive(Debug)] +pub struct StringExceedsBoundsError { + /// The actual length the string would have after the operation. + pub len: usize, + /// The upper bound on the string length. + pub upper_bound: usize, +} + +// ========================= impls for String and WString ========================= + +// There is a lot of redundancy between String and WString, which this macro aims to reduce. +macro_rules! string_impl { + ($string:ty, $char_type:ty, $unsigned_char_type:ty, $string_conversion_func:ident, $init:ident, $fini:ident, $assignn:ident, $sequence_init:ident, $sequence_fini:ident, $sequence_copy:ident) => { + #[link(name = "rosidl_runtime_c")] + extern "C" { + fn $init(s: *mut $string) -> bool; + fn $fini(s: *mut $string); + fn $assignn(s: *mut $string, value: *const $char_type, n: usize) -> bool; + fn $sequence_init(seq: *mut Sequence<$string>, size: usize) -> bool; + fn $sequence_fini(seq: *mut Sequence<$string>); + fn $sequence_copy( + in_seq: *const Sequence<$string>, + out_seq: *mut Sequence<$string>, + ) -> bool; + } + + impl Clone for $string { + fn clone(&self) -> Self { + let mut msg = Self::default(); + // SAFETY: This is doing the same thing as rosidl_runtime_c__String__copy. + if !unsafe { $assignn(&mut msg as *mut _, self.data as *const _, self.size) } { + panic!("$assignn failed"); + } + msg + } + } + + impl Debug for $string { + fn fmt(&self, f: &mut fmt::Formatter<'_>) -> Result<(), fmt::Error> { + Debug::fmt(&self.to_string(), f) + } + } + + impl Default for $string { + fn default() -> Self { + let mut msg = Self { + data: std::ptr::null_mut(), + size: 0, + capacity: 0, + }; + // SAFETY: Passing in a zeroed string is safe. + if !unsafe { $init(&mut msg as *mut _) } { + panic!("$init failed"); + } + msg + } + } + + // It's not guaranteed that there are no interior null bytes, hence no Deref to CStr. + // This does not include the null byte at the end! + impl Deref for $string { + type Target = [$char_type]; + fn deref(&self) -> &Self::Target { + // SAFETY: self.data points to self.size consecutive, initialized elements and + // isn't modified externally. + unsafe { std::slice::from_raw_parts(self.data, self.size) } + } + } + + impl DerefMut for $string { + fn deref_mut(&mut self) -> &mut Self::Target { + // SAFETY: self.data points to self.size consecutive, initialized elements and + // isn't modified externally. + unsafe { std::slice::from_raw_parts_mut(self.data, self.size) } + } + } + + impl Display for $string { + fn fmt(&self, f: &mut fmt::Formatter<'_>) -> Result<(), fmt::Error> { + // SAFETY: Same as deref, but with an additional cast to the unsigned type. + // See also https://users.rust-lang.org/t/how-to-convert-i8-to-u8/16308/11 + let u8_slice = unsafe { + std::slice::from_raw_parts(self.data as *mut $unsigned_char_type, self.size) + }; + let converted = std::string::String::$string_conversion_func(u8_slice); + Display::fmt(&converted, f) + } + } + + impl Drop for $string { + fn drop(&mut self) { + // SAFETY: There are no special preconditions to the fini function. + unsafe { + $fini(self as *mut _); + } + } + } + + impl Eq for $string {} + + impl Extend for $string { + fn extend>(&mut self, iter: I) { + let mut s = self.to_string(); + s.extend(iter); + *self = Self::from(s.as_str()); + } + } + + impl<'a> Extend<&'a char> for $string { + fn extend>(&mut self, iter: I) { + self.extend(iter.into_iter().cloned()); + } + } + + impl FromIterator for $string { + fn from_iter>(iter: I) -> Self { + let mut buf = <$string>::default(); + buf.extend(iter); + buf + } + } + + impl<'a> FromIterator<&'a char> for $string { + fn from_iter>(iter: I) -> Self { + let mut buf = <$string>::default(); + buf.extend(iter); + buf + } + } + + impl Hash for $string { + fn hash(&self, state: &mut H) { + self.deref().hash(state) + } + } + + impl Ord for $string { + fn cmp(&self, other: &Self) -> Ordering { + self.deref().cmp(other.deref()) + } + } + + impl PartialEq for $string { + fn eq(&self, other: &Self) -> bool { + self.deref().eq(other.deref()) + } + } + + impl PartialOrd for $string { + fn partial_cmp(&self, other: &Self) -> Option { + Some(self.cmp(other)) + } + } + + // SAFETY: A string is a simple data structure, and therefore not thread-specific. + unsafe impl Send for $string {} + // SAFETY: A string does not have interior mutability, so it can be shared. + unsafe impl Sync for $string {} + + impl SequenceAlloc for $string { + fn sequence_init(seq: &mut Sequence, size: usize) -> bool { + // SAFETY: There are no special preconditions to the sequence_init function. + unsafe { $sequence_init(seq as *mut _, size) } + } + fn sequence_fini(seq: &mut Sequence) { + // SAFETY: There are no special preconditions to the sequence_fini function. + unsafe { $sequence_fini(seq as *mut _) } + } + fn sequence_copy(in_seq: &Sequence, out_seq: &mut Sequence) -> bool { + // SAFETY: There are no special preconditions to the sequence_copy function. + unsafe { $sequence_copy(in_seq as *const _, out_seq as *mut _) } + } + } + }; +} + +string_impl!( + String, + std::os::raw::c_char, + u8, + from_utf8_lossy, + rosidl_runtime_c__String__init, + rosidl_runtime_c__String__fini, + rosidl_runtime_c__String__assignn, + rosidl_runtime_c__String__Sequence__init, + rosidl_runtime_c__String__Sequence__fini, + rosidl_runtime_c__String__Sequence__copy +); +string_impl!( + WString, + u16, + u16, + from_utf16_lossy, + rosidl_runtime_c__U16String__init, + rosidl_runtime_c__U16String__fini, + rosidl_runtime_c__U16String__assignn, + rosidl_runtime_c__U16String__Sequence__init, + rosidl_runtime_c__U16String__Sequence__fini, + rosidl_runtime_c__U16String__Sequence__copy +); + +impl From for String +where + T: Borrow, +{ + fn from(s: T) -> Self { + let mut msg = Self { + data: std::ptr::null_mut(), + size: 0, + capacity: 0, + }; + let s = s.borrow(); + // SAFETY: It's okay to pass a non-zero-terminated string here since assignn uses the + // specified length and will append the 0 byte to the dest string itself. + if !unsafe { + rosidl_runtime_c__String__assignn(&mut msg as *mut _, s.as_ptr() as *const _, s.len()) + } { + panic!("rosidl_runtime_c__String__assignn failed"); + } + msg + } +} + +impl String { + /// Creates a CStr from this String. + /// + /// This scales with the length of the string but does not create copy of the string. + /// See also [`CStr::from_ptr()`]. + pub fn to_cstr(&self) -> &CStr { + // SAFETY: self.data is a valid pointer and won't change. + // Also, the lifetime of the CStr is the same as self, which is correct. + unsafe { CStr::from_ptr(self.data as *const _) } + } +} + +impl From<&str> for WString { + fn from(s: &str) -> Self { + let mut msg = Self { + data: std::ptr::null_mut(), + size: 0, + capacity: 0, + }; + let buf: Vec = s.encode_utf16().collect(); + // SAFETY: It's okay to pass a non-zero-terminated string here since assignn uses the + // specified length and will append the 0 to the dest string itself. + if !unsafe { + rosidl_runtime_c__U16String__assignn( + &mut msg as *mut _, + buf.as_ptr() as *const _, + buf.len(), + ) + } { + panic!("rosidl_runtime_c__U16String__assignn failed"); + } + msg + } +} + +// ========================= impl for BoundedString ========================= + +impl Debug for BoundedString { + fn fmt(&self, f: &mut fmt::Formatter<'_>) -> Result<(), fmt::Error> { + Debug::fmt(&self.inner, f) + } +} + +impl Deref for BoundedString { + type Target = [std::os::raw::c_char]; + fn deref(&self) -> &Self::Target { + self.inner.deref() + } +} + +impl DerefMut for BoundedString { + fn deref_mut(&mut self) -> &mut Self::Target { + self.inner.deref_mut() + } +} + +impl Display for BoundedString { + fn fmt(&self, f: &mut fmt::Formatter<'_>) -> Result<(), fmt::Error> { + Display::fmt(&self.inner, f) + } +} + +impl SequenceAlloc for BoundedString { + fn sequence_init(seq: &mut Sequence, size: usize) -> bool { + // SAFETY: There are no special preconditions to the rosidl_runtime_c__String__Sequence__init function. + unsafe { + rosidl_runtime_c__String__Sequence__init(seq as *mut Sequence as *mut _, size) + } + } + fn sequence_fini(seq: &mut Sequence) { + // SAFETY: There are no special preconditions to the rosidl_runtime_c__String__Sequence__fini function. + unsafe { rosidl_runtime_c__String__Sequence__fini(seq as *mut Sequence as *mut _) } + } + fn sequence_copy(in_seq: &Sequence, out_seq: &mut Sequence) -> bool { + // SAFETY: Transmute of a transparent type to the inner type is fine + unsafe { + ::sequence_copy( + std::mem::transmute::<&Sequence, &Sequence>(in_seq), + std::mem::transmute::<&mut Sequence, &mut Sequence>(out_seq), + ) + } + } +} + +impl TryFrom<&str> for BoundedString { + type Error = StringExceedsBoundsError; + fn try_from(s: &str) -> Result { + let length = s.len(); + if length <= N { + Ok(Self { + inner: String::from(s), + }) + } else { + Err(StringExceedsBoundsError { + len: length, + upper_bound: N, + }) + } + } +} + +// ========================= impl for BoundedWString ========================= + +impl Debug for BoundedWString { + fn fmt(&self, f: &mut fmt::Formatter<'_>) -> Result<(), fmt::Error> { + Debug::fmt(&self.inner, f) + } +} + +impl Deref for BoundedWString { + type Target = [u16]; + fn deref(&self) -> &Self::Target { + self.inner.deref() + } +} + +impl DerefMut for BoundedWString { + fn deref_mut(&mut self) -> &mut Self::Target { + self.inner.deref_mut() + } +} + +impl Display for BoundedWString { + fn fmt(&self, f: &mut fmt::Formatter<'_>) -> Result<(), fmt::Error> { + Display::fmt(&self.inner, f) + } +} + +impl SequenceAlloc for BoundedWString { + fn sequence_init(seq: &mut Sequence, size: usize) -> bool { + // SAFETY: There are no special preconditions to the rosidl_runtime_c__U16String__Sequence__init function. + unsafe { + rosidl_runtime_c__U16String__Sequence__init(seq as *mut Sequence as *mut _, size) + } + } + fn sequence_fini(seq: &mut Sequence) { + // SAFETY: There are no special preconditions to the rosidl_runtime_c__U16String__Sequence__fini function. + unsafe { rosidl_runtime_c__U16String__Sequence__fini(seq as *mut Sequence as *mut _) } + } + fn sequence_copy(in_seq: &Sequence, out_seq: &mut Sequence) -> bool { + // SAFETY: Transmute of a transparent type to the inner type is fine + unsafe { + ::sequence_copy( + std::mem::transmute::<&Sequence, &Sequence>(in_seq), + std::mem::transmute::<&mut Sequence, &mut Sequence>(out_seq), + ) + } + } +} + +impl TryFrom<&str> for BoundedWString { + type Error = StringExceedsBoundsError; + fn try_from(s: &str) -> Result { + let inner = WString::from(s); + if inner.size <= N { + Ok(Self { inner }) + } else { + Err(StringExceedsBoundsError { + len: inner.size, + upper_bound: N, + }) + } + } +} + +// ========================= impl for StringExceedsBoundsError ========================= + +impl Display for StringExceedsBoundsError { + fn fmt(&self, f: &mut fmt::Formatter<'_>) -> Result<(), fmt::Error> { + write!( + f, + "BoundedString with upper bound {} initialized with len {}", + self.upper_bound, self.len + ) + } +} + +impl std::error::Error for StringExceedsBoundsError {} + +#[cfg(test)] +mod tests { + use quickcheck::{Arbitrary, Gen}; + + use super::*; + + impl Arbitrary for String { + fn arbitrary(g: &mut Gen) -> Self { + std::string::String::arbitrary(g).as_str().into() + } + } + + impl Arbitrary for WString { + fn arbitrary(g: &mut Gen) -> Self { + std::string::String::arbitrary(g).as_str().into() + } + } + + impl Arbitrary for BoundedString<256> { + fn arbitrary(g: &mut Gen) -> Self { + let len = u8::arbitrary(g); + let s: std::string::String = (0..len).map(|_| char::arbitrary(g)).collect(); + s.as_str().try_into().unwrap() + } + } + + impl Arbitrary for BoundedWString<256> { + fn arbitrary(g: &mut Gen) -> Self { + let len = u8::arbitrary(g); + let s: std::string::String = (0..len).map(|_| char::arbitrary(g)).collect(); + s.as_str().try_into().unwrap() + } + } + + #[test] + fn string_from_char_iterator() { + // Base char case + let expected = String::from("abc"); + let actual = "abc".chars().collect::(); + + assert_eq!(expected, actual); + + // Empty case + let expected = String::from(""); + let actual = "".chars().collect::(); + + assert_eq!(expected, actual); + + // Non-ascii char case + let expected = String::from("Grüß Gott! 𝕊"); + let actual = "Grüß Gott! 𝕊".chars().collect::(); + + assert_eq!(expected, actual); + } + + #[test] + fn extend_string_with_char_iterator() { + let expected = WString::from("abcdef"); + let mut actual = WString::from("abc"); + actual.extend("def".chars()); + + assert_eq!(expected, actual); + } + + #[test] + fn wstring_from_char_iterator() { + // Base char case + let expected = WString::from("abc"); + let actual = "abc".chars().collect::(); + + assert_eq!(expected, actual); + + // Empty case + let expected = WString::from(""); + let actual = "".chars().collect::(); + + assert_eq!(expected, actual); + + // Non-ascii char case + let expected = WString::from("Grüß Gott! 𝕊"); + let actual = "Grüß Gott! 𝕊".chars().collect::(); + + assert_eq!(expected, actual); + } + + #[test] + fn extend_wstring_with_char_iterator() { + let expected = WString::from("abcdef"); + let mut actual = WString::from("abc"); + actual.extend("def".chars()); + + assert_eq!(expected, actual); + } +} diff --git a/rosidl_runtime_rs/src/string/serde.rs b/rosidl_runtime_rs/src/string/serde.rs new file mode 100644 index 0000000..0ded3fd --- /dev/null +++ b/rosidl_runtime_rs/src/string/serde.rs @@ -0,0 +1,209 @@ +use std::fmt; + +use serde::{ + de::{Error, SeqAccess, Visitor}, + Deserialize, Deserializer, Serialize, Serializer, +}; + +use super::{ + rosidl_runtime_c__String__assignn, rosidl_runtime_c__U16String__assignn, BoundedString, + BoundedWString, String, WString, +}; + +struct StringVisitor; +struct WStringVisitor; + +impl Visitor<'_> for StringVisitor { + type Value = String; + + fn expecting(&self, formatter: &mut fmt::Formatter) -> fmt::Result { + formatter.write_str("a string") + } + + fn visit_str(self, v: &str) -> Result + where + E: Error, + { + Ok(String::from(v)) + } + + fn visit_bytes(self, v: &[u8]) -> Result + where + E: Error, + { + let mut msg = String { + data: std::ptr::null_mut(), + size: 0, + capacity: 0, + }; + // SAFETY: This is doing the same thing as rosidl_runtime_c__String__copy. + unsafe { + rosidl_runtime_c__String__assignn(&mut msg, v.as_ptr() as *const _, v.len()); + } + Ok(msg) + } + + // We don't implement visit_bytes_buf, since the data in a string must always be managed by C. +} + +impl<'de> Visitor<'de> for WStringVisitor { + type Value = WString; + + fn expecting(&self, formatter: &mut fmt::Formatter) -> fmt::Result { + formatter.write_str("a string") + } + + fn visit_str(self, v: &str) -> Result + where + E: Error, + { + Ok(WString::from(v)) + } + + fn visit_seq(self, mut seq: A) -> Result + where + A: SeqAccess<'de>, + { + let mut buf = if let Some(size) = seq.size_hint() { + Vec::with_capacity(size) + } else { + Vec::new() + }; + while let Some(el) = seq.next_element::()? { + buf.push(el); + } + let mut msg = WString { + data: std::ptr::null_mut(), + size: 0, + capacity: 0, + }; + // SAFETY: This is doing the same thing as rosidl_runtime_c__U16String__copy. + unsafe { + rosidl_runtime_c__U16String__assignn(&mut msg, buf.as_ptr(), buf.len()); + } + Ok(msg) + } + + // We don't implement visit_bytes_buf, since the data in a string must always be managed by C. +} + +impl<'de> Deserialize<'de> for String { + fn deserialize(deserializer: D) -> Result + where + D: Deserializer<'de>, + { + deserializer.deserialize_string(StringVisitor) + } +} + +impl Serialize for String { + fn serialize(&self, serializer: S) -> Result + where + S: Serializer, + { + // Not particularly efficient + // SAFETY: See the Display implementation. + let u8_slice = unsafe { std::slice::from_raw_parts(self.data as *mut u8, self.size) }; + let s = std::string::String::from_utf8_lossy(u8_slice); + serializer.serialize_str(&s) + } +} + +impl<'de> Deserialize<'de> for WString { + fn deserialize(deserializer: D) -> Result + where + D: Deserializer<'de>, + { + deserializer.deserialize_string(WStringVisitor) + } +} + +impl Serialize for WString { + fn serialize(&self, serializer: S) -> Result + where + S: Serializer, + { + // Not particularly efficient + // SAFETY: See the Display implementation. + let u16_slice = unsafe { std::slice::from_raw_parts(self.data, self.size) }; + let s = std::string::String::from_utf16_lossy(u16_slice); + serializer.serialize_str(&s) + } +} + +impl<'de, const N: usize> Deserialize<'de> for BoundedString { + fn deserialize(deserializer: D) -> Result + where + D: Deserializer<'de>, + { + std::string::String::deserialize(deserializer) + .and_then(|s| Self::try_from(s.as_str()).map_err(D::Error::custom)) + } +} + +impl Serialize for BoundedString { + fn serialize(&self, serializer: S) -> Result + where + S: Serializer, + { + self.inner.serialize(serializer) + } +} + +impl<'de, const N: usize> Deserialize<'de> for BoundedWString { + fn deserialize(deserializer: D) -> Result + where + D: Deserializer<'de>, + { + std::string::String::deserialize(deserializer) + .and_then(|s| Self::try_from(s.as_str()).map_err(D::Error::custom)) + } +} + +impl Serialize for BoundedWString { + fn serialize(&self, serializer: S) -> Result + where + S: Serializer, + { + self.inner.serialize(serializer) + } +} + +#[cfg(test)] +mod tests { + use quickcheck::quickcheck; + + use crate::{BoundedString, BoundedWString, String, WString}; + + quickcheck! { + fn test_json_roundtrip_string(s: String) -> bool { + let value = serde_json::to_value(s.clone()).unwrap(); + let recovered = serde_json::from_value(value).unwrap(); + s == recovered + } + } + + quickcheck! { + fn test_json_roundtrip_wstring(s: WString) -> bool { + let value = serde_json::to_value(s.clone()).unwrap(); + let recovered = serde_json::from_value(value).unwrap(); + s == recovered + } + } + + quickcheck! { + fn test_json_roundtrip_bounded_string(s: BoundedString<256>) -> bool { + let value = serde_json::to_value(s.clone()).unwrap(); + let recovered = serde_json::from_value(value).unwrap(); + s == recovered + } + } + + quickcheck! { + fn test_json_roundtrip_bounded_wstring(s: BoundedWString<256>) -> bool { + let value = serde_json::to_value(s.clone()).unwrap(); + let recovered = serde_json::from_value(value).unwrap(); + s == recovered + } + } +} diff --git a/rosidl_runtime_rs/src/traits.rs b/rosidl_runtime_rs/src/traits.rs new file mode 100644 index 0000000..61d8c23 --- /dev/null +++ b/rosidl_runtime_rs/src/traits.rs @@ -0,0 +1,254 @@ +// Copyright 2020 DCS Corporation, All Rights Reserved. + +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at + +// http://www.apache.org/licenses/LICENSE-2.0 + +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +// DISTRIBUTION A. Approved for public release; distribution unlimited. +// OPSEC #4584. +// +use std::{borrow::Cow, fmt::Debug}; + +/// Internal trait that connects a particular `Sequence` instance to generated C functions +/// that allocate and deallocate memory. +/// +/// User code never needs to call these trait methods, much less implement this trait. +pub trait SequenceAlloc: Sized { + /// Wraps the corresponding init function generated by `rosidl_generator_c`. + fn sequence_init(seq: &mut crate::Sequence, size: usize) -> bool; + /// Wraps the corresponding fini function generated by `rosidl_generator_c`. + fn sequence_fini(seq: &mut crate::Sequence); + /// Wraps the corresponding copy function generated by `rosidl_generator_c`. + fn sequence_copy(in_seq: &crate::Sequence, out_seq: &mut crate::Sequence) -> bool; +} + +/// Trait for RMW-native messages. +/// +/// See the documentation for the [`Message`] trait, which is the trait that should generally be +/// used by user code. +/// +/// User code never needs to call this trait's method, much less implement this trait. +pub trait RmwMessage: Clone + Debug + Default + Send + Sync + Message { + /// A string representation of this message's type, e.g. "geometry_msgs/msg/Twist" + const TYPE_NAME: &'static str; + + /// Get a pointer to the correct `rosidl_message_type_support_t` structure. + fn get_type_support() -> *const std::ffi::c_void; +} + +/// Trait for types that can be used in a `rclrs::Subscription` and a `rclrs::Publisher`. +/// +/// `rosidl_generator_rs` generates two types of messages that implement this trait: +/// - An "idiomatic" message type, in the `${package_name}::msg` module +/// - An "RMW-native" message type, in the `${package_name}::msg::rmw` module +/// +/// # Idiomatic message type +/// The idiomatic message type aims to be familiar to Rust developers and ROS 2 developers coming +/// from `rclcpp`. +/// To this end, it translates the original ROS 2 message into a version that uses idiomatic Rust +/// structs: [`std::vec::Vec`] for sequences and [`std::string::String`] for strings. All other +/// fields are the same as in an RMW-native message. +/// +/// This conversion incurs some overhead when reading and publishing messages. +/// +/// It's possible to use the idiomatic type for a publisher and the RMW-native type for a +/// corresponding subscription, and vice versa. +/// +/// # RMW-native message type +/// The RMW-native message type aims to achieve higher performance by avoiding the conversion +/// step to an idiomatic message. +/// +/// It uses the following type mapping: +/// +/// | Message field type | Rust type | +/// |------------|---------------| +/// | `string` | [`String`](crate::String) | +/// | `wstring` | [`WString`](crate::WString) | +/// | `string<=N`, for example `string<=10` | [`BoundedString`](crate::BoundedString) | +/// | `wstring<=N`, for example `wstring<=10` | [`BoundedWString`](crate::BoundedWString) | +/// | `T[]`, for example `int32[]` | [`Sequence`](crate::Sequence) | +/// | `T[<=N]`, for example `int32[<=32]` | [`BoundedSequence`](crate::BoundedSequence) | +/// | `T[N]`, for example `float32[8]` | standard Rust arrays | +/// | primitive type, for example `float64` | corresponding Rust primitive type | +/// +///
+/// +/// The linked Rust types provided by this package are equivalents of types defined in C that are +/// used by the RMW layer. +/// +/// The API for these types, and the message as a whole, is still memory-safe and as convenient as +/// possible. +/// For instance, the [`Sequence`](crate::Sequence) struct that is used for sequences supports +/// iteration and all of the functionality of slices. However, it doesn't have an equivalent of +/// [`Vec::push()`], among others. +/// +/// ## What does "RMW-native" mean in detail? +/// The message can be directly passed to and from the RMW layer because (1) its layout is +/// identical to the layout of the type generated by `rosidl_generator_c` and (2) the dynamic +/// memory inside the message is owned by the C allocator. +/// +/// The above type mapping, together with a `#[repr(C)]` annotation on the message, guarantees +/// these two properties. +/// +/// This means the user of a message does not need to care about memory ownership, because that is +/// managed by the relevant functions and trait impls. +/// +/// ## I need even more detail, please +/// `rosidl_runtime_c` and the code generated by `rosidl_generator_c` manages +/// memory by means of four functions for each message: `init()`, `fini()`, `create()`, and +/// `destroy()`. +/// +/// `init()` does the following: +/// - for a message, it calls `init()` on all its members that are of non-primitive type, and applies default values +/// - for a primitive sequence, it allocates the space requested +/// - for a string, it constructs a string containing a single null terminator byte +/// - for a non-primitive sequence, it zero-allocates the space requested and calls `init()` on all its elements +/// +/// `fini()` does the following (which means after a call to `fini()`, everything inside the message has been deallocated): +/// - for a message, it calls `fini()` on all its members that are of non-primitive type +/// - for a primitive sequence, it deallocates +/// - for a string, it deallocates +/// - for a non-primitive sequence, it calls `fini()` on all its elements, and then deallocates +/// +/// `create()` simply allocates space for the message itself, and calls `init()`. +/// +/// `destroy()` simply deallocates the message itself, and calls `fini()`. +/// +/// Memory ownership by C is achieved by calling `init()` when any string or sequence is created, +/// as well as in the `Default` impl for messages. +/// +/// User code can still create messages explicitly, which will not call `init()`, but this is not a +/// problem, since nothing is allocated this way. +/// +/// The `Drop` impl for any sequence or string will call `fini()`. +pub trait Message: Clone + Debug + Default + 'static + Send + Sync { + /// The corresponding RMW-native message type. + type RmwMsg: RmwMessage; + + /// Converts the idiomatic message into an RMW-native message. + /// + /// If the idiomatic message is owned, a slightly more efficient conversion is possible. + /// This is why the function takes a `Cow`. + /// + /// If this function receives a borrowed message that is already RMW-native, it should + /// directly return that borrowed message. + /// This is why the return type is also `Cow`. + fn into_rmw_message(msg_cow: Cow<'_, Self>) -> Cow<'_, Self::RmwMsg>; + + /// Converts the RMW-native message into an idiomatic message. + fn from_rmw_message(msg: Self::RmwMsg) -> Self; +} + +/// Trait for services. +/// +/// User code never needs to call this trait's method, much less implement this trait. +pub trait Service: 'static { + /// The request message associated with this service. + type Request: Message; + + /// The response message associated with this service. + type Response: Message; + + /// Get a pointer to the correct `rosidl_service_type_support_t` structure. + fn get_type_support() -> *const std::ffi::c_void; +} + +/// Trait for actions. +/// +/// User code never needs to call this trait's method, much less implement this trait. +pub trait Action: 'static { + /// The goal message associated with this action. + type Goal: Message; + + /// The result message associated with this action. + type Result: Message; + + /// The feedback message associated with this action. + type Feedback: Message; + + /// Get a pointer to the correct `rosidl_action_type_support_t` structure. + fn get_type_support() -> *const std::ffi::c_void; +} + +/// Trait for action implementation details. +/// +/// User code never needs to implement this trait, nor use its associated types. +pub trait ActionImpl: 'static + Action { + /// The goal_status message associated with this action. + type GoalStatusMessage: Message; + + /// The feedback message associated with this action. + type FeedbackMessage: Message; + + /// The send_goal service associated with this action. + type SendGoalService: Service; + + /// The cancel_goal service associated with this action. + type CancelGoalService: Service; + + /// The get_result service associated with this action. + type GetResultService: Service; + + /// Create a goal request message with the given UUID and goal. + fn create_goal_request(goal_id: &[u8; 16], goal: RmwGoalData) -> RmwGoalRequest; + + /// Get the UUID of a goal request. + fn get_goal_request_uuid(request: &RmwGoalRequest) -> &[u8; 16]; + + /// Create a goal response message with the given acceptance and timestamp. + fn create_goal_response(accepted: bool, stamp: (i32, u32)) -> RmwGoalResponse; + + /// Get the `accepted` field of a goal response. + fn get_goal_response_accepted(response: &RmwGoalResponse) -> bool; + + /// Get the `stamp` field of a goal response. + fn get_goal_response_stamp(response: &RmwGoalResponse) -> (i32, u32); + + /// Create a feedback message with the given goal ID and contents. + fn create_feedback_message( + goal_id: &[u8; 16], + feedback: RmwFeedbackData, + ) -> RmwFeedbackMessage; + + /// Get the UUID of a feedback message. + fn get_feedback_message_uuid(feedback: &RmwFeedbackMessage) -> &[u8; 16]; + + /// Get the feedback of a feedback message. + fn get_feedback_message_feedback(feedback: &RmwFeedbackMessage) + -> &RmwFeedbackData; + + /// Create a result request message with the given goal ID. + fn create_result_request(goal_id: &[u8; 16]) -> RmwResultRequest; + + /// Get the UUID of a result request. + fn get_result_request_uuid(request: &RmwResultRequest) -> &[u8; 16]; + + /// Create a result response message with the given status and contents. + fn create_result_response(status: i8, result: RmwResultData) -> RmwResultResponse; + + /// Get the result of a result response. + fn get_result_response_result(response: &RmwResultResponse) -> &RmwResultData; + + /// Get the status of a result response. + fn get_result_response_status(response: &RmwResultResponse) -> i8; +} + +// Type definitions to simplify the ActionImpl trait +pub type RmwServiceRequest = <::Request as Message>::RmwMsg; +pub type RmwServiceResponse = <::Response as Message>::RmwMsg; +pub type RmwGoalRequest
= RmwServiceRequest<::SendGoalService>; +pub type RmwGoalResponse = RmwServiceResponse<::SendGoalService>; +pub type RmwGoalData = <::Goal as Message>::RmwMsg; +pub type RmwFeedbackData = <::Feedback as Message>::RmwMsg; +pub type RmwFeedbackMessage = <::FeedbackMessage as Message>::RmwMsg; +pub type RmwResultRequest = RmwServiceRequest<::GetResultService>; +pub type RmwResultResponse = RmwServiceResponse<::GetResultService>; +pub type RmwResultData = <::Result as Message>::RmwMsg;