A Rust implementation for fast, safe and customizable conversions to and from the sensor_msgs/PointCloud2
ROS message.
Providing a fast and memory efficient way for message conversion while allowing user defined types without the cost of iterations.
Currently only supports rosrust_msg with ROS1.
```rust use rospointcloud2::ConvertXYZ; use rospointcloud2::pclutils::PointXYZ; use rospointcloud2::fallible_iterator::FallibleIterator;
use rosrustmsg::sensormsgs::PointCloud2;
// Your points (here using the predefined type PointXYZ). let cloud_points = vec![ PointXYZ { x: 1.3, y: 1.6, z: 5.7 }, PointXYZ { x: f32::MAX, y: f32::MIN, z: f32::MAX }, ];
let cloudcopy = cloudpoints.clone(); // Only for checking equality later.
// Vector -> Convert -> Message let msg: PointCloud2 = ConvertXYZ::tryfrom(cloudpoints).unwrap().try_into().unwrap();
// Message -> Convert -> Vector
let convert: ConvertXYZ = ConvertXYZ::tryfrom(msg).unwrap();
let newcloudpoints = convert.map(|point: PointXYZ| {
// Insert your point business logic here or use other methods like .foreach().
// I will just copy the points into a vector as an example.
// Also, since we are using a fallible iterator, we need to return a Result.
Ok(point)
}).collect::
asserteq!(newcloudpoints, cloudcopy); ```
Instead of converting the entire cloud into a Vector
, you get an Iterator
that converts each point from the message on the fly.
An example for using this crate is this filter node. It is also a good starting point for
implementing ROS1 nodes in Rust inside a catkin environment.
sensor_msgs/PointCloud2
messagesFrom
and Into
traitsAdd this to your Cargo.toml:
toml
[dependencies]
ros_pointcloud2 = "0.1.0"
When building, the rosrust_msg
crate needs to have the ROS environment sourced or use ROSRUST_MSG_PATH=/opt/ros/$ROS_DISTRO/share cargo build
.
You can freely convert to your own types without reiterating the entire cloud.
You just need to implement the Into
and From
traits.
```rust
use rospointcloud2::memmacros::sizeof;
use rospointcloud2::{Convert, MetaNames, PointMeta, ConversionError, PointConvertible};
use rosrustmsg::sensormsgs::PointCloud2;
const DIM : usize = 3; const METADIM : usize = 4;
struct CustomPoint { x: f32, // DIM 1 y: f32, // DIM 2 z: f32, // DIM 3 r: u8, // METADIM 1 g: u8, // METADIM 2 b: u8, // METADIM 3 a: u8, // METADIM 4 }
// Converting your custom point to the crate's internal representation impl Into<([f32; DIM], [PointMeta; METADIM])> for CustomPoint { fn into(self) -> ([f32; DIM], [PointMeta; METADIM]) { ([self.x, self.y, self.z], [PointMeta::new(self.r), PointMeta::new(self.g), PointMeta::new(self.b), PointMeta::new(self.a)]) } }
// The mappings for index of meta idx to field names. Example: 0 -> "r", 1 -> "g", 2 -> "b", 3 -> "a"
impl MetaNames
// Converting crate's internal representation to your custom point
impl TryFrom<([f32; DIM], [PointMeta; METADIM])> for CustomPoint {
type Error = ConversionError;
fn try_from(data: ([f32; DIM], [PointMeta; METADIM])) -> Result
impl PointConvertible
type MyConverter = Convert
// Your custom cloud (Vector) let custom_cloud = vec![ CustomPoint { x: 0.0, y: 1.0, z: 5.0, r: 0, g: 0, b: 0, a: 0 }, CustomPoint { x: 1.0, y: 1.5, z: 5.0, r: 1, g: 1, b: 1, a: 1 }, CustomPoint { x: 1.3, y: 1.6, z: 5.7, r: 2, g: 2, b: 2, a: 2 }, CustomPoint { x: f32::MAX, y: f32::MIN, z: f32::MAX, r: u8::MAX, g: u8::MAX, b: u8::MAX, a: u8::MAX }, ];
// Cloud -> ROS message let custommsg: PointCloud2 = MyConverter::tryfrom(customcloud).unwrap().tryinto().unwrap();
// ROS message -> Cloud let tocustomtype = MyConverter::tryfrom(custommsg).unwrap(); ```
PointConversionError
)