vec without derive
This commit is contained in:
parent
0968bc1f9b
commit
9f6068125f
|
|
@ -57,9 +57,9 @@ You can use `rosrust` and `r2r` by enabling the respective feature:
|
|||
|
||||
```toml
|
||||
[dependencies]
|
||||
ros_pointcloud2 = { version = "*", features = ["r2r_msg", "derive"]}
|
||||
ros_pointcloud2 = { version = "*", features = ["r2r_msg"]}
|
||||
# or
|
||||
ros_pointcloud2 = { version = "*", features = ["rosrust_msg", "derive"]}
|
||||
ros_pointcloud2 = { version = "*", features = ["rosrust_msg"]}
|
||||
```
|
||||
|
||||
### rclrs (ros2_rust)
|
||||
|
|
|
|||
|
|
@ -4,8 +4,9 @@ extern crate proc_macro;
|
|||
use std::collections::HashMap;
|
||||
|
||||
use proc_macro::TokenStream;
|
||||
use quote::{quote, ToTokens};
|
||||
use syn::{parenthesized, parse_macro_input, DeriveInput, LitStr};
|
||||
use proc_macro2::{Ident, Literal};
|
||||
use quote::{quote, quote_spanned, ToTokens};
|
||||
use syn::{parenthesized, parse_macro_input, spanned::Spanned, Data, DeriveInput, Fields, LitStr};
|
||||
|
||||
fn get_allowed_types() -> HashMap<&'static str, usize> {
|
||||
let mut allowed_datatypes = HashMap::<&'static str, usize>::new();
|
||||
|
|
@ -194,3 +195,78 @@ pub fn ros_point_derive(input: TokenStream) -> TokenStream {
|
|||
#convertible
|
||||
})
|
||||
}
|
||||
|
||||
#[proc_macro_derive(TypeLayout)]
|
||||
pub fn derive_type_layout(input: TokenStream) -> TokenStream {
|
||||
let input = parse_macro_input!(input as DeriveInput);
|
||||
let name = input.ident;
|
||||
|
||||
let (impl_generics, ty_generics, where_clause) = input.generics.split_for_impl();
|
||||
let layout = layout_of_type(&name, &input.data);
|
||||
|
||||
let expanded = quote! {
|
||||
impl #impl_generics ::ros_pointcloud2::TypeLayout for #name #ty_generics #where_clause {
|
||||
fn layout() -> ::ros_pointcloud2::LayoutDescription {
|
||||
let mut last_field_end = 0;
|
||||
let mut fields = Vec::new();
|
||||
|
||||
#layout
|
||||
|
||||
::ros_pointcloud2::LayoutDescription::new(fields.as_slice())
|
||||
}
|
||||
}
|
||||
};
|
||||
|
||||
TokenStream::from(expanded)
|
||||
}
|
||||
|
||||
fn layout_of_type(struct_name: &Ident, data: &Data) -> proc_macro2::TokenStream {
|
||||
match data {
|
||||
Data::Struct(data) => match &data.fields {
|
||||
Fields::Named(fields) => {
|
||||
let values = fields.named.iter().map(|field| {
|
||||
let field_name = field.ident.as_ref().unwrap();
|
||||
let field_name_str = Literal::string(&field_name.to_string());
|
||||
let field_ty = &field.ty;
|
||||
let field_ty_str = Literal::string(&field_ty.to_token_stream().to_string());
|
||||
|
||||
quote_spanned! { field.span() =>
|
||||
#[allow(unused_assignments)]
|
||||
{
|
||||
let size = ::std::mem::size_of::<#field_ty>();
|
||||
let offset = ::ros_pointcloud2::memoffset::offset_of!(#struct_name, #field_name);
|
||||
|
||||
if offset > last_field_end {
|
||||
fields.push(::ros_pointcloud2::LayoutField::Padding {
|
||||
size: offset - last_field_end
|
||||
});
|
||||
}
|
||||
|
||||
fields.push(::ros_pointcloud2::LayoutField::Field {
|
||||
name: ::std::borrow::Cow::Borrowed(#field_name_str),
|
||||
ty: ::std::borrow::Cow::Borrowed(#field_ty_str),
|
||||
size,
|
||||
});
|
||||
|
||||
last_field_end = offset + size;
|
||||
}
|
||||
}
|
||||
});
|
||||
|
||||
quote! {
|
||||
#(#values)*
|
||||
|
||||
let struct_size = ::std::mem::size_of::<#struct_name>();
|
||||
if struct_size > last_field_end {
|
||||
fields.push(::ros_pointcloud2::LayoutField::Padding {
|
||||
size: struct_size - last_field_end,
|
||||
});
|
||||
}
|
||||
}
|
||||
}
|
||||
Fields::Unnamed(_) => unimplemented!(),
|
||||
Fields::Unit => unimplemented!(),
|
||||
},
|
||||
Data::Enum(_) | Data::Union(_) => unimplemented!("type-layout only supports structs"),
|
||||
}
|
||||
}
|
||||
|
|
|
|||
|
|
@ -35,8 +35,8 @@ rosrust = { version = "0.9.11", optional = true }
|
|||
r2r = { version = "0.8.4", optional = true }
|
||||
rayon = { version = "1", optional = true }
|
||||
nalgebra = { version = "0.32.5", optional = true, default-features = false }
|
||||
type-layout = { version = "0.2", package = "type-layout-syn2", optional = true }
|
||||
rpcl2-derive = { version = "0.1.0", optional = true, path = "../rpcl2-derive" }
|
||||
memoffset = { version = "0.9", optional = true }
|
||||
|
||||
[dev-dependencies]
|
||||
rand = "0.8"
|
||||
|
|
@ -51,11 +51,11 @@ path = "benches/roundtrip.rs"
|
|||
rosrust_msg = ["dep:rosrust_msg", "dep:rosrust"]
|
||||
r2r_msg = ["dep:r2r"]
|
||||
rayon = ["dep:rayon"]
|
||||
derive = ["dep:rpcl2-derive", "dep:type-layout"]
|
||||
derive = ["dep:rpcl2-derive", "dep:memoffset"]
|
||||
nalgebra = ["dep:nalgebra"]
|
||||
std = ["nalgebra/std"]
|
||||
|
||||
default = ["std", "derive"]
|
||||
default = ["std"]
|
||||
|
||||
[package.metadata.docs.rs]
|
||||
features = ["derive", "nalgebra", "rayon"]
|
||||
|
|
|
|||
|
|
@ -162,7 +162,6 @@ pub fn heavy_computing(point: &PointXYZ, iterations: u32) -> f32 {
|
|||
result
|
||||
}
|
||||
|
||||
#[cfg(feature = "derive")]
|
||||
fn roundtrip_vec(cloud: Vec<PointXYZB>) -> bool {
|
||||
let orig_len = cloud.len();
|
||||
let internal_msg = PointCloud2Msg::try_from_vec(cloud).unwrap();
|
||||
|
|
@ -180,7 +179,6 @@ fn roundtrip(cloud: Vec<PointXYZB>) -> bool {
|
|||
orig_len == total.len()
|
||||
}
|
||||
|
||||
#[cfg(feature = "derive")]
|
||||
fn roundtrip_filter_vec(cloud: Vec<PointXYZB>) -> bool {
|
||||
let orig_len = cloud.len();
|
||||
let internal_msg = PointCloud2Msg::try_from_vec(cloud).unwrap();
|
||||
|
|
@ -243,7 +241,6 @@ fn roundtrip_computing_par_par(cloud: Vec<PointXYZB>) -> bool {
|
|||
total > 0.0
|
||||
}
|
||||
|
||||
#[cfg(feature = "derive")]
|
||||
fn roundtrip_computing_vec(cloud: Vec<PointXYZB>) -> bool {
|
||||
let internal_msg = PointCloud2Msg::try_from_vec(cloud).unwrap();
|
||||
let total: f32 = internal_msg
|
||||
|
|
@ -339,7 +336,6 @@ fn roundtrip_benchmark(c: &mut Criterion) {
|
|||
})
|
||||
});
|
||||
|
||||
#[cfg(feature = "derive")]
|
||||
c.bench_function("16k vec", |b| {
|
||||
b.iter(|| {
|
||||
black_box(roundtrip_vec(cloud_points_16k.clone()));
|
||||
|
|
@ -367,7 +363,6 @@ fn roundtrip_benchmark(c: &mut Criterion) {
|
|||
})
|
||||
});
|
||||
|
||||
#[cfg(feature = "derive")]
|
||||
c.bench_function("16k vec_filter", |b| {
|
||||
b.iter(|| {
|
||||
roundtrip_filter_vec(black_box(cloud_points_16k.clone()));
|
||||
|
|
@ -395,7 +390,6 @@ fn roundtrip_benchmark(c: &mut Criterion) {
|
|||
})
|
||||
});
|
||||
|
||||
#[cfg(feature = "derive")]
|
||||
c.bench_function("16k vec_compute", |b| {
|
||||
b.iter(|| {
|
||||
roundtrip_computing_vec(black_box(cloud_points_16k.clone()));
|
||||
|
|
@ -425,7 +419,6 @@ fn roundtrip_benchmark(c: &mut Criterion) {
|
|||
})
|
||||
});
|
||||
|
||||
#[cfg(feature = "derive")]
|
||||
c.bench_function("60k vec", |b| {
|
||||
b.iter(|| {
|
||||
black_box(roundtrip_vec(cloud_points_60k.clone()));
|
||||
|
|
@ -455,7 +448,6 @@ fn roundtrip_benchmark(c: &mut Criterion) {
|
|||
})
|
||||
});
|
||||
|
||||
#[cfg(feature = "derive")]
|
||||
c.bench_function("120k vec", |b| {
|
||||
b.iter(|| {
|
||||
black_box(roundtrip_vec(cloud_points_120k.clone()));
|
||||
|
|
@ -483,7 +475,6 @@ fn roundtrip_benchmark(c: &mut Criterion) {
|
|||
})
|
||||
});
|
||||
|
||||
#[cfg(feature = "derive")]
|
||||
c.bench_function("120k vec_filter", |b| {
|
||||
b.iter(|| {
|
||||
roundtrip_filter_vec(black_box(cloud_points_120k.clone()));
|
||||
|
|
@ -511,7 +502,6 @@ fn roundtrip_benchmark(c: &mut Criterion) {
|
|||
})
|
||||
});
|
||||
|
||||
#[cfg(feature = "derive")]
|
||||
c.bench_function("120k vec_compute", |b| {
|
||||
b.iter(|| {
|
||||
roundtrip_computing_vec(black_box(cloud_points_120k.clone()));
|
||||
|
|
@ -541,7 +531,6 @@ fn roundtrip_benchmark(c: &mut Criterion) {
|
|||
})
|
||||
});
|
||||
|
||||
#[cfg(feature = "derive")]
|
||||
c.bench_function("500k vec", |b| {
|
||||
b.iter(|| {
|
||||
black_box(roundtrip_vec(cloud_points_500k.clone()));
|
||||
|
|
@ -569,7 +558,6 @@ fn roundtrip_benchmark(c: &mut Criterion) {
|
|||
})
|
||||
});
|
||||
|
||||
#[cfg(feature = "derive")]
|
||||
c.bench_function("500k vec_filter", |b| {
|
||||
b.iter(|| {
|
||||
roundtrip_filter_vec(black_box(cloud_points_500k.clone()));
|
||||
|
|
@ -597,7 +585,6 @@ fn roundtrip_benchmark(c: &mut Criterion) {
|
|||
})
|
||||
});
|
||||
|
||||
#[cfg(feature = "derive")]
|
||||
c.bench_function("500k vec_compute", |b| {
|
||||
b.iter(|| {
|
||||
roundtrip_computing_vec(black_box(cloud_points_500k.clone()));
|
||||
|
|
@ -627,7 +614,6 @@ fn roundtrip_benchmark(c: &mut Criterion) {
|
|||
})
|
||||
});
|
||||
|
||||
#[cfg(feature = "derive")]
|
||||
c.bench_function("1.5m vec", |b| {
|
||||
b.iter(|| {
|
||||
black_box(roundtrip_vec(cloud_points_1_5m.clone()));
|
||||
|
|
@ -655,7 +641,6 @@ fn roundtrip_benchmark(c: &mut Criterion) {
|
|||
})
|
||||
});
|
||||
|
||||
#[cfg(feature = "derive")]
|
||||
c.bench_function("1.5m vec_filter", |b| {
|
||||
b.iter(|| {
|
||||
roundtrip_filter_vec(black_box(cloud_points_1_5m.clone()));
|
||||
|
|
@ -683,7 +668,6 @@ fn roundtrip_benchmark(c: &mut Criterion) {
|
|||
})
|
||||
});
|
||||
|
||||
#[cfg(feature = "derive")]
|
||||
c.bench_function("1.5m vec_compute", |b| {
|
||||
b.iter(|| {
|
||||
roundtrip_computing_vec(black_box(cloud_points_1_5m.clone()));
|
||||
|
|
|
|||
|
|
@ -20,6 +20,7 @@ enum Label {
|
|||
// Define a custom point with an enum.
|
||||
// This is normally not supported by PointCloud2 but we will explain the library how to handle it.
|
||||
#[derive(Debug, PartialEq, Clone, Default)]
|
||||
#[repr(C)]
|
||||
struct CustomPoint {
|
||||
x: f32,
|
||||
y: f32,
|
||||
|
|
@ -96,6 +97,18 @@ impl Fields<5> for CustomPoint {
|
|||
}
|
||||
}
|
||||
|
||||
// C representation of the struct hardcoded without using the derive feature.
|
||||
impl TypeLayout for CustomPoint {
|
||||
fn layout() -> LayoutDescription {
|
||||
LayoutDescription::new(&[
|
||||
LayoutField::new("x", "f32", 4),
|
||||
LayoutField::new("y", "f32", 4),
|
||||
LayoutField::new("z", "f32", 4),
|
||||
LayoutField::new("intensity", "f32", 4),
|
||||
])
|
||||
}
|
||||
}
|
||||
|
||||
// We implemented everything that is needed for PointConvertible so we declare it as a done.
|
||||
#[cfg(not(feature = "derive"))]
|
||||
impl PointConvertible<5> for CustomPoint {}
|
||||
|
|
|
|||
192
rpcl2/src/lib.rs
192
rpcl2/src/lib.rs
|
|
@ -3,8 +3,8 @@
|
|||
//! The library provides the [`PointCloud2Msg`] type, which implements conversions to and from `Vec` and (parallel) iterators.
|
||||
//!
|
||||
//! Vector conversions are optimized for direct copy. They are useful when you just move similar data around. They are usually a good default.
|
||||
//! - [`try_from_vec`](PointCloud2Msg::try_from_vec) requires `derive` feature (enabled by default)
|
||||
//! - [`try_into_vec`](PointCloud2Msg::try_into_vec) requires `derive` feature (enabled by default)
|
||||
//! - [`try_from_vec`](PointCloud2Msg::try_from_vec)
|
||||
//! - [`try_into_vec`](PointCloud2Msg::try_into_vec)
|
||||
//!
|
||||
//! You can use the iterator functions for more control over the conversion process.
|
||||
//! - [`try_from_iter`](PointCloud2Msg::try_from_iter)
|
||||
|
|
@ -106,6 +106,18 @@
|
|||
//! }
|
||||
//!
|
||||
//! #[cfg(not(feature = "derive"))]
|
||||
//! impl TypeLayout for MyPointXYZI {
|
||||
//! fn layout() -> LayoutDescription {
|
||||
//! LayoutDescription::new(&[
|
||||
//! LayoutField::new("x", "f32", 4),
|
||||
//! LayoutField::new("y", "f32", 4),
|
||||
//! LayoutField::new("z", "f32", 4),
|
||||
//! LayoutField::new("intensity", "f32", 4), // Use the original name.
|
||||
//! ])
|
||||
//! }
|
||||
//! }
|
||||
//!
|
||||
//! #[cfg(not(feature = "derive"))]
|
||||
//! impl PointConvertible<4> for MyPointXYZI {}
|
||||
//!
|
||||
//! let first_p = MyPointXYZI::new(1.0, 2.0, 3.0, 0.5);
|
||||
|
|
@ -149,6 +161,9 @@ pub mod iterator;
|
|||
use crate::ros::{HeaderMsg, PointFieldMsg};
|
||||
|
||||
#[cfg(feature = "derive")]
|
||||
#[doc(hidden)]
|
||||
pub use memoffset;
|
||||
|
||||
use core::str::FromStr;
|
||||
|
||||
#[macro_use]
|
||||
|
|
@ -222,7 +237,6 @@ impl std::error::Error for MsgConversionError {
|
|||
}
|
||||
}
|
||||
|
||||
#[cfg(feature = "derive")]
|
||||
fn system_endian() -> Endian {
|
||||
if cfg!(target_endian = "big") {
|
||||
Endian::Big
|
||||
|
|
@ -233,6 +247,43 @@ fn system_endian() -> Endian {
|
|||
}
|
||||
}
|
||||
|
||||
/// Description of the memory layout of a type with named fields.
|
||||
#[derive(Clone, Debug)]
|
||||
pub struct LayoutDescription(Vec<LayoutField>);
|
||||
|
||||
impl LayoutDescription {
|
||||
pub fn new(fields: &[LayoutField]) -> Self {
|
||||
Self(fields.to_vec())
|
||||
}
|
||||
}
|
||||
|
||||
/// Enum to describe the field type and size in a padded or unpadded layout.
|
||||
#[derive(Clone, Debug)]
|
||||
pub enum LayoutField {
|
||||
Field {
|
||||
name: alloc::borrow::Cow<'static, str>,
|
||||
ty: alloc::borrow::Cow<'static, str>,
|
||||
size: usize,
|
||||
},
|
||||
Padding {
|
||||
size: usize,
|
||||
},
|
||||
}
|
||||
|
||||
impl LayoutField {
|
||||
pub fn new(name: &'static str, ty: &'static str, size: usize) -> Self {
|
||||
LayoutField::Field {
|
||||
name: name.into(),
|
||||
ty: ty.into(),
|
||||
size,
|
||||
}
|
||||
}
|
||||
|
||||
pub fn padding(size: usize) -> Self {
|
||||
LayoutField::Padding { size }
|
||||
}
|
||||
}
|
||||
|
||||
/// The intermediate point cloud type for ROS integrations.
|
||||
///
|
||||
/// To assert consistency, the type should be build with the [`PointCloud2MsgBuilder`].
|
||||
|
|
@ -265,7 +316,6 @@ pub enum Denseness {
|
|||
Sparse,
|
||||
}
|
||||
|
||||
#[cfg(feature = "derive")]
|
||||
enum ByteSimilarity {
|
||||
Equal,
|
||||
Overlapping,
|
||||
|
|
@ -421,7 +471,6 @@ pub struct CloudDimensions {
|
|||
}
|
||||
|
||||
impl PointCloud2Msg {
|
||||
#[cfg(feature = "derive")]
|
||||
#[inline]
|
||||
fn byte_similarity<const N: usize, C>(&self) -> Result<ByteSimilarity, MsgConversionError>
|
||||
where
|
||||
|
|
@ -433,7 +482,7 @@ impl PointCloud2Msg {
|
|||
let field_names = C::field_names_ordered();
|
||||
debug_assert!(field_names.len() == N);
|
||||
|
||||
let layout = TypeLayoutInfo::try_from(C::type_layout())?;
|
||||
let layout = KnownLayoutInfo::try_from(C::layout())?;
|
||||
debug_assert!(field_names.len() == layout.fields.len());
|
||||
|
||||
let mut offset: u32 = 0;
|
||||
|
|
@ -549,8 +598,8 @@ impl PointCloud2Msg {
|
|||
}
|
||||
|
||||
/// Create a PointCloud2Msg from a parallel iterator. Requires the `rayon` and `derive` feature to be enabled.
|
||||
#[cfg(all(feature = "rayon", feature = "derive"))]
|
||||
#[cfg_attr(docsrs, doc(cfg(all(feature = "rayon", feature = "derive"))))]
|
||||
#[cfg(feature = "rayon")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "rayon")))]
|
||||
pub fn try_from_par_iter<const N: usize, C>(
|
||||
iterable: impl rayon::iter::ParallelIterator<Item = C>,
|
||||
) -> Result<Self, MsgConversionError>
|
||||
|
|
@ -577,8 +626,6 @@ impl PointCloud2Msg {
|
|||
///
|
||||
/// # Errors
|
||||
/// Returns an error if the byte buffer does not match the expected layout or the message contains other discrepancies.
|
||||
#[cfg(feature = "derive")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "derive")))]
|
||||
pub fn try_from_vec<const N: usize, C>(vec: Vec<C>) -> Result<Self, MsgConversionError>
|
||||
where
|
||||
C: PointConvertible<N>,
|
||||
|
|
@ -592,7 +639,7 @@ impl PointCloud2Msg {
|
|||
let field_names = C::field_names_ordered();
|
||||
debug_assert!(field_names.len() == N);
|
||||
|
||||
let layout = TypeLayoutInfo::try_from(C::type_layout())?;
|
||||
let layout = KnownLayoutInfo::try_from(C::layout())?;
|
||||
debug_assert!(field_names.len() == layout.fields.len());
|
||||
|
||||
let mut offset = 0;
|
||||
|
|
@ -666,8 +713,6 @@ impl PointCloud2Msg {
|
|||
///
|
||||
/// # Errors
|
||||
/// Returns an error if the byte buffer does not match the expected layout or the message contains other discrepancies.
|
||||
#[cfg(feature = "derive")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "derive")))]
|
||||
pub fn try_into_vec<const N: usize, C>(self) -> Result<Vec<C>, MsgConversionError>
|
||||
where
|
||||
C: PointConvertible<N>,
|
||||
|
|
@ -794,7 +839,23 @@ impl<const N: usize> From<[PointData; N]> for RPCL2Point<N> {
|
|||
|
||||
/// Trait to enable point conversions on the fly.
|
||||
///
|
||||
/// # Example
|
||||
/// Implement this trait for your custom point you want to read or write in the message.
|
||||
/// For a more convenient way to implement this trait, enable the `derive` feature and use the `#[derive(PointConvertible, TypeLayout)]` macro.
|
||||
///
|
||||
/// # Derive Example
|
||||
/// ```
|
||||
/// use ros_pointcloud2::prelude::*;
|
||||
///
|
||||
/// #[derive(Clone, Debug, PartialEq, Copy, Default)]
|
||||
/// pub struct MyPointXYZI {
|
||||
/// pub x: f32,
|
||||
/// pub y: f32,
|
||||
/// pub z: f32,
|
||||
/// pub intensity: f32,
|
||||
/// }
|
||||
/// ```
|
||||
///
|
||||
/// # Manual Example
|
||||
/// ```
|
||||
/// use ros_pointcloud2::prelude::*;
|
||||
///
|
||||
|
|
@ -829,74 +890,21 @@ impl<const N: usize> From<[PointData; N]> for RPCL2Point<N> {
|
|||
/// }
|
||||
/// }
|
||||
///
|
||||
/// impl PointConvertible<4> for MyPointXYZI {}
|
||||
/// ```
|
||||
#[cfg_attr(docsrs, doc(cfg(not(feature = "derive"))))]
|
||||
#[cfg(not(feature = "derive"))]
|
||||
pub trait PointConvertible<const N: usize>:
|
||||
From<RPCL2Point<N>> + Into<RPCL2Point<N>> + Fields<N> + Clone + Default
|
||||
{
|
||||
}
|
||||
|
||||
/// Trait to enable point conversions on the fly.
|
||||
///
|
||||
/// Implement this trait for your custom point you want to read or write in the message.
|
||||
/// For a more convenient way to implement this trait, enable the `derive` feature and use the `#[derive(PointConvertible, TypeLayout)]` macro.
|
||||
///
|
||||
/// # Derive Example
|
||||
/// ```
|
||||
/// use ros_pointcloud2::prelude::*;
|
||||
///
|
||||
/// #[derive(Clone, Debug, PartialEq, Copy, Default, PointConvertible, TypeLayout)]
|
||||
/// pub struct MyPointXYZI {
|
||||
/// pub x: f32,
|
||||
/// pub y: f32,
|
||||
/// pub z: f32,
|
||||
/// pub intensity: f32,
|
||||
/// }
|
||||
/// ```
|
||||
///
|
||||
/// # Manual Example
|
||||
/// ```
|
||||
/// use ros_pointcloud2::prelude::*;
|
||||
///
|
||||
/// #[derive(Clone, Debug, PartialEq, Copy, Default, TypeLayout)]
|
||||
/// pub struct MyPointXYZI {
|
||||
/// pub x: f32,
|
||||
/// pub y: f32,
|
||||
/// pub z: f32,
|
||||
/// pub intensity: f32,
|
||||
/// }
|
||||
///
|
||||
/// impl From<MyPointXYZI> for RPCL2Point<4> {
|
||||
/// fn from(point: MyPointXYZI) -> Self {
|
||||
/// [point.x.into(), point.y.into(), point.z.into(), point.intensity.into()].into()
|
||||
/// impl TypeLayout for MyPointXYZI {
|
||||
/// fn layout() -> LayoutDescription {
|
||||
/// LayoutDescription::new(&[
|
||||
/// LayoutField::new("x", "f32", 4),
|
||||
/// LayoutField::new("y", "f32", 4),
|
||||
/// LayoutField::new("z", "f32", 4),
|
||||
/// LayoutField::new("intensity", "f32", 4),
|
||||
/// ])
|
||||
/// }
|
||||
/// }
|
||||
///
|
||||
/// impl From<RPCL2Point<4>> for MyPointXYZI {
|
||||
/// fn from(point: RPCL2Point<4>) -> Self {
|
||||
/// Self {
|
||||
/// x: point[0].get(),
|
||||
/// y: point[1].get(),
|
||||
/// z: point[2].get(),
|
||||
/// intensity: point[3].get(),
|
||||
/// }
|
||||
/// }
|
||||
/// }
|
||||
///
|
||||
/// impl Fields<4> for MyPointXYZI {
|
||||
/// fn field_names_ordered() -> [&'static str; 4] {
|
||||
/// ["x", "y", "z", "intensity"]
|
||||
/// }
|
||||
/// }
|
||||
///
|
||||
/// impl PointConvertible<4> for MyPointXYZI {}
|
||||
/// ```
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "derive")))]
|
||||
#[cfg(feature = "derive")]
|
||||
pub trait PointConvertible<const N: usize>:
|
||||
type_layout::TypeLayout + From<RPCL2Point<N>> + Into<RPCL2Point<N>> + Fields<N> + Default
|
||||
TypeLayout + From<RPCL2Point<N>> + Into<RPCL2Point<N>> + Fields<N> + Default
|
||||
{
|
||||
}
|
||||
|
||||
|
|
@ -927,24 +935,26 @@ pub trait Fields<const N: usize> {
|
|||
fn field_names_ordered() -> [&'static str; N];
|
||||
}
|
||||
|
||||
#[cfg(feature = "derive")]
|
||||
enum PointField {
|
||||
Padding(u32),
|
||||
Field { size: u32, datatype: u8, count: u32 },
|
||||
}
|
||||
|
||||
#[cfg(feature = "derive")]
|
||||
struct TypeLayoutInfo {
|
||||
struct KnownLayoutInfo {
|
||||
fields: Vec<PointField>,
|
||||
}
|
||||
|
||||
#[cfg(feature = "derive")]
|
||||
impl TryFrom<type_layout::Field> for PointField {
|
||||
/// Trait to enable the layout description for the point type for direct copy operations.
|
||||
pub trait TypeLayout {
|
||||
fn layout() -> LayoutDescription;
|
||||
}
|
||||
|
||||
impl TryFrom<LayoutField> for PointField {
|
||||
type Error = MsgConversionError;
|
||||
|
||||
fn try_from(f: type_layout::Field) -> Result<Self, Self::Error> {
|
||||
fn try_from(f: LayoutField) -> Result<Self, Self::Error> {
|
||||
match f {
|
||||
type_layout::Field::Field { name: _, ty, size } => {
|
||||
LayoutField::Field { name: _, ty, size } => {
|
||||
let typename: String = ty.into_owned().to_lowercase();
|
||||
let datatype = FieldDatatype::from_str(typename.as_str())?;
|
||||
Ok(Self::Field {
|
||||
|
|
@ -953,21 +963,19 @@ impl TryFrom<type_layout::Field> for PointField {
|
|||
count: 1,
|
||||
})
|
||||
}
|
||||
type_layout::Field::Padding { size } => Ok(Self::Padding(size.try_into()?)),
|
||||
LayoutField::Padding { size } => Ok(Self::Padding(size.try_into()?)),
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#[cfg(feature = "derive")]
|
||||
impl TryFrom<type_layout::TypeLayoutInfo> for TypeLayoutInfo {
|
||||
impl TryFrom<LayoutDescription> for KnownLayoutInfo {
|
||||
type Error = MsgConversionError;
|
||||
|
||||
fn try_from(t: type_layout::TypeLayoutInfo) -> Result<Self, Self::Error> {
|
||||
let fields: Vec<PointField> = t
|
||||
.fields
|
||||
.into_iter()
|
||||
.map(PointField::try_from)
|
||||
.collect::<Result<Vec<_>, _>>()?;
|
||||
fn try_from(t: LayoutDescription) -> Result<Self, Self::Error> {
|
||||
let fields: Vec<PointField> =
|
||||
t.0.into_iter()
|
||||
.map(PointField::try_from)
|
||||
.collect::<Result<Vec<_>, _>>()?;
|
||||
Ok(Self { fields })
|
||||
}
|
||||
}
|
||||
|
|
|
|||
|
|
@ -1,11 +1,5 @@
|
|||
//! Predefined point types commonly used in ROS.
|
||||
use crate::{Fields, PointConvertible, RPCL2Point};
|
||||
|
||||
#[cfg(feature = "derive")]
|
||||
use type_layout::TypeLayout;
|
||||
|
||||
#[cfg(feature = "derive")]
|
||||
use alloc::vec::Vec;
|
||||
use crate::{Fields, LayoutDescription, LayoutField, PointConvertible, RPCL2Point, TypeLayout};
|
||||
|
||||
/// A packed RGB color encoding as used in ROS tools.
|
||||
#[derive(Clone, Copy)]
|
||||
|
|
@ -112,7 +106,6 @@ impl From<f32> for RGB {
|
|||
/// Predefined point type commonly used in ROS with PCL.
|
||||
/// This is a 3D point with x, y, z coordinates.
|
||||
#[derive(Clone, Debug, PartialEq, Copy, Default)]
|
||||
#[cfg_attr(feature = "derive", derive(TypeLayout))]
|
||||
#[repr(C)]
|
||||
pub struct PointXYZ {
|
||||
pub x: f32,
|
||||
|
|
@ -120,6 +113,16 @@ pub struct PointXYZ {
|
|||
pub z: f32,
|
||||
}
|
||||
|
||||
impl TypeLayout for PointXYZ {
|
||||
fn layout() -> LayoutDescription {
|
||||
LayoutDescription::new(&[
|
||||
LayoutField::new("x", "f32", 4),
|
||||
LayoutField::new("y", "f32", 4),
|
||||
LayoutField::new("z", "f32", 4),
|
||||
])
|
||||
}
|
||||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
impl From<nalgebra::Point3<f32>> for PointXYZ {
|
||||
fn from(point: nalgebra::Point3<f32>) -> Self {
|
||||
|
|
@ -178,7 +181,6 @@ impl PointConvertible<3> for PointXYZ {}
|
|||
/// Predefined point type commonly used in ROS with PCL.
|
||||
/// This is a 3D point with x, y, z coordinates and an intensity value.
|
||||
#[derive(Clone, Debug, PartialEq, Copy, Default)]
|
||||
#[cfg_attr(feature = "derive", derive(TypeLayout))]
|
||||
#[repr(C)]
|
||||
pub struct PointXYZI {
|
||||
pub x: f32,
|
||||
|
|
@ -187,6 +189,17 @@ pub struct PointXYZI {
|
|||
pub intensity: f32,
|
||||
}
|
||||
|
||||
impl TypeLayout for PointXYZI {
|
||||
fn layout() -> LayoutDescription {
|
||||
LayoutDescription::new(&[
|
||||
LayoutField::new("x", "f32", 4),
|
||||
LayoutField::new("y", "f32", 4),
|
||||
LayoutField::new("z", "f32", 4),
|
||||
LayoutField::new("intensity", "f32", 4),
|
||||
])
|
||||
}
|
||||
}
|
||||
|
||||
impl PointXYZI {
|
||||
pub fn new(x: f32, y: f32, z: f32, intensity: f32) -> Self {
|
||||
Self { x, y, z, intensity }
|
||||
|
|
@ -237,7 +250,6 @@ impl PointConvertible<4> for PointXYZI {}
|
|||
/// Predefined point type commonly used in ROS with PCL.
|
||||
/// This is a 3D point with x, y, z coordinates and a label.
|
||||
#[derive(Clone, Debug, PartialEq, Copy, Default)]
|
||||
#[cfg_attr(feature = "derive", derive(TypeLayout))]
|
||||
#[repr(C)]
|
||||
pub struct PointXYZL {
|
||||
pub x: f32,
|
||||
|
|
@ -246,6 +258,17 @@ pub struct PointXYZL {
|
|||
pub label: u32,
|
||||
}
|
||||
|
||||
impl TypeLayout for PointXYZL {
|
||||
fn layout() -> LayoutDescription {
|
||||
LayoutDescription::new(&[
|
||||
LayoutField::new("x", "f32", 4),
|
||||
LayoutField::new("y", "f32", 4),
|
||||
LayoutField::new("z", "f32", 4),
|
||||
LayoutField::new("label", "u32", 4),
|
||||
])
|
||||
}
|
||||
}
|
||||
|
||||
impl PointXYZL {
|
||||
pub fn new(x: f32, y: f32, z: f32, label: u32) -> Self {
|
||||
Self { x, y, z, label }
|
||||
|
|
@ -296,7 +319,6 @@ impl PointConvertible<4> for PointXYZL {}
|
|||
/// Predefined point type commonly used in ROS with PCL.
|
||||
/// This is a 3D point with x, y, z coordinates and an RGB color value.
|
||||
#[derive(Clone, Debug, PartialEq, Copy, Default)]
|
||||
#[cfg_attr(feature = "derive", derive(TypeLayout))]
|
||||
#[repr(C)]
|
||||
pub struct PointXYZRGB {
|
||||
pub x: f32,
|
||||
|
|
@ -305,6 +327,17 @@ pub struct PointXYZRGB {
|
|||
pub rgb: RGB,
|
||||
}
|
||||
|
||||
impl TypeLayout for PointXYZRGB {
|
||||
fn layout() -> LayoutDescription {
|
||||
LayoutDescription::new(&[
|
||||
LayoutField::new("x", "f32", 4),
|
||||
LayoutField::new("y", "f32", 4),
|
||||
LayoutField::new("z", "f32", 4),
|
||||
LayoutField::new("rgb", "RGB", 4),
|
||||
])
|
||||
}
|
||||
}
|
||||
|
||||
impl PointXYZRGB {
|
||||
#[must_use]
|
||||
pub fn new(x: f32, y: f32, z: f32, r: u8, g: u8, b: u8) -> Self {
|
||||
|
|
@ -373,7 +406,6 @@ impl PointConvertible<4> for PointXYZRGB {}
|
|||
/// This is a 3D point with x, y, z coordinates and an RGBA color value.
|
||||
/// The alpha channel is commonly used as padding but this crate uses every channel and no padding.
|
||||
#[derive(Clone, Debug, PartialEq, Copy, Default)]
|
||||
#[cfg_attr(feature = "derive", derive(TypeLayout))]
|
||||
#[repr(C)]
|
||||
pub struct PointXYZRGBA {
|
||||
pub x: f32,
|
||||
|
|
@ -383,6 +415,19 @@ pub struct PointXYZRGBA {
|
|||
pub a: u8,
|
||||
}
|
||||
|
||||
impl TypeLayout for PointXYZRGBA {
|
||||
fn layout() -> LayoutDescription {
|
||||
LayoutDescription::new(&[
|
||||
LayoutField::new("x", "f32", 4),
|
||||
LayoutField::new("y", "f32", 4),
|
||||
LayoutField::new("z", "f32", 4),
|
||||
LayoutField::new("rgb", "RGB", 4),
|
||||
LayoutField::new("a", "u8", 1),
|
||||
LayoutField::padding(3),
|
||||
])
|
||||
}
|
||||
}
|
||||
|
||||
impl PointXYZRGBA {
|
||||
#[must_use]
|
||||
pub fn new(x: f32, y: f32, z: f32, r: u8, g: u8, b: u8, a: u8) -> Self {
|
||||
|
|
@ -452,7 +497,6 @@ impl PointConvertible<5> for PointXYZRGBA {}
|
|||
/// Predefined point type commonly used in ROS with PCL.
|
||||
/// This is a 3D point with x, y, z coordinates, an RGB color value and a normal vector.
|
||||
#[derive(Clone, Debug, PartialEq, Copy, Default)]
|
||||
#[cfg_attr(feature = "derive", derive(TypeLayout))]
|
||||
#[repr(C)]
|
||||
pub struct PointXYZRGBNormal {
|
||||
pub x: f32,
|
||||
|
|
@ -464,6 +508,20 @@ pub struct PointXYZRGBNormal {
|
|||
pub normal_z: f32,
|
||||
}
|
||||
|
||||
impl TypeLayout for PointXYZRGBNormal {
|
||||
fn layout() -> LayoutDescription {
|
||||
LayoutDescription::new(&[
|
||||
LayoutField::new("x", "f32", 4),
|
||||
LayoutField::new("y", "f32", 4),
|
||||
LayoutField::new("z", "f32", 4),
|
||||
LayoutField::new("rgb", "RGB", 4),
|
||||
LayoutField::new("normal_x", "f32", 4),
|
||||
LayoutField::new("normal_y", "f32", 4),
|
||||
LayoutField::new("normal_z", "f32", 4),
|
||||
])
|
||||
}
|
||||
}
|
||||
|
||||
impl PointXYZRGBNormal {
|
||||
#[must_use]
|
||||
pub fn new(
|
||||
|
|
@ -552,7 +610,6 @@ impl PointConvertible<7> for PointXYZRGBNormal {}
|
|||
/// Predefined point type commonly used in ROS with PCL.
|
||||
/// This is a 3D point with x, y, z coordinates, an intensity value and a normal vector.
|
||||
#[derive(Clone, Debug, PartialEq, Copy, Default)]
|
||||
#[cfg_attr(feature = "derive", derive(TypeLayout))]
|
||||
#[repr(C)]
|
||||
pub struct PointXYZINormal {
|
||||
pub x: f32,
|
||||
|
|
@ -564,6 +621,20 @@ pub struct PointXYZINormal {
|
|||
pub normal_z: f32,
|
||||
}
|
||||
|
||||
impl TypeLayout for PointXYZINormal {
|
||||
fn layout() -> LayoutDescription {
|
||||
LayoutDescription::new(&[
|
||||
LayoutField::new("x", "f32", 4),
|
||||
LayoutField::new("y", "f32", 4),
|
||||
LayoutField::new("z", "f32", 4),
|
||||
LayoutField::new("intensity", "f32", 4),
|
||||
LayoutField::new("normal_x", "f32", 4),
|
||||
LayoutField::new("normal_y", "f32", 4),
|
||||
LayoutField::new("normal_z", "f32", 4),
|
||||
])
|
||||
}
|
||||
}
|
||||
|
||||
impl PointXYZINormal {
|
||||
#[must_use]
|
||||
pub fn new(
|
||||
|
|
@ -637,7 +708,6 @@ impl PointConvertible<7> for PointXYZINormal {}
|
|||
/// Predefined point type commonly used in ROS with PCL.
|
||||
/// This is a 3D point with x, y, z coordinates and a label.
|
||||
#[derive(Clone, Debug, PartialEq, Copy, Default)]
|
||||
#[cfg_attr(feature = "derive", derive(TypeLayout))]
|
||||
#[repr(C)]
|
||||
pub struct PointXYZRGBL {
|
||||
pub x: f32,
|
||||
|
|
@ -647,6 +717,18 @@ pub struct PointXYZRGBL {
|
|||
pub label: u32,
|
||||
}
|
||||
|
||||
impl TypeLayout for PointXYZRGBL {
|
||||
fn layout() -> LayoutDescription {
|
||||
LayoutDescription::new(&[
|
||||
LayoutField::new("x", "f32", 4),
|
||||
LayoutField::new("y", "f32", 4),
|
||||
LayoutField::new("z", "f32", 4),
|
||||
LayoutField::new("rgb", "RGB", 4),
|
||||
LayoutField::new("label", "u32", 4),
|
||||
])
|
||||
}
|
||||
}
|
||||
|
||||
unsafe impl Send for PointXYZRGBL {}
|
||||
unsafe impl Sync for PointXYZRGBL {}
|
||||
|
||||
|
|
@ -722,7 +804,6 @@ impl PointConvertible<5> for PointXYZRGBL {}
|
|||
/// Predefined point type commonly used in ROS with PCL.
|
||||
/// This is a 3D point with x, y, z coordinates and a normal vector.
|
||||
#[derive(Clone, Debug, PartialEq, Copy, Default)]
|
||||
#[cfg_attr(feature = "derive", derive(TypeLayout))]
|
||||
#[repr(C)]
|
||||
pub struct PointXYZNormal {
|
||||
pub x: f32,
|
||||
|
|
@ -733,6 +814,19 @@ pub struct PointXYZNormal {
|
|||
pub normal_z: f32,
|
||||
}
|
||||
|
||||
impl TypeLayout for PointXYZNormal {
|
||||
fn layout() -> LayoutDescription {
|
||||
LayoutDescription::new(&[
|
||||
LayoutField::new("x", "f32", 4),
|
||||
LayoutField::new("y", "f32", 4),
|
||||
LayoutField::new("z", "f32", 4),
|
||||
LayoutField::new("normal_x", "f32", 4),
|
||||
LayoutField::new("normal_y", "f32", 4),
|
||||
LayoutField::new("normal_z", "f32", 4),
|
||||
])
|
||||
}
|
||||
}
|
||||
|
||||
impl PointXYZNormal {
|
||||
#[must_use]
|
||||
pub fn new(x: f32, y: f32, z: f32, normal_x: f32, normal_y: f32, normal_z: f32) -> Self {
|
||||
|
|
|
|||
|
|
@ -1,7 +1,7 @@
|
|||
//! Commonly used types and traits for predefined and custom point conversions.
|
||||
pub use crate::{
|
||||
FieldDatatype, Fields, FromBytes, GetFieldDatatype, MsgConversionError, PointCloud2Msg,
|
||||
PointConvertible, PointDataBuffer, RPCL2Point,
|
||||
FieldDatatype, Fields, FromBytes, GetFieldDatatype, LayoutDescription, LayoutField,
|
||||
MsgConversionError, PointCloud2Msg, PointConvertible, PointDataBuffer, RPCL2Point, TypeLayout,
|
||||
};
|
||||
|
||||
pub use crate::points::*;
|
||||
|
|
@ -10,8 +10,5 @@ pub use crate::ros::*;
|
|||
#[cfg(feature = "rayon")]
|
||||
pub use rayon::prelude::*;
|
||||
|
||||
#[cfg(feature = "derive")]
|
||||
pub use type_layout::TypeLayout;
|
||||
|
||||
#[cfg(feature = "derive")]
|
||||
pub use rpcl2_derive::*;
|
||||
|
|
|
|||
|
|
@ -9,7 +9,6 @@ macro_rules! convert_from_into {
|
|||
};
|
||||
}
|
||||
|
||||
#[cfg(feature = "derive")]
|
||||
macro_rules! convert_from_into_vec {
|
||||
($point:ty, $cloud:expr) => {
|
||||
convert_from_into_in_out_cloud_vec!($cloud, $point, $cloud, $point);
|
||||
|
|
@ -30,7 +29,6 @@ macro_rules! convert_from_into_in_out_cloud {
|
|||
};
|
||||
}
|
||||
|
||||
#[cfg(feature = "derive")]
|
||||
macro_rules! convert_from_into_in_out_cloud_vec {
|
||||
($in_cloud:expr, $in_point:ty, $out_cloud:expr, $out_point:ty) => {
|
||||
let msg = PointCloud2Msg::try_from_vec($in_cloud.clone());
|
||||
|
|
@ -59,7 +57,6 @@ fn write_cloud() {
|
|||
}
|
||||
|
||||
#[test]
|
||||
#[cfg(feature = "derive")]
|
||||
fn write_cloud_from_vec() {
|
||||
let cloud = vec![
|
||||
PointXYZ::new(0.0, 1.0, 5.0),
|
||||
|
|
@ -73,7 +70,6 @@ fn write_cloud_from_vec() {
|
|||
}
|
||||
|
||||
#[test]
|
||||
#[cfg(feature = "derive")]
|
||||
fn write_empty_cloud_vec() {
|
||||
let cloud: Vec<PointXYZ> = vec![];
|
||||
let msg = PointCloud2Msg::try_from_vec(cloud);
|
||||
|
|
@ -90,7 +86,7 @@ fn write_empty_cloud_iter() {
|
|||
}
|
||||
|
||||
#[test]
|
||||
#[cfg(all(feature = "derive", feature = "rayon"))]
|
||||
#[cfg(feature = "rayon")]
|
||||
fn conv_cloud_par_iter() {
|
||||
let cloud = vec![
|
||||
PointXYZ::new(0.0, 1.0, 5.0),
|
||||
|
|
@ -110,7 +106,7 @@ fn conv_cloud_par_iter() {
|
|||
}
|
||||
|
||||
#[test]
|
||||
#[cfg(all(feature = "derive", feature = "rayon"))]
|
||||
#[cfg(feature = "rayon")]
|
||||
fn conv_cloud_par_par_iter() {
|
||||
let cloud = vec![
|
||||
PointXYZ::new(0.0, 1.0, 5.0),
|
||||
|
|
@ -375,7 +371,6 @@ fn converterxyzrgb() {
|
|||
}
|
||||
|
||||
#[test]
|
||||
#[cfg(feature = "derive")]
|
||||
fn converterxyzrgb_from_vec() {
|
||||
convert_from_into_vec!(
|
||||
PointXYZRGB,
|
||||
|
|
@ -433,7 +428,6 @@ fn write_xyzi_read_xyz() {
|
|||
}
|
||||
|
||||
#[test]
|
||||
#[cfg(feature = "derive")]
|
||||
fn write_xyzi_read_xyz_vec() {
|
||||
let write_cloud = vec![
|
||||
PointXYZI::new(0.0, 1.0, 5.0, 0.0),
|
||||
|
|
@ -533,36 +527,3 @@ fn write_less_than_available() {
|
|||
|
||||
convert_from_into_in_out_cloud!(write_cloud, CustomPoint, read_cloud, CustomPoint);
|
||||
}
|
||||
|
||||
#[test]
|
||||
#[cfg(feature = "derive")]
|
||||
#[allow(unused_variables)]
|
||||
fn readme() {
|
||||
use ros_pointcloud2::prelude::*;
|
||||
|
||||
// PointXYZ (and many others) are provided by the crate.
|
||||
let cloud_points = vec![
|
||||
PointXYZI::new(91.486, -4.1, 42.0001, 0.1),
|
||||
PointXYZI::new(f32::MAX, f32::MIN, f32::MAX, f32::MIN),
|
||||
];
|
||||
|
||||
let out_msg = PointCloud2Msg::try_from_vec(cloud_points).unwrap();
|
||||
|
||||
// Convert the ROS crate message type, we will use r2r here.
|
||||
// let msg: r2r::sensor_msgs::msg::PointCloud2 = out_msg.into();
|
||||
// Publish ...
|
||||
// ... now incoming from a topic.
|
||||
// let in_msg: PointCloud2Msg = msg.into();
|
||||
let in_msg = out_msg;
|
||||
|
||||
let processed_cloud = in_msg
|
||||
.try_into_iter()
|
||||
.unwrap()
|
||||
.map(|point: PointXYZ| {
|
||||
// Define the info you want to have from the Msg.
|
||||
// Some logic here ...
|
||||
|
||||
point
|
||||
})
|
||||
.collect::<Vec<_>>();
|
||||
}
|
||||
|
|
|
|||
Loading…
Reference in New Issue