Expand description
A PointCloud2 message conversion library.
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.
You can use the iterator functions for more control over the conversion process.
These feature predictable performance but they do not scale well with large clouds. Learn more about that in the performance section of the repository. The iterators are useful when your conversions are more complex than a simple copy or 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.
try_into_par_iter
requiresrayon
featuretry_from_par_iter
requiresrayon
feature
For ROS interoperability, there are integrations available 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 PointXYZ
or PointXYZI
are provided. See the full list here
. You can easily add any additional custom type.
See custom_enum_field_filter.rs for an example.
§Minimal Example
use ros_pointcloud2::prelude::*;
let cloud_points = vec![
PointXYZI::new(9.6, 42.0, -6.2, 0.1),
PointXYZI::new(46.0, 5.47, 0.5, 0.1),
];
let cloud_copy = cloud_points.clone(); // For equality test later.
let out_msg = PointCloud2Msg::try_from_iter(cloud_points).unwrap();
// Convert to your ROS crate message type.
// let msg: r2r::sensor_msgs::msg::PointCloud2 = in_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 data you want from the point.
// Some logic here.
PointXYZI::new(point.x, point.y, point.z, 0.1)
}).collect::<Vec<_>>();
assert_eq!(processed_cloud, cloud_copy);
§Features
- r2r_msg — Integration for the ROS2 library r2r.
- rosrust_msg — Integration with the rosrust library for ROS1 message types.
- (rclrs_msg) — Integration for ROS2 rclrs but it currently needs this workaround.
- derive — Offers implementations for the
PointConvertible
trait needed for custom points. - rayon — Parallel iterator support for
_par_iter
functions. - nalgebra — Predefined points offer a nalgebra typed getter for coordinates (e.g.
xyz
). - std (enabled by default) — Omit this feature to use this library in no_std environments. ROS integrations and ‘rayon’ will not work with no_std.
§Custom Points
Implement PointConvertible
for your point with the derive
feature or manually.
§Derive (recommended)
#[derive(Clone, Debug, PartialEq, Copy, Default, PointConvertible)]
#[repr(C, align(4))]
pub struct MyPointXYZI {
pub x: f32,
pub y: f32,
pub z: f32,
#[rpcl2(rename("i"))]
pub intensity: f32,
}
§Manual
use ros_pointcloud2::prelude::*;
#[derive(Clone, Debug, PartialEq, Copy, Default)]
#[repr(C, align(4))]
pub struct MyPointXYZI {
pub x: f32,
pub y: f32,
pub z: f32,
pub intensity: f32,
}
impl MyPointXYZI {
pub fn new(x: f32, y: f32, z: f32, intensity: f32) -> Self {
Self { x, y, z, intensity }
}
}
impl From<RPCL2Point<4>> for MyPointXYZI {
fn from(point: RPCL2Point<4>) -> Self {
Self::new(point[0].get(), point[1].get(), point[2].get(), point[3].get())
}
}
impl From<MyPointXYZI> for RPCL2Point<4> {
fn from(point: MyPointXYZI) -> Self {
[point.x.into(), point.y.into(), point.z.into(), point.intensity.into()].into()
}
}
unsafe impl PointConvertible<4> 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),
])
}
}
let first_p = MyPointXYZI::new(1.0, 2.0, 3.0, 0.5);
let cloud_points = vec![first_p, MyPointXYZI::new(4.0, 5.0, 6.0, 0.5)];
let msg_out = PointCloud2Msg::try_from_iter(cloud_points).unwrap();
let cloud_points_out: Vec<MyPointXYZI> = msg_out.try_into_iter().unwrap().collect();
assert_eq!(first_p, *cloud_points_out.first().unwrap());
Modules§
- iterator
- Iterator implementations for
PointCloud2Msg
including a parallel iterator for rayon. - points
- Predefined point types commonly used in ROS.
- prelude
- Commonly used types and traits for predefined and custom point conversions.
- ros
- Types used to represent ROS messages and convert between different ROS crates.
Structs§
- Cloud
Dimensions - Dimensions of the point cloud as width and height.
- Cloud
Dimensions Builder - Creating a
CloudDimensions
type with the builder pattern to avoid invalid states when using 1-row point clouds. - Layout
Description - Description of the memory layout of a type with named fields.
- Point
Cloud2 Msg - The intermediate point cloud type for ROS integrations.
- Point
Cloud2 MsgBuilder - Creating a
PointCloud2Msg
with the builder pattern to avoid invalid states. - Point
Data - Single data representation for a point.
- Point
Data Buffer - Byte buffer alias for endian-aware point data reading and writing.
- RPCL2
Point - Internal point representation. It is used to store the point data entries.
Enums§
- Denseness
- Density flag for the message. Writing sparse point clouds is not supported.
- Endian
- Endianess encoding hint for the message.
- Field
Datatype - Datatypes from the
PointFieldMsg
. - Layout
Field - Enum to describe the field type and size in a padded or unpadded layout.
- MsgConversion
Error - All errors that can occur while converting to or from the message type.
Traits§
- From
Bytes - This trait is used to convert a byte slice to a primitive type.
All
PointFieldMsg
types are supported. - GetField
Datatype - Getter trait for the datatype of a field value.
- Point
Convertible - Trait to enable point conversions on the fly.