Rust crate for PointCloud2 ROS1/ROS2 message conversion.
Go to file
stelzo 0968bc1f9b fixed rclrs tag method 2024-05-17 14:37:01 +02:00
.github use workspace 2024-05-16 15:43:37 +02:00
rpcl2 fix tests 2024-05-17 11:31:09 +02:00
rpcl2-derive use workspace 2024-05-16 15:43:37 +02:00
.gitignore first commit 2023-04-25 18:30:54 +02:00
CHANGELOG.md add changelog 2024-05-16 11:41:40 +02:00
Cargo.toml use workspace 2024-05-16 15:43:37 +02:00
LICENSE-APACHE adapt to rust-lang licenses 2024-05-16 10:04:22 +02:00
LICENSE-MIT adapt to rust-lang licenses 2024-05-16 10:04:22 +02:00
README.md fixed rclrs tag method 2024-05-17 14:37:01 +02:00

README.md

ROS PointCloud2

A PointCloud2 message conversion library.

ros_pointcloud2 uses its own type for the message PointCloud2Msg to keep the library framework agnostic. ROS1 and ROS2 are supported with feature flags.

Get started with the example below, check out the other use cases in the examples folder or see the Documentation for a complete guide.

Quickstart

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<_>>();

Integrations

There are currently 3 integrations for common ROS crates.

You can use rosrust and r2r by enabling the respective feature:

[dependencies]
ros_pointcloud2 = { version = "*", features = ["r2r_msg", "derive"]}
# or
ros_pointcloud2 = { version = "*", features = ["rosrust_msg", "derive"]}

rclrs (ros2_rust)

Features do not work properly with rcrls because the messages are linked externally. You need to use tags instead:

[dependencies]
ros_pointcloud2 = { git = "https://github.com/stelzo/ros_pointcloud2", tag = "v0.5.0-rc.1_rclrs" }

Also, indicate the following dependencies to your linker inside the package.xml of your package.

<depend>std_msgs</depend>
<depend>sensor_msgs</depend>
<depend>builtin_interfaces</depend>

Please open an issue or PR if you need other integrations.

Performance

This library offers a speed up when compared to PointCloudLibrary (PCL) conversions but the specific factor depends heavily on the use case and system. The _vec conversions are on average ~6x faster than PCL while the single core iteration _iter functions are around ~2x faster. Parallelization with _par_iter gives a ~9x speed up compared to an OpenMP accelerated PCL pipeline.

The results are measured on an Intel i7-14700 with benchmarks from this repository.

For minimizing the conversion overhead in general, always use the functions that best fit your use case.

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. Only nalgebra can be added as an additional feature in this case.

License

Licensed under either of

at your option.

Contribution

Unless you explicitly state otherwise, any contribution intentionally submitted for inclusion in the work by you, as defined in the Apache-2.0 license, shall be dual licensed as above, without any additional terms or conditions.