merge no_std

This commit is contained in:
stelzo 2024-05-15 18:42:45 +02:00
commit 756647e44f
17 changed files with 395 additions and 253 deletions

View File

@ -16,6 +16,6 @@ jobs:
tests_galactic:
runs-on: ubuntu-latest
steps:
- uses: actions/checkout@v2
- run: docker build . --file ./tests/Dockerfile_r2r_galactic --tag r2r_galactic
- run: docker run r2r_galactic cargo test --features r2r_msg,derive,nalgebra,rayon
- uses: actions/checkout@v2
- run: docker build . --file ./tests/Dockerfile_r2r_galactic --tag r2r_galactic
- run: docker run r2r_galactic cargo test --features r2r_msg,derive,nalgebra,rayon

View File

@ -16,6 +16,6 @@ jobs:
tests_humble:
runs-on: ubuntu-latest
steps:
- uses: actions/checkout@v2
- run: docker build . --file ./tests/Dockerfile_r2r_humble --tag r2r_humble
- run: docker run r2r_humble cargo test --features r2r_msg,derive,nalgebra,rayon
- uses: actions/checkout@v2
- run: docker build . --file ./tests/Dockerfile_r2r_humble --tag r2r_humble
- run: docker run r2r_humble cargo test --features r2r_msg,derive,nalgebra,rayon

View File

@ -16,6 +16,6 @@ jobs:
tests_humble:
runs-on: ubuntu-latest
steps:
- uses: actions/checkout@v2
- run: docker build . --file ./tests/Dockerfile_r2r_iron --tag r2r_iron
- run: docker run r2r_iron cargo test --features r2r_msg,derive,nalgebra,rayon
- uses: actions/checkout@v2
- run: docker build . --file ./tests/Dockerfile_r2r_iron --tag r2r_iron
- run: docker run r2r_iron cargo test --features r2r_msg,derive,nalgebra,rayon

View File

@ -16,6 +16,6 @@ jobs:
tests_humble:
runs-on: ubuntu-latest
steps:
- uses: actions/checkout@v2
- run: docker build . --file ./tests/Dockerfile_rclrs_humble --tag rclrs_humble
- run: docker run rclrs_humble cargo test --features derive,nalgebra,rayon
- uses: actions/checkout@v2
- run: docker build . --file ./tests/Dockerfile_rclrs_humble --tag rclrs_humble
- run: docker run rclrs_humble cargo test --features derive,nalgebra,rayon

View File

@ -16,6 +16,6 @@ jobs:
tests_iron:
runs-on: ubuntu-latest
steps:
- uses: actions/checkout@v2
- run: docker build . --file ./tests/Dockerfile_rclrs_iron --tag rclrs_iron
- run: docker run rclrs_iron cargo test --features derive,nalgebra,rayon
- uses: actions/checkout@v2
- run: docker build . --file ./tests/Dockerfile_rclrs_iron --tag rclrs_iron
- run: docker run rclrs_iron cargo test --features derive,nalgebra,rayon

View File

