merge main

This commit is contained in:
stelzo 2024-05-16 00:04:21 +02:00
commit 91a81436c7
No known key found for this signature in database
GPG Key ID: FC4EF89052319374
5 changed files with 25 additions and 22 deletions

View File

@ -26,3 +26,5 @@ jobs:
run: cargo clippy --all-targets --features derive,nalgebra,rayon -- -D warnings
- name: Tests
run: cargo test --features derive,nalgebra,rayon
- name: no_std Tests
run: cargo test --no-default-features --features nalgebra

View File

@ -17,6 +17,7 @@ readme = "README.md"
documentation = "https://docs.rs/ros_pointcloud2"
homepage = "https://github.com/stelzo/ros_pointcloud2"
exclude = [
"**/.github/**",
"**/tests/**",
"**/examples/**",
"**/benches/**",
@ -33,8 +34,8 @@ rosrust_msg = { version = "0.1", optional = true }
rosrust = { version = "0.9.11", optional = true }
r2r = { version = "0.8.4", optional = true }
rayon = { version = "1", optional = true }
nalgebra = { version = "0", optional = true }
rpcl2_derive = { path = "./rpcl2_derive", optional = true }
nalgebra = { version = "0.32.5", optional = true, default-features = false }
rpcl2_derive = { path = "rpcl2_derive", optional = true }
type-layout = { path = "type-layout", optional = true }
sensor_msgs = { version = "*", optional = true }
@ -56,9 +57,9 @@ r2r_msg = ["dep:r2r"]
rayon = ["dep:rayon"]
derive = ["dep:rpcl2_derive", "dep:type-layout"]
nalgebra = ["dep:nalgebra"]
std = []
std = ["nalgebra/std"]
default = ["derive", "std", "rclrs_msg"]
default = ["std", "derive", "rclrs_msg"]
[package.metadata.docs.rs]
features = ["derive", "nalgebra", "rayon"]

View File

@ -96,7 +96,7 @@ For minimizing the conversion overhead in general, always use the functions that
## `no_std` Environments
The `_iter` conversions are compatible with `#[no_std]` environments if 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.
The `_iter` conversions are compatible with `#[no_std]` environments if 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. Only `nalgebra` can be added as an additional feature in this case.
## License

View File

@ -3,24 +3,24 @@
//! 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.
//! - [`PointCloud2Msg::try_from_vec`] requires `derive` feature (enabled by default)
//! - [`PointCloud2Msg::try_into_vec`] requires `derive` feature (enabled by 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)
//!
//! You can use the iterator functions for more control over the conversion process.
//! - [`PointCloud2Msg::try_from_iter`]
//! - [`PointCloud2Msg::try_into_iter`]
//! - [`try_from_iter`](PointCloud2Msg::try_from_iter)
//! - [`try_into_iter`](PointCloud2Msg::try_into_iter)
//!
//! These feature predictable performance but they do not scale well with large clouds. Learn more about that in the [performance section](https://github.com/stelzo/ros_pointcloud2?tab=readme-ov-file#performance) of the repository.
//! The iterators are useful when your conversions are more complex than a simple copy or you the cloud is small enough.
//!
//! When the cloud is getting larger or you are doing a lot of processing per point, switch to the parallel iterators.
//! - [`PointCloud2Msg::try_into_par_iter`] requires `rayon` feature
//! - [`PointCloud2Msg::try_from_par_iter`] requires `rayon` + `derive` feature
//! - [`try_into_par_iter`](PointCloud2Msg::try_into_par_iter) requires `rayon` feature
//! - [`try_from_par_iter`](PointCloud2Msg::try_from_par_iter) requires `rayon` + `derive` feature
//!
//! For ROS interoperability, there are integrations avialable with feature flags. If you miss a message type, please open an issue or a PR.
//! See the [`ros`] module for more information on how to integrate more libraries.
//!
//! Common point types like [`points::PointXYZ`] or [`points::PointXYZI`] are provided. You can easily add any additional custom type.
//! Common point types like [`PointXYZ`](points::PointXYZ) or [`PointXYZI`](points::PointXYZI) are provided. See the full list [`here`](points). You can easily add any additional custom type.
//! See [custom_enum_field_filter.rs](https://github.com/stelzo/ros_pointcloud2/blob/main/examples/custom_enum_field_filter.rs) for an example.
//!
//! # Minimal Example
@ -58,8 +58,8 @@
//! - (rclrs_msg) — Integration for ROS2 [rclrs](https://github.com/ros2-rust/ros2_rust) but it currently needs [this workaround](https://github.com/stelzo/ros_pointcloud2?tab=readme-ov-file#rclrs-ros2_rust).
//! - derive *(enabled by default)* — Enables the `_vec` functions and offers helpful custom point derive macros for the [`PointConvertible`] trait.
//! - rayon — Parallel iterator support for `_par_iter` functions. [`PointCloud2Msg::try_from_par_iter`] additionally needs the 'derive' feature.
//! - nalgebra — Predefined points offer a nalgebra typed getter for coordinates (e.g. [`points::PointXYZ::xyz`]).
//! - std *(enabled by default)* — Use the standard library. Disable *all* features for `no_std` environments.
//! - nalgebra — Predefined points offer a nalgebra typed getter for coordinates (e.g. [`xyz`](points::PointXYZ::xyz)).
//! - std *(enabled by default)* — Use the standard library. `no_std` only works standalone or with the 'nalgebra' feature.
//!
//! # Custom Points
//! Implement [`PointConvertible`] for your point with the `derive` feature or manually.
@ -1108,7 +1108,7 @@ impl From<i16> for PointData {
}
}
/// Datatypes from the [`ros::PointFieldMsg`].
/// Datatypes from the [`PointFieldMsg`].
#[derive(Default, Clone, Debug, PartialEq, Copy)]
pub enum FieldDatatype {
F32,
@ -1122,7 +1122,7 @@ pub enum FieldDatatype {
I16,
/// While RGB is not officially supported by ROS, it is used in the tooling as a packed f32.
/// To make it easy to work with and avoid packing code, the [`points::RGB`] union is supported here and handled like a f32.
/// To make it easy to work with and avoid packing code, the [`RGB`](points::RGB) union is supported here and handled like a f32.
RGB,
}
@ -1270,7 +1270,7 @@ 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 [`ros::PointFieldMsg`] is f64.
/// It uses a fixed size buffer of 8 bytes since the largest supported datatype for [`PointFieldMsg`] is f64.
pub struct PointDataBuffer([u8; 8]);
impl core::ops::Index<usize> for PointDataBuffer {
@ -1372,7 +1372,7 @@ impl From<points::RGB> for PointDataBuffer {
}
/// This trait is used to convert a byte slice to a primitive type.
/// All [`ros::PointFieldMsg`] types are supported.
/// All [`PointFieldMsg`] 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;

View File

@ -3,7 +3,7 @@
//! This intermediate layer allows various ROS libraries to be integrated to the conversion process.
//!
//! There are 2 functions needed to be implemented for a new ROS message library:
//! - `From` for converting from the library-generated message to [`crate::PointCloud2Msg`].
//! - `From` for converting from the library-generated message to [`PointCloud2Msg`](crate::PointCloud2Msg).
//! ```
//! #[cfg(feature = "fancy_ros_msg")]
//! impl From<fancy_ros::sensor_msgs::msg::PointCloud2> for crate::PointCloud2Msg {
@ -13,7 +13,7 @@
//! }
//! ```
//!
//! - `From` for converting from the [`crate::PointCloud2Msg`] to the library-generated message type.
//! - `From` for converting from the [`PointCloud2Msg`](crate::PointCloud2Msg) to the library-generated message type.
//! ```
//! #[cfg(feature = "fancy_ros_msg")]
//! impl From<crate::PointCloud2Msg> for fancy_ros::sensor_msgs::msg::PointCloud2 {