@ -13,11 +13,11 @@ jobs:
build:
runs-on: ubuntu-20.04
env:
ROS_CI_DESKTOP: "`lsb_release -cs`" # e.g. [trusty|xenial|...]
ROS_CI_DESKTOP: "`lsb_release -cs`" # e.g. [trusty|xenial|...]
# CI_SOURCE_PATH: $(pwd)
ROSINSTALL_FILE: $CI_SOURCE_PATH/dependencies.rosinstall
CATKIN_OPTIONS: $CI_SOURCE_PATH/catkin.options
ROS_PARALLEL_JOBS: '-j8 -l6'
ROS_PARALLEL_JOBS: "-j8 -l6"
# Set the python path manually to include /usr/-/python2.7/dist-packages
# as this is where apt-get installs python packages.
PYTHONPATH: $PYTHONPATH:/usr/lib/python2.7/dist-packages:/usr/local/lib/python2.7/dist-packages
@ -27,81 +27,81 @@ jobs:
uses: actions/checkout@v1
- name: Install latest rust
run: |
curl --proto '=https' --tlsv1.2 https://sh.rustup.rs -sSf | sh -s -- -y
rustc --version
cargo --version
curl --proto '=https' --tlsv1.2 https://sh.rustup.rs -sSf | sh -s -- -y
rustc --version
cargo --version
- name: Configure ROS for install
run: |
sudo sh -c "echo \"deb http://packages.ros.org/ros/ubuntu $ROS_CI_DESKTOP main\" > /etc/apt/sources.list.d/ros-latest.list"
sudo apt-key adv --keyserver 'hkp://keyserver.ubuntu.com:80' --recv-key C1CF6E31E6BADE8868B172B4F42ED6FBAB17C654
sudo apt-get update -qq
sudo apt-get install dpkg
sudo apt-get install -y libyaml-cpp-dev
sudo sh -c "echo \"deb http://packages.ros.org/ros/ubuntu $ROS_CI_DESKTOP main\" > /etc/apt/sources.list.d/ros-latest.list"
sudo apt-key adv --keyserver 'hkp://keyserver.ubuntu.com:80' --recv-key C1CF6E31E6BADE8868B172B4F42ED6FBAB17C654
sudo apt-get update -qq
sudo apt-get install dpkg
sudo apt-get install -y libyaml-cpp-dev
- name: Install ROS basic packages
run: |
sudo apt-get install -y python3-catkin-pkg
sudo apt-get install -y python3-catkin-tools
sudo apt-get install -y python3-rosdep
sudo apt-get install -y python3-wstool
sudo apt-get install -y python3-osrf-pycommon
sudo apt-get install -y ros-cmake-modules
sudo apt-get install -y ros-$ROS_DISTRO-ros-base
source /opt/ros/$ROS_DISTRO/setup.bash
sudo rosdep init
rosdep update # --include-eol-distros # Support EOL distros.
- name: Install ROS additional packages (TODO maybe don't need these)
sudo apt-get install -y python3-catkin-pkg
sudo apt-get install -y python3-catkin-tools
sudo apt-get install -y python3-rosdep
sudo apt-get install -y python3-wstool
sudo apt-get install -y python3-osrf-pycommon
sudo apt-get install -y ros-cmake-modules
sudo apt-get install -y ros-$ROS_DISTRO-ros-base
source /opt/ros/$ROS_DISTRO/setup.bash
sudo rosdep init
rosdep update # --include-eol-distros # Support EOL distros.
- name: Install ROS additional packages
# Does installing these mean rosrust_msg builds more messages, which is a better
# check? Or does it just slow down the action?
run: |
sudo apt-get install -y ros-$ROS_DISTRO-actionlib
sudo apt-get install -y ros-$ROS_DISTRO-actionlib-msgs
sudo apt-get install -y ros-$ROS_DISTRO-camera-info-manager
sudo apt-get install -y ros-$ROS_DISTRO-compressed-image-transport
sudo apt-get install -y ros-$ROS_DISTRO-catkin
sudo apt-get install -y ros-$ROS_DISTRO-class-loader
sudo apt-get install -y ros-$ROS_DISTRO-cmake-modules
sudo apt-get install -y ros-$ROS_DISTRO-cv-bridge
sudo apt-get install -y ros-$ROS_DISTRO-dynamic-reconfigure
sudo apt-get install -y ros-$ROS_DISTRO-ddynamic-reconfigure
# Not in noetic yet
# sudo apt-get install -y ros-$ROS_DISTRO-ddynamic-reconfigure-python
sudo apt-get install -y ros-$ROS_DISTRO-eigen-conversions
sudo apt-get install -y ros-$ROS_DISTRO-geometry-msgs
sudo apt-get install -y ros-$ROS_DISTRO-genmsg
sudo apt-get install -y ros-$ROS_DISTRO-image-geometry
sudo apt-get install -y ros-$ROS_DISTRO-image-proc
sudo apt-get install -y ros-$ROS_DISTRO-image-transport
sudo apt-get install -y ros-$ROS_DISTRO-message-generation
sudo apt-get install -y ros-$ROS_DISTRO-message-runtime
# sudo apt-get install -y ros-$ROS_DISTRO-nodelet-core
# sudo apt-get install -y ros-$ROS_DISTRO-nodelet-topic-tools
# sudo apt-get install -y ros-$ROS_DISTRO-pcl-conversions
# sudo apt-get install -y ros-$ROS_DISTRO-pcl-ros
sudo apt-get install -y ros-$ROS_DISTRO-pluginlib
sudo apt-get install -y ros-$ROS_DISTRO-roscpp
sudo apt-get install -y ros-$ROS_DISTRO-roslib
sudo apt-get install -y ros-$ROS_DISTRO-roslint
sudo apt-get install -y ros-$ROS_DISTRO-rospy
sudo apt-get install -y ros-$ROS_DISTRO-rospy-message-converter
sudo apt-get install -y ros-$ROS_DISTRO-rostest
sudo apt-get install -y ros-$ROS_DISTRO-sensor-msgs
sudo apt-get install -y ros-$ROS_DISTRO-std-msgs
sudo apt-get install -y ros-$ROS_DISTRO-tf
sudo apt-get install -y ros-$ROS_DISTRO-tf-conversions
sudo apt-get install -y ros-$ROS_DISTRO-tf2-geometry-msgs
sudo apt-get install -y ros-$ROS_DISTRO-tf2-msgs
sudo apt-get install -y ros-$ROS_DISTRO-tf2-py
sudo apt-get install -y ros-$ROS_DISTRO-tf2-ros
sudo apt-get install -y ros-$ROS_DISTRO-tf2-sensor-msgs
sudo apt-get install -y ros-$ROS_DISTRO-actionlib
sudo apt-get install -y ros-$ROS_DISTRO-actionlib-msgs
sudo apt-get install -y ros-$ROS_DISTRO-camera-info-manager
sudo apt-get install -y ros-$ROS_DISTRO-compressed-image-transport
sudo apt-get install -y ros-$ROS_DISTRO-catkin
sudo apt-get install -y ros-$ROS_DISTRO-class-loader
sudo apt-get install -y ros-$ROS_DISTRO-cmake-modules
sudo apt-get install -y ros-$ROS_DISTRO-cv-bridge
sudo apt-get install -y ros-$ROS_DISTRO-dynamic-reconfigure
sudo apt-get install -y ros-$ROS_DISTRO-ddynamic-reconfigure
# Not in noetic yet
# sudo apt-get install -y ros-$ROS_DISTRO-ddynamic-reconfigure-python
sudo apt-get install -y ros-$ROS_DISTRO-eigen-conversions
sudo apt-get install -y ros-$ROS_DISTRO-geometry-msgs
sudo apt-get install -y ros-$ROS_DISTRO-genmsg
sudo apt-get install -y ros-$ROS_DISTRO-image-geometry
sudo apt-get install -y ros-$ROS_DISTRO-image-proc
sudo apt-get install -y ros-$ROS_DISTRO-image-transport
sudo apt-get install -y ros-$ROS_DISTRO-message-generation
sudo apt-get install -y ros-$ROS_DISTRO-message-runtime
# sudo apt-get install -y ros-$ROS_DISTRO-nodelet-core
# sudo apt-get install -y ros-$ROS_DISTRO-nodelet-topic-tools
# sudo apt-get install -y ros-$ROS_DISTRO-pcl-conversions
# sudo apt-get install -y ros-$ROS_DISTRO-pcl-ros
sudo apt-get install -y ros-$ROS_DISTRO-pluginlib
sudo apt-get install -y ros-$ROS_DISTRO-roscpp
sudo apt-get install -y ros-$ROS_DISTRO-roslib
sudo apt-get install -y ros-$ROS_DISTRO-roslint
sudo apt-get install -y ros-$ROS_DISTRO-rospy
sudo apt-get install -y ros-$ROS_DISTRO-rospy-message-converter
sudo apt-get install -y ros-$ROS_DISTRO-rostest
sudo apt-get install -y ros-$ROS_DISTRO-sensor-msgs
sudo apt-get install -y ros-$ROS_DISTRO-std-msgs
sudo apt-get install -y ros-$ROS_DISTRO-tf
sudo apt-get install -y ros-$ROS_DISTRO-tf-conversions
sudo apt-get install -y ros-$ROS_DISTRO-tf2-geometry-msgs
sudo apt-get install -y ros-$ROS_DISTRO-tf2-msgs
sudo apt-get install -y ros-$ROS_DISTRO-tf2-py
sudo apt-get install -y ros-$ROS_DISTRO-tf2-ros
sudo apt-get install -y ros-$ROS_DISTRO-tf2-sensor-msgs
- name: build
run: |
source /opt/ros/$ROS_DISTRO/setup.bash
cargo build # --verbose
- name: Install ROS packages for tests
run: |
sudo apt-get install -y ros-$ROS_DISTRO-actionlib-tutorials
sudo apt-get install -y ros-$ROS_DISTRO-roscpp-tutorials
sudo apt-get install -y ros-$ROS_DISTRO-rospy-tutorials
sudo apt-get install -y ros-$ROS_DISTRO-actionlib-tutorials
sudo apt-get install -y ros-$ROS_DISTRO-roscpp-tutorials
sudo apt-get install -y ros-$ROS_DISTRO-rospy-tutorials
- name: test
run: |
source /opt/ros/$ROS_DISTRO/setup.bash

View File

@ -19,9 +19,9 @@ jobs:
- uses: actions/checkout@v2
- name: Install latest Rust
run: |
curl --proto '=https' --tlsv1.2 https://sh.rustup.rs -sSf | sh -s -- -y
rustc --version
cargo --version
curl --proto '=https' --tlsv1.2 https://sh.rustup.rs -sSf | sh -s -- -y
rustc --version
cargo --version
- name: Linting
run: cargo clippy --all-targets -- -D warnings
- name: Tests

View File

@ -26,6 +26,7 @@ exclude = [
"**/docs/**",
"**/doc/**",
]
rust-version = "1.63"
[dependencies]
rosrust_msg = { version = "0.1", optional = true }
@ -34,7 +35,7 @@ r2r = { version = "0.8.4", optional = true }
rayon = { version = "1", optional = true }
nalgebra = { version = "0", optional = true }
rpcl2_derive = { path = "./rpcl2_derive", optional = true }
type-layout = { version = "0.2", optional = true }
type-layout = { git = "https://github.com/stelzo/type-layout", branch = "syn2", optional = true }
sensor_msgs = { version = "*", optional = true }
std_msgs = { version = "*", optional = true }
@ -55,11 +56,10 @@ r2r_msg = ["dep:r2r"]
rayon = ["dep:rayon"]
derive = ["dep:rpcl2_derive", "dep:type-layout"]
nalgebra = ["dep:nalgebra"]
std = []
default = ["rclrs_msg"]
default = ["derive", "std", "rclrs_msg"]
[package.metadata.docs.rs]
features = ["derive", "nalgebra", "rayon"]
default-target = "x86_64-unknown-linux-gnu"
rclrs_msg = ["dep:sensor_msgs", "dep:std_msgs", "dep:builtin_interfaces"]

View File

@ -95,6 +95,10 @@ The results are measured on an Intel i7-14700 with benchmarks from [this reposit
For minimizing the conversion overhead in general, always use the functions that best fit your use case.
## `#[no_std]`
The `_iter` conversions are compatible with `#[no_std]` environments when an allocator is provided. This is due to the fact that names for point fields do not have a maximum length, and PointCloud2 data vectors can have arbitrary sizes. Use `default-features = false` to disable std for this crate.
## License
[MIT](https://choosealicense.com/licenses/mit/)

View File

@ -7,6 +7,6 @@ edition = "2021"
proc-macro = true
[dependencies]
syn = "1"
quote = "1"
proc-macro2 = "1"
syn = "2.0"
quote = "1.0"
proc-macro2 = "1.0"

View File

@ -4,7 +4,7 @@ use std::collections::HashMap;
use proc_macro::TokenStream;
use quote::{quote, ToTokens};
use syn::{parse_macro_input, DeriveInput};
use syn::{parenthesized, parse_macro_input, DeriveInput, LitStr};
fn get_allowed_types() -> HashMap<&'static str, usize> {
let mut allowed_datatypes = HashMap::<&'static str, usize>::new();
@ -19,28 +19,6 @@ fn get_allowed_types() -> HashMap<&'static str, usize> {
allowed_datatypes
}
// Given a field, get the value of the `rpcl2` renaming attribute like
// #[rpcl2(name = "new_name")]
fn get_ros_fields_attribute(attrs: &[syn::Attribute]) -> Option<syn::Lit> {
for attr in attrs {
if attr.path.is_ident("rpcl2") {
let meta = attr.parse_meta().unwrap();
if let syn::Meta::List(meta_list) = meta {
for nested_meta in meta_list.nested {
if let syn::NestedMeta::Meta(meta) = nested_meta {
if let syn::Meta::NameValue(meta_name_value) = meta {
if meta_name_value.path.is_ident("name") {
return Some(meta_name_value.lit);
}
}
}
}
}
}
}
None
}
fn struct_field_rename_array(input: &DeriveInput) -> Vec<String> {
let fields = match input.data {
syn::Data::Struct(ref data) => match data.fields {
@ -50,31 +28,39 @@ fn struct_field_rename_array(input: &DeriveInput) -> Vec<String> {
_ => panic!("StructNames can only be derived for structs"),
};
fields
.iter()
.map(|field| {
let field_name = field.ident.as_ref().unwrap();
let ros_fields_attr = get_ros_fields_attribute(&field.attrs);
match ros_fields_attr {
Some(ros_fields) => match ros_fields {
syn::Lit::Str(lit_str) => {
let val = lit_str.value();
if val.is_empty() {
panic!("Empty string literals are not allowed for the rpcl2 attribute");
let mut field_names = Vec::with_capacity(fields.len());
for f in fields.iter() {
if f.attrs.len() == 0 {
field_names.push(f.ident.as_ref().unwrap().to_token_stream().to_string());
} else {
f.attrs.iter().for_each(|attr| {
if attr.path().is_ident("rpcl2") {
let res = attr.parse_nested_meta(|meta| {
if meta.path.is_ident("rename") {
let new_name;
parenthesized!(new_name in meta.input);
let lit: LitStr = new_name.parse()?;
field_names.push(lit.value());
Ok(())
} else {
panic!("expected `name` attribute");
}
val
});
if let Err(err) = res {
panic!("Error parsing attribute: {}", err);
}
_ => {
panic!("Only string literals are allowed for the rpcl2 attribute")
}
},
None => String::from(field_name.to_token_stream().to_string()),
}
})
.collect()
}
});
}
}
field_names
}
/// This macro will implement the `Fields` trait for your struct so you can use your point for the PointCloud2 conversion.
/// This macro implements the `Fields` trait which is a subset of the `PointConvertible` trait.
/// It is useful for points that convert the `From` trait themselves but want to use this macro for not repeating the field names.
///
/// You can rename the fields with the `rename` attribute.
///
/// Use the rename attribute if your struct field name should be different to the ROS field name.
#[proc_macro_derive(Fields, attributes(rpcl2))]
@ -104,11 +90,14 @@ pub fn ros_point_fields_derive(input: TokenStream) -> TokenStream {
expanded.into()
}
/// This macro will fully implement the `PointConvertible` trait for your struct so you can use your point for the PointCloud2 conversion.
/// This macro implements the `PointConvertible` trait for your struct so you can use your point for the PointCloud2 conversion.
///
/// The struct field names are used in the message if you do not use the `rename` attribute for a custom name.
///
/// Note that the repr(C) attribute is required for the struct to work efficiently with C++ PCL.
/// With Rust layout optimizations, the struct might not work with the PCL library but the message still conforms to the description of PointCloud2.
/// Furthermore, Rust layout can lead to smaller messages to be send over the network.
///
#[proc_macro_derive(PointConvertible, attributes(rpcl2))]
pub fn ros_point_derive(input: TokenStream) -> TokenStream {
let input = parse_macro_input!(input as DeriveInput);

View File

@ -1,10 +1,19 @@
//! Iterator implementations for PointCloud2Msg including a parallel iterator for rayon.
//! Iterator implementations for [`PointCloud2Msg`] including a parallel iterator for rayon.
use crate::{
Endian, FieldDatatype, Fields, MsgConversionError, PointCloud2Msg, PointConvertible, PointData,
RPCL2Point,
};
/// The PointCloudIterator provides a an iterator abstraction of the PointCloud2Msg.
#[cfg(not(feature = "std"))]
use alloc::string::String;
#[cfg(not(feature = "std"))]
use alloc::vec::Vec;
#[cfg(not(feature = "std"))]
use alloc::borrow::ToOwned;
/// The PointCloudIterator provides a an iterator abstraction of the [`PointCloud2Msg`].
///
/// The iterator is defined at compile time, so the point has to be described via template arguments.
///
@ -19,7 +28,7 @@ use crate::{
/// let msg: r2r::sensor_msgs::msg::PointCloud2 = internal_msg.into();
/// let converted: ros_pointcloud2::PointCloud2Msg = msg.into();
///
/// ros_pointcloud2 supports r2r, rclrs and rosrust as conversion targets out of the box via feature flags.
/// `ros_pointcloud2` supports r2r, rclrs and rosrust as conversion targets out of the box via feature flags.
///
pub struct PointCloudIterator<const N: usize, C>
where
@ -28,7 +37,7 @@ where
iteration: usize,
iteration_back: usize,
data: ByteBufferView<N>,
phantom_c: std::marker::PhantomData<C>, // internally used for meta names array
phantom_c: core::marker::PhantomData<C>, // internally used for pdata names array
}
#[cfg(feature = "rayon")]
@ -133,7 +142,6 @@ where
}
}
/// Implementation of the iterator trait.
impl<const N: usize, C> Iterator for PointCloudIterator<N, C>
where
C: PointConvertible<N>,
@ -157,12 +165,15 @@ where
}
struct ByteBufferView<const N: usize> {
#[cfg(feature = "rayon")]
data: std::sync::Arc<[u8]>,
#[cfg(not(feature = "rayon"))]
data: Vec<u8>,
start_point_idx: usize,
end_point_idx: usize,
point_step_size: usize,
offsets: [usize; N],
meta: Vec<(String, FieldDatatype)>,
pdata: Vec<(String, FieldDatatype)>,
endian: Endian,
}
@ -173,16 +184,19 @@ impl<const N: usize> ByteBufferView<N> {
start_point_idx: usize,
end_point_idx: usize,
offsets: [usize; N],
meta: Vec<(String, FieldDatatype)>,
pdata: Vec<(String, FieldDatatype)>,
endian: Endian,
) -> Self {
Self {
#[cfg(feature = "rayon")]
data: std::sync::Arc::<[u8]>::from(data),
#[cfg(not(feature = "rayon"))]
data,
start_point_idx,
end_point_idx,
point_step_size,
offsets,
meta,
pdata,
endian,
}
}
@ -192,25 +206,24 @@ impl<const N: usize> ByteBufferView<N> {
self.end_point_idx - self.start_point_idx + 1
}
#[inline(always)]
#[inline]
fn point_at(&self, idx: usize) -> RPCL2Point<N> {
let offset = (self.start_point_idx + idx) * self.point_step_size;
// TODO memcpy entire point at once, then extract fields?
let mut meta = [PointData::default(); N];
meta.iter_mut()
let mut pdata = [PointData::default(); N];
pdata
.iter_mut()
.zip(self.offsets.iter())
.zip(self.meta.iter())
.for_each(|((p_meta, in_point_offset), (_, meta_type))| {
*p_meta = PointData::from_buffer(
.zip(self.pdata.iter())
.for_each(|((pdata_entry, in_point_offset), (_, pdata_type))| {
*pdata_entry = PointData::from_buffer(
&self.data,
offset + in_point_offset,
*meta_type,
*pdata_type,
self.endian,
);
});
RPCL2Point { fields: meta }
pdata.into()
}
#[inline]
@ -221,7 +234,7 @@ impl<const N: usize> ByteBufferView<N> {
end_point_idx: start + size - 1,
point_step_size: self.point_step_size,
offsets: self.offsets,
meta: self.meta.clone(),
pdata: self.pdata.clone(),
endian: self.endian,
}
}
@ -231,9 +244,8 @@ impl<const N: usize> ByteBufferView<N> {
let left_start = self.start_point_idx;
let left_size = point_index;
let right_start = point_index;
let right_start = self.start_point_idx + point_index;
let right_size = self.len() - point_index;
(
self.clone_with_bounds(left_start, left_size),
self.clone_with_bounds(right_start, right_size),
@ -247,13 +259,13 @@ where
{
type Error = MsgConversionError;
/// Convert a PointCloud2Msg into an iterator.
/// Converting a PointCloud2Msg into an iterator is a fallible operation since the message can contain only a subset of the required fields.
/// Convert a [`PointCloud2Msg`] into an iterator.
/// The conversion to an iterator is a fallible operation since the message could contain a subset of the required fields.
///
/// The theoretical time complexity is O(n) where n is the number of fields defined in the message for a single point which is typically small.
/// It therefore has a constant time complexity O(1) for practical purposes.
fn try_from(cloud: PointCloud2Msg) -> Result<Self, Self::Error> {
let mut meta_with_offsets = vec![(String::default(), FieldDatatype::default(), 0); N];
let mut pdata_with_offsets = vec![(String::default(), FieldDatatype::default(), 0); N];
let not_found_fieldnames = C::field_names_ordered()
.into_iter()
@ -273,7 +285,7 @@ where
}
let ordered_fieldnames = C::field_names_ordered();
for (field, with_offset) in cloud.fields.iter().zip(meta_with_offsets.iter_mut()) {
for (field, with_offset) in cloud.fields.iter().zip(pdata_with_offsets.iter_mut()) {
if ordered_fieldnames.contains(&field.name.as_str()) {
*with_offset = (
field.name.clone(),
@ -283,25 +295,26 @@ where
}
}
meta_with_offsets.sort_unstable_by(|(_, _, offset1), (_, _, offset2)| offset1.cmp(offset2));
pdata_with_offsets
.sort_unstable_by(|(_, _, offset1), (_, _, offset2)| offset1.cmp(offset2));
debug_assert!(
meta_with_offsets.len() == N,
pdata_with_offsets.len() == N,
"Not all fields were found in the message. Expected {} but found {}.",
N,
meta_with_offsets.len()
pdata_with_offsets.len()
);
let mut offsets = [usize::default(); N];
let mut meta = vec![(String::default(), FieldDatatype::default()); N];
let mut pdata = vec![(String::default(), FieldDatatype::default()); N];
meta_with_offsets
pdata_with_offsets
.into_iter()
.zip(meta.iter_mut())
.zip(pdata.iter_mut())
.zip(offsets.iter_mut())
.for_each(|(((name, datatype, offset), meta), meta_offset)| {
*meta = (name, datatype);
*meta_offset = offset;
.for_each(|(((name, datatype, offset), pdata), pdata_offset)| {
*pdata = (name, datatype);
*pdata_offset = offset;
});
let point_step_size = cloud.point_step as usize;
@ -312,9 +325,9 @@ where
let last_offset = offsets.last().expect("Dimensionality is 0.");
let last_meta = meta.last().expect("Dimensionality is 0.");
let size_with_last_meta = last_offset + last_meta.1.size();
if size_with_last_meta > point_step_size {
let last_pdata = pdata.last().expect("Dimensionality is 0.");
let size_with_last_pdata = last_offset + last_pdata.1.size();
if size_with_last_pdata > point_step_size {
return Err(MsgConversionError::DataLengthMismatch);
}
@ -326,7 +339,7 @@ where
0,
cloud_length - 1,
offsets,
meta,
pdata,
cloud.endian,
);
@ -334,7 +347,7 @@ where
iteration: 0,
iteration_back: cloud_length - 1,
data,
phantom_c: std::marker::PhantomData,
phantom_c: core::marker::PhantomData,
})
}
}
@ -344,16 +357,18 @@ where
C: Fields<N>,
{
#[inline]
#[must_use]
fn from_byte_buffer_view(data: ByteBufferView<N>) -> Self {
Self {
iteration: 0,
iteration_back: data.len() - 1,
data,
phantom_c: std::marker::PhantomData,
phantom_c: core::marker::PhantomData,
}
}
#[inline]
#[must_use]
pub fn split_at(self, point_index: usize) -> (Self, Self) {
let (left_data, right_data) = self.data.split_at(point_index);
(

View File

@ -72,7 +72,7 @@
//! pub x: f32,
//! pub y: f32,
//! pub z: f32,
//! #[cfg_attr(feature = "derive", rpcl2(name = "i"))]
//! #[cfg_attr(feature = "derive", rpcl2(rename("i")))]
//! pub intensity: f32,
//! }
//!
@ -121,14 +121,21 @@
//! pub x: f32,
//! pub y: f32,
//! pub z: f32,
//! #[rpcl2(name = "i")]
//! #[rpcl2(rename("i"))]
//! pub intensity: f32,
//! }
//! ```
#![crate_type = "lib"]
#![warn(clippy::print_stderr)]
#![warn(clippy::print_stdout)]
#![warn(clippy::unwrap_used)]
#![warn(clippy::cargo)]
#![warn(clippy::std_instead_of_core)]
#![warn(clippy::alloc_instead_of_core)]
#![warn(clippy::std_instead_of_alloc)]
#![cfg_attr(not(feature = "std"), no_std)]
// Setup an allocator with #[global_allocator]
// see: https://doc.rust-lang.org/std/alloc/trait.GlobalAlloc.html
pub mod points;
pub mod prelude;
@ -136,46 +143,65 @@ pub mod ros;
pub mod iterator;
use std::num::TryFromIntError;
use std::str::FromStr;
use crate::ros::{HeaderMsg, PointFieldMsg};
use core::str::FromStr;
#[cfg(not(feature = "std"))]
#[macro_use]
extern crate alloc;
#[cfg(not(feature = "std"))]
use alloc::string::String;
#[cfg(not(feature = "std"))]
use alloc::vec::Vec;
/// All errors that can occur while converting to or from the message type.
#[derive(Debug)]
pub enum MsgConversionError {
InvalidFieldFormat,
#[cfg(feature = "std")]
UnsupportedFieldType(String),
#[cfg(not(feature = "std"))]
UnsupportedFieldType,
DataLengthMismatch,
FieldsNotFound(Vec<String>),
UnsupportedFieldCount,
NumberConversion,
}
impl From<TryFromIntError> for MsgConversionError {
fn from(_: TryFromIntError) -> Self {
impl From<core::num::TryFromIntError> for MsgConversionError {
fn from(_: core::num::TryFromIntError) -> Self {
MsgConversionError::NumberConversion
}
}
impl std::fmt::Display for MsgConversionError {
fn fmt(&self, f: &mut std::fmt::Formatter<'_>) -> std::fmt::Result {
impl core::fmt::Display for MsgConversionError {
fn fmt(&self, f: &mut core::fmt::Formatter<'_>) -> core::fmt::Result {
match self {
MsgConversionError::InvalidFieldFormat => {
write!(f, "The field does not match the expected datatype.")
}
#[cfg(feature = "std")]
MsgConversionError::UnsupportedFieldType(datatype) => {
write!(
f,
"The field datatype is not supported by the ROS message description: {}",
datatype
"The field datatype is not supported by the ROS message description: {datatype}"
)
}
#[cfg(not(feature = "std"))]
MsgConversionError::UnsupportedFieldType => {
write!(
f,
"There is an unsupported field type in the ROS message description."
)
}
MsgConversionError::DataLengthMismatch => {
write!(f, "The length of the byte buffer in the message does not match the expected length computed from the fields, indicating a corrupted or malformed message.")
}
MsgConversionError::FieldsNotFound(fields) => {
write!(f, "Some fields are not found in the message: {:?}", fields)
write!(f, "Some fields are not found in the message: {fields:?}")
}
MsgConversionError::UnsupportedFieldCount => {
write!(
@ -190,6 +216,7 @@ impl std::fmt::Display for MsgConversionError {
}
}
#[cfg(feature = "std")]
impl std::error::Error for MsgConversionError {
fn source(&self) -> Option<&(dyn std::error::Error + 'static)> {
None
@ -246,11 +273,12 @@ enum ByteSimilarity {
Different,
}
/// Creating a CloudDimensions type with the builder pattern to avoid invalid states when using 1-row point clouds.
/// Creating a [`CloudDimensions`] type with the builder pattern to avoid invalid states when using 1-row point clouds.
#[derive(Clone, Debug)]
pub struct CloudDimensionsBuilder(usize);
impl CloudDimensionsBuilder {
#[must_use]
pub fn new_with_width(width: usize) -> Self {
Self(width)
}
@ -263,12 +291,12 @@ impl CloudDimensionsBuilder {
Ok(CloudDimensions {
width,
height: if self.0 > 0 { 1 } else { 0 },
height: u32::from(self.0 > 0),
})
}
}
/// Creating a PointCloud2Msg with the builder pattern to avoid invalid states.
/// Creating a [`PointCloud2Msg`] with the builder pattern to avoid invalid states.
#[derive(Clone, Debug, Default)]
pub struct PointCloud2MsgBuilder {
header: HeaderMsg,
@ -282,50 +310,63 @@ pub struct PointCloud2MsgBuilder {
}
impl PointCloud2MsgBuilder {
#[must_use]
pub fn new() -> Self {
Self::default()
}
#[must_use]
pub fn header(mut self, header: HeaderMsg) -> Self {
self.header = header;
self
}
#[must_use]
pub fn width(mut self, width: u32) -> Self {
self.width = width;
self
}
#[must_use]
pub fn fields(mut self, fields: Vec<PointFieldMsg>) -> Self {
self.fields = fields;
self
}
#[must_use]
pub fn endian(mut self, is_big_endian: bool) -> Self {
self.is_big_endian = is_big_endian;
self
}
#[must_use]
pub fn point_step(mut self, point_step: u32) -> Self {
self.point_step = point_step;
self
}
#[must_use]
pub fn row_step(mut self, row_step: u32) -> Self {
self.row_step = row_step;
self
}
#[must_use]
pub fn data(mut self, data: Vec<u8>) -> Self {
self.data = data;
self
}
#[must_use]
pub fn dense(mut self, is_dense: bool) -> Self {
self.is_dense = is_dense;
self
}
/// Build the [`PointCloud2Msg`] from the builder.
///
/// # Errors
/// Returns an error if the fields are empty, the field count is not 1, the field format is invalid, the data length does not match the point step, or the field size is too large.
pub fn build(self) -> Result<PointCloud2Msg, MsgConversionError> {
if self.fields.is_empty() {
return Err(MsgConversionError::FieldsNotFound(vec![]));
@ -382,7 +423,7 @@ pub struct CloudDimensions {
impl PointCloud2Msg {
#[cfg(feature = "derive")]
#[inline(always)]
#[inline]
fn byte_similarity<const N: usize, C>(&self) -> Result<ByteSimilarity, MsgConversionError>
where
C: PointConvertible<N>,
@ -405,7 +446,8 @@ impl PointCloud2Msg {
size,
count,
} => {
let f_translated = field_names[field_counter].to_string();
let f_translated = String::from_str(field_names[field_counter])
.expect("Field name is not a valid string.");
field_counter += 1;
if msg_f.name != f_translated
@ -431,7 +473,7 @@ impl PointCloud2Msg {
})
}
/// Create a PointCloud2Msg from any iterable type.
/// Create a [`PointCloud2Msg`] from any iterable type.
///
/// # Example
/// ```
@ -457,33 +499,33 @@ impl PointCloud2Msg {
let field_names = C::field_names_ordered();
debug_assert!(field_names.len() == N);
let mut meta_offsets_acc: u32 = 0;
let mut pdata_offsets_acc: u32 = 0;
let mut fields = vec![PointFieldMsg::default(); N];
let field_count: u32 = 1;
for ((meta_value, field_name), field_val) in point
for ((pdata_entry, field_name), field_val) in point
.fields
.into_iter()
.zip(field_names.into_iter())
.zip(fields.iter_mut())
{
let datatype_code = meta_value.datatype.into();
let datatype_code = pdata_entry.datatype.into();
let _ = FieldDatatype::try_from(datatype_code)?;
*field_val = PointFieldMsg {
name: field_name.into(),
offset: meta_offsets_acc,
offset: pdata_offsets_acc,
datatype: datatype_code,
count: 1,
};
meta_offsets_acc += field_count * meta_value.datatype.size() as u32;
pdata_offsets_acc += field_count * pdata_entry.datatype.size() as u32;
}
(
PointCloud2MsgBuilder::new()
.fields(fields)
.point_step(meta_offsets_acc),
meta_offsets_acc,
.point_step(pdata_offsets_acc),
pdata_offsets_acc,
)
};
let mut cloud_width = 0;
@ -491,9 +533,9 @@ impl PointCloud2Msg {
iterable.into_iter().for_each(|pointdata| {
let point: RPCL2Point<N> = pointdata.into();
point.fields.iter().for_each(|meta| {
point.fields.iter().for_each(|pdata| {
let truncated_bytes = unsafe {
std::slice::from_raw_parts(meta.bytes.as_ptr(), meta.datatype.size())
core::slice::from_raw_parts(pdata.bytes.as_ptr(), pdata.datatype.size())
};
cloud.data.extend_from_slice(truncated_bytes);
});
@ -518,7 +560,7 @@ impl PointCloud2Msg {
Self::try_from_vec(iterable.collect::<Vec<_>>())
}
/// Create a PointCloud2Msg from a Vec of points.
/// Create a [`PointCloud2Msg`] from a Vec of points.
/// Since the point type is known at compile time, the conversion is done by direct copy.
///
/// # Example
@ -532,6 +574,9 @@ impl PointCloud2Msg {
///
/// let msg_out = PointCloud2Msg::try_from_vec(cloud_points).unwrap();
/// ```
///
/// # Errors
/// Returns an error if the byte buffer does not match the expected layout or the message contains other discrepancies.
#[cfg(feature = "derive")]
pub fn try_from_vec<const N: usize, C>(vec: Vec<C>) -> Result<Self, MsgConversionError>
where
@ -552,7 +597,8 @@ impl PointCloud2Msg {
let mut offset = 0;
let mut fields: Vec<PointFieldMsg> = Vec::with_capacity(layout.fields.len());
for f in layout.fields.into_iter() {
let f_translated = field_names[fields.len()].to_string();
let f_translated = String::from_str(field_names[fields.len()])
.expect("Field name is not a valid string.");
match f {
PointField::Field {
datatype,
@ -585,9 +631,9 @@ impl PointCloud2Msg {
cloud.data.resize(bytes_total, u8::default());
let raw_data: *mut C = cloud.data.as_ptr() as *mut C;
unsafe {
std::ptr::copy_nonoverlapping(
vec.as_ptr() as *const u8,
raw_data as *mut u8,
core::ptr::copy_nonoverlapping(
vec.as_ptr().cast::<u8>(),
raw_data.cast::<u8>(),
bytes_total,
);
}
@ -601,7 +647,7 @@ impl PointCloud2Msg {
}
}
/// Convert the PointCloud2Msg to a Vec of points.
/// Convert the [`PointCloud2Msg`] to a Vec of points.
///
/// # Example
/// ```
@ -616,6 +662,9 @@ impl PointCloud2Msg {
/// let cloud_points_out: Vec<PointXYZ> = msg_out.try_into_vec().unwrap();
/// assert_eq!(1.0, cloud_points_out.get(0).unwrap().x);
/// ```
///
/// # Errors
/// Returns an error if the byte buffer does not match the expected layout or the message contains other discrepancies.
#[cfg(feature = "derive")]
pub fn try_into_vec<const N: usize, C>(self) -> Result<Vec<C>, MsgConversionError>
where
@ -631,12 +680,12 @@ impl PointCloud2Msg {
let cloud_width = self.dimensions.width as usize;
let point_step = self.point_step as usize;
let mut vec = Vec::with_capacity(cloud_width);
let mut vec: Vec<C> = Vec::with_capacity(cloud_width);
if bytematch {
unsafe {
std::ptr::copy_nonoverlapping(
core::ptr::copy_nonoverlapping(
self.data.as_ptr(),
vec.as_mut_ptr() as *mut u8,
vec.as_mut_ptr().cast::<u8>(),
self.data.len(),
);
vec.set_len(cloud_width);
@ -644,7 +693,7 @@ impl PointCloud2Msg {
} else {
unsafe {
for i in 0..cloud_width {
let point_ptr = self.data.as_ptr().add(i * point_step) as *const C;
let point_ptr = self.data.as_ptr().add(i * point_step).cast::<C>();
let point = point_ptr.read();
vec.push(point);
}
@ -657,7 +706,7 @@ impl PointCloud2Msg {
}
}
/// Convert the PointCloud2Msg to an iterator.
/// Convert the [`PointCloud2Msg`] to an iterator.
///
/// # Example
/// ```
@ -671,6 +720,8 @@ impl PointCloud2Msg {
/// let msg_out = PointCloud2Msg::try_from_iter(cloud_points).unwrap();
/// let cloud_points_out = msg_out.try_into_iter().unwrap().collect::<Vec<PointXYZ>>();
/// ```
/// # Errors
/// Returns an error if the byte buffer does not match the expected layout or the message contains other discrepancies.
pub fn try_into_iter<const N: usize, C>(
self,
) -> Result<impl Iterator<Item = C>, MsgConversionError>
@ -706,7 +757,7 @@ impl PointCloud2Msg {
}
}
/// Internal point representation. It is used to store the coordinates and meta data of a point.
/// Internal point representation. It is used to store the point data entries.
///
/// In each iteration, an internal point representation is converted to the desired point type.
/// Implement the `From` traits for your point type to use the conversion.
@ -724,7 +775,7 @@ impl<const N: usize> Default for RPCL2Point<N> {
}
}
impl<const N: usize> std::ops::Index<usize> for RPCL2Point<N> {
impl<const N: usize> core::ops::Index<usize> for RPCL2Point<N> {
type Output = PointData;
fn index(&self, index: usize) -> &Self::Output {
@ -779,7 +830,7 @@ impl<const N: usize> From<[PointData; N]> for RPCL2Point<N> {
/// ```
#[cfg(not(feature = "derive"))]
pub trait PointConvertible<const N: usize>:
From<RPCL2Point<N>> + Into<RPCL2Point<N>> + Fields<N> + Clone + 'static + Default
From<RPCL2Point<N>> + Into<RPCL2Point<N>> + Fields<N> + Clone + Default
{
}
@ -840,7 +891,7 @@ pub trait PointConvertible<const N: usize>:
/// ```
#[cfg(feature = "derive")]
pub trait PointConvertible<const N: usize>:
type_layout::TypeLayout + From<RPCL2Point<N>> + Into<RPCL2Point<N>> + Fields<N> + 'static + Default
type_layout::TypeLayout + From<RPCL2Point<N>> + Into<RPCL2Point<N>> + Fields<N> + Default
{
}
@ -926,12 +977,12 @@ impl TryFrom<type_layout::TypeLayoutInfo> for TypeLayoutInfo {
/// use ros_pointcloud2::PointData;
///
/// let original_data: f64 = 1.0;
/// let meta = PointData::new(original_data);
/// let my_data: f64 = meta.get();
/// let pdata = PointData::new(original_data);
/// let my_data: f64 = pdata.get();
/// ```
#[derive(Debug, Clone, Copy)]
pub struct PointData {
bytes: [u8; std::mem::size_of::<f64>()],
bytes: [u8; core::mem::size_of::<f64>()],
endian: Endian,
datatype: FieldDatatype,
}
@ -939,7 +990,7 @@ pub struct PointData {
impl Default for PointData {
fn default() -> Self {
Self {
bytes: [u8::default(); std::mem::size_of::<f64>()],
bytes: [u8::default(); core::mem::size_of::<f64>()],
datatype: FieldDatatype::F32,
endian: Endian::default(),
}
@ -947,13 +998,13 @@ impl Default for PointData {
}
impl PointData {
/// Create a new PointData from a value.
/// Create a new [`PointData`] from a value.
///
/// # Example
/// ```
/// let meta = ros_pointcloud2::PointData::new(1.0);
/// let pdata = ros_pointcloud2::PointData::new(1.0);
/// ```
#[inline(always)]
#[inline]
pub fn new<T: FromBytes>(value: T) -> Self {
Self {
bytes: value.into().raw(),
@ -962,31 +1013,32 @@ impl PointData {
}
}
#[inline(always)]
#[inline]
fn from_buffer(data: &[u8], offset: usize, datatype: FieldDatatype, endian: Endian) -> Self {
debug_assert!(data.len() >= offset + datatype.size());
let bytes = [u8::default(); std::mem::size_of::<f64>()];
let bytes = [u8::default(); core::mem::size_of::<f64>()];
unsafe {
let data_ptr = data.as_ptr().add(offset);
let bytes_ptr = bytes.as_ptr() as *mut u8;
std::ptr::copy_nonoverlapping(data_ptr, bytes_ptr, datatype.size());
core::ptr::copy_nonoverlapping(data_ptr, bytes_ptr, datatype.size());
}
Self {
bytes,
datatype,
endian,
datatype,
}
}
/// Get the numeric value from the PointData description.
/// Get the numeric value from the [`PointData`] description.
///
/// # Example
/// ```
/// let original_data: f64 = 1.0;
/// let meta = ros_pointcloud2::PointData::new(original_data);
/// let my_data: f64 = meta.get();
/// let pdata = ros_pointcloud2::PointData::new(original_data);
/// let my_data: f64 = pdata.get();
/// ```
#[must_use]
pub fn get<T: FromBytes>(&self) -> T {
match self.endian {
Endian::Big => T::from_be_bytes(PointDataBuffer::new(self.bytes)),
@ -1062,22 +1114,22 @@ pub enum FieldDatatype {
}
impl FieldDatatype {
#[must_use]
pub fn size(&self) -> usize {
match self {
FieldDatatype::U8 => std::mem::size_of::<u8>(),
FieldDatatype::U16 => std::mem::size_of::<u16>(),
FieldDatatype::U32 => std::mem::size_of::<u32>(),
FieldDatatype::I8 => std::mem::size_of::<i8>(),
FieldDatatype::I16 => std::mem::size_of::<i16>(),
FieldDatatype::I32 => std::mem::size_of::<i32>(),
FieldDatatype::F32 => std::mem::size_of::<f32>(),
FieldDatatype::F64 => std::mem::size_of::<f64>(),
FieldDatatype::RGB => std::mem::size_of::<f32>(), // packed in f32
FieldDatatype::U8 => core::mem::size_of::<u8>(),
FieldDatatype::U16 => core::mem::size_of::<u16>(),
FieldDatatype::U32 => core::mem::size_of::<u32>(),
FieldDatatype::I8 => core::mem::size_of::<i8>(),
FieldDatatype::I16 => core::mem::size_of::<i16>(),
FieldDatatype::I32 => core::mem::size_of::<i32>(),
FieldDatatype::F32 | FieldDatatype::RGB => core::mem::size_of::<f32>(), // packed in f32
FieldDatatype::F64 => core::mem::size_of::<f64>(),
}
}
}
impl FromStr for FieldDatatype {
impl core::str::FromStr for FieldDatatype {
type Err = MsgConversionError;
fn from_str(s: &str) -> Result<Self, Self::Err> {
@ -1091,7 +1143,10 @@ impl FromStr for FieldDatatype {
"i8" => Ok(FieldDatatype::I8),
"i16" => Ok(FieldDatatype::I16),
"rgb" => Ok(FieldDatatype::RGB),
#[cfg(feature = "std")]
_ => Err(MsgConversionError::UnsupportedFieldType(s.into())),
#[cfg(not(feature = "std"))]
_ => Err(MsgConversionError::UnsupportedFieldType),
}
}
}
@ -1169,7 +1224,10 @@ impl TryFrom<u8> for FieldDatatype {
6 => Ok(FieldDatatype::U32),
7 => Ok(FieldDatatype::F32),
8 => Ok(FieldDatatype::F64),
#[cfg(feature = "std")]
_ => Err(MsgConversionError::UnsupportedFieldType(value.to_string())),
#[cfg(not(feature = "std"))]
_ => Err(MsgConversionError::UnsupportedFieldType),
}
}
}
@ -1183,9 +1241,8 @@ impl From<FieldDatatype> for u8 {
FieldDatatype::U16 => 4,
FieldDatatype::I32 => 5,
FieldDatatype::U32 => 6,
FieldDatatype::F32 => 7,
FieldDatatype::F32 | FieldDatatype::RGB => 7, // RGB is marked as f32 in the buffer
FieldDatatype::F64 => 8,
FieldDatatype::RGB => 7, // RGB is marked as f32 in the buffer
}
}
}
@ -1200,10 +1257,10 @@ impl TryFrom<&ros::PointFieldMsg> for FieldDatatype {
/// Byte buffer alias for endian-aware point data reading and writing.
///
/// It uses a fixed size buffer of 8 bytes since the largest supported datatype for PointFieldMsg is f64.
/// It uses a fixed size buffer of 8 bytes since the largest supported datatype for [`ros::PointFieldMsg`] is f64.
pub struct PointDataBuffer([u8; 8]);
impl std::ops::Index<usize> for PointDataBuffer {
impl core::ops::Index<usize> for PointDataBuffer {
type Output = u8;
fn index(&self, index: usize) -> &Self::Output {
@ -1212,18 +1269,22 @@ impl std::ops::Index<usize> for PointDataBuffer {
}
impl PointDataBuffer {
#[must_use]
pub fn new(data: [u8; 8]) -> Self {
Self(data)
}
#[must_use]
pub fn as_slice(&self) -> &[u8] {
&self.0
}
#[must_use]
pub fn raw(self) -> [u8; 8] {
self.0
}
#[must_use]
pub fn from_slice(data: &[u8]) -> Self {
let mut buffer = [0; 8];
data.iter().enumerate().for_each(|(i, &v)| buffer[i] = v);
@ -1298,7 +1359,7 @@ impl From<points::RGB> for PointDataBuffer {
}
/// This trait is used to convert a byte slice to a primitive type.
/// All PointField types are supported.
/// All [`PointField`] types are supported.
pub trait FromBytes: Default + Sized + Copy + GetFieldDatatype + Into<PointDataBuffer> {
fn from_be_bytes(bytes: PointDataBuffer) -> Self;
fn from_le_bytes(bytes: PointDataBuffer) -> Self;
@ -1404,11 +1465,14 @@ mod tests {
use super::Fields;
use rpcl2_derive::Fields;
#[cfg(not(feature = "std"))]
use alloc::string::String;
#[allow(dead_code)]
#[derive(Fields)]
struct TestStruct {
field1: String,
#[rpcl2(name = "renamed_field")]
#[rpcl2(rename("renamed_field"))]
field2: i32,
field3: f64,
field4: bool,

View File

@ -4,6 +4,9 @@ use crate::{Fields, PointConvertible, RPCL2Point};
#[cfg(feature = "derive")]
use type_layout::TypeLayout;
#[cfg(all(not(feature = "std"), feature = "derive"))]
use alloc::vec::Vec;
/// A packed RGB color encoding as used in ROS tools.
#[derive(Clone, Copy)]
#[repr(C)]
@ -28,13 +31,13 @@ impl PartialEq for RGB {
}
impl core::fmt::Display for RGB {
fn fmt(&self, f: &mut std::fmt::Formatter<'_>) -> std::fmt::Result {
fn fmt(&self, f: &mut core::fmt::Formatter<'_>) -> core::fmt::Result {
write!(f, "#{:02X}{:02X}{:02X}", self.r(), self.g(), self.b())
}
}
impl core::fmt::Debug for RGB {
fn fmt(&self, f: &mut std::fmt::Formatter<'_>) -> std::fmt::Result {
fn fmt(&self, f: &mut core::fmt::Formatter<'_>) -> core::fmt::Result {
f.debug_struct("RGB")
.field("r", &self.r())
.field("g", &self.g())
@ -44,32 +47,39 @@ impl core::fmt::Debug for RGB {
}
impl RGB {
#[must_use]
pub fn new(r: u8, g: u8, b: u8) -> Self {
Self {
unpacked: [b, g, r, 0],
}
}
#[must_use]
pub fn new_from_packed_f32(packed: f32) -> Self {
Self { packed }
}
#[must_use]
pub fn new_from_packed(packed: u32) -> Self {
Self::new_from_packed_f32(f32::from_bits(packed))
}
#[must_use]
pub fn raw(&self) -> f32 {
unsafe { self.packed }
}
#[must_use]
pub fn r(&self) -> u8 {
unsafe { self.unpacked[2] }
}
#[must_use]
pub fn g(&self) -> u8 {
unsafe { self.unpacked[1] }
}
#[must_use]
pub fn b(&self) -> u8 {
unsafe { self.unpacked[0] }
}
@ -129,6 +139,7 @@ impl From<PointXYZ> for nalgebra::Point3<f32> {
}
impl PointXYZ {
#[must_use]
pub fn new(x: f32, y: f32, z: f32) -> Self {
Self { x, y, z }
}
@ -289,19 +300,23 @@ pub struct PointXYZRGB {
}
impl PointXYZRGB {
#[must_use]
pub fn new(x: f32, y: f32, z: f32, r: u8, g: u8, b: u8) -> Self {
let rgb = RGB::new(r, g, b);
Self { x, y, z, rgb }
}
#[must_use]
pub fn r(&self) -> u8 {
self.rgb.r()
}
#[must_use]
pub fn g(&self) -> u8 {
self.rgb.g()
}
#[must_use]
pub fn b(&self) -> u8 {
self.rgb.b()
}
@ -361,19 +376,23 @@ pub struct PointXYZRGBA {
}
impl PointXYZRGBA {
#[must_use]
pub fn new(x: f32, y: f32, z: f32, r: u8, g: u8, b: u8, a: u8) -> Self {
let rgb = RGB::new(r, g, b);
Self { x, y, z, rgb, a }
}
#[must_use]
pub fn r(&self) -> u8 {
self.rgb.r()
}
#[must_use]
pub fn g(&self) -> u8 {
self.rgb.g()
}
#[must_use]
pub fn b(&self) -> u8 {
self.rgb.b()
}
@ -436,6 +455,7 @@ pub struct PointXYZRGBNormal {
}
impl PointXYZRGBNormal {
#[must_use]
pub fn new(
x: f32,
y: f32,
@ -456,14 +476,17 @@ impl PointXYZRGBNormal {
}
}
#[must_use]
pub fn r(&self) -> u8 {
self.rgb.r()
}
#[must_use]
pub fn g(&self) -> u8 {
self.rgb.g()
}
#[must_use]
pub fn b(&self) -> u8 {
self.rgb.b()
}
@ -530,6 +553,7 @@ pub struct PointXYZINormal {
}
impl PointXYZINormal {
#[must_use]
pub fn new(
x: f32,
y: f32,
@ -613,6 +637,7 @@ unsafe impl Send for PointXYZRGBL {}
unsafe impl Sync for PointXYZRGBL {}
impl PointXYZRGBL {
#[must_use]
pub fn new(x: f32, y: f32, z: f32, r: u8, g: u8, b: u8, label: u32) -> Self {
let rgb = RGB::new(r, g, b);
Self {
@ -624,14 +649,17 @@ impl PointXYZRGBL {
}
}
#[must_use]
pub fn r(&self) -> u8 {
self.rgb.r()
}
#[must_use]
pub fn g(&self) -> u8 {
self.rgb.g()
}
#[must_use]
pub fn b(&self) -> u8 {
self.rgb.b()
}
@ -690,6 +718,7 @@ pub struct PointXYZNormal {
}
impl PointXYZNormal {
#[must_use]
pub fn new(x: f32, y: f32, z: f32, normal_x: f32, normal_y: f32, normal_z: f32) -> Self {
Self {
x,

View File

@ -23,6 +23,9 @@
//! }
//! ```
#[cfg(not(feature = "std"))]
use alloc::string::String;
/// [Time](https://docs.ros2.org/latest/api/builtin_interfaces/msg/Time.html) representation for ROS messages.
#[cfg(not(any(feature = "rclrs_msg")))]
#[derive(Clone, Debug, Default)]

View File

@ -70,9 +70,6 @@ fn write_cloud_from_vec() {
let msg = PointCloud2Msg::try_from_vec(cloud);
assert!(msg.is_ok());
let msg = msg.unwrap();
println!("{:?}", msg);
}
#[test]
@ -92,6 +89,47 @@ fn write_empty_cloud_iter() {
assert!(msg.unwrap().data.is_empty());
}
#[test]
#[cfg(all(feature = "derive", feature = "rayon"))]
fn conv_cloud_par_iter() {
let cloud = vec![
PointXYZ::new(0.0, 1.0, 5.0),
PointXYZ::new(1.0, 1.5, 5.0),
PointXYZ::new(1.3, 1.6, 5.7),
];
let copy = cloud.clone();
let msg: Result<PointCloud2Msg, MsgConversionError> = PointCloud2Msg::try_from_vec(cloud);
assert!(msg.is_ok());
let msg = msg.unwrap();
let to_p_type = msg.try_into_par_iter();
assert!(to_p_type.is_ok());
let to_p_type = to_p_type.unwrap();
let back_to_type = to_p_type.collect::<Vec<PointXYZ>>();
assert_eq!(copy, back_to_type);
}
#[test]
#[cfg(all(feature = "derive", feature = "rayon"))]
fn conv_cloud_par_par_iter() {
let cloud = vec![
PointXYZ::new(0.0, 1.0, 5.0),
PointXYZ::new(1.0, 1.5, 5.0),
PointXYZ::new(1.3, 1.6, 5.7),
PointXYZ::new(f32::MAX, f32::MIN, f32::MAX),
];
let copy = cloud.clone();
let msg = PointCloud2Msg::try_from_par_iter(cloud.into_par_iter());
assert!(msg.is_ok());
let msg = msg.unwrap();
let to_p_type = msg.try_into_par_iter();
assert!(to_p_type.is_ok());
let to_p_type = to_p_type.unwrap();
let back_to_type = to_p_type.collect::<Vec<PointXYZ>>();
assert_eq!(copy, back_to_type);
}
#[test]
#[cfg(feature = "derive")]
fn custom_xyz_f32() {