Compare commits

...

2 Commits

Author SHA1 Message Date
stelzo 506ff826a3 fix build and tests 2025-02-01 21:38:16 +01:00
stelzo 54c5e8f6bb add serde 2025-02-01 20:15:19 +01:00
18 changed files with 85 additions and 19 deletions

View File

@ -18,9 +18,9 @@ jobs:
with:
components: clippy
- name: Linting
run: cargo clippy --all-targets --features derive,nalgebra,rayon -- -D warnings
run: cargo clippy --all-targets --features derive,nalgebra,rayon,serde -- -D warnings
- name: Tests
run: cargo test --features derive,nalgebra,rayon
run: cargo test --features derive,nalgebra,rayon,serde
outdated:
name: Outdated

View File

@ -18,4 +18,4 @@ jobs:
steps:
- uses: actions/checkout@v2
- run: docker build . --file ./rpcl2/tests/Dockerfile_r2r_galactic --tag r2r_galactic
- run: docker run r2r_galactic cargo test --features r2r_msg,derive,nalgebra,rayon
- run: docker run r2r_galactic cargo test --features r2r_msg,derive,nalgebra,rayon,serde

View File

@ -18,4 +18,4 @@ jobs:
steps:
- uses: actions/checkout@v2
- run: docker build . --file ./rpcl2/tests/Dockerfile_r2r_humble --tag r2r_humble
- run: docker run r2r_humble cargo test --features r2r_msg,derive,nalgebra,rayon
- run: docker run r2r_humble cargo test --features r2r_msg,derive,nalgebra,rayon,serde

View File

@ -18,4 +18,4 @@ jobs:
steps:
- uses: actions/checkout@v2
- run: docker build . --file ./rpcl2/tests/Dockerfile_r2r_iron --tag r2r_iron
- run: docker run r2r_iron cargo test --features r2r_msg,derive,nalgebra,rayon
- run: docker run r2r_iron cargo test --features r2r_msg,derive,nalgebra,rayon,serde

View File

@ -18,4 +18,4 @@ jobs:
steps:
- uses: actions/checkout@v2
- run: docker build . --file ./rpcl2/tests/Dockerfile_r2r_jazzy --tag r2r_jazzy
- run: docker run r2r_jazzy cargo test --features r2r_msg,derive,nalgebra,rayon
- run: docker run r2r_jazzy cargo test --features r2r_msg,derive,nalgebra,rayon,serde

View File

@ -18,4 +18,4 @@ jobs:
steps:
- uses: actions/checkout@v2
- run: docker build . --file ./rpcl2/tests/Dockerfile_rclrs_humble --tag rclrs_humble
- run: docker run rclrs_humble cargo test --features derive,nalgebra,rayon
- run: docker run rclrs_humble cargo test --features derive,nalgebra,rayon,serde

View File

@ -18,4 +18,4 @@ jobs:
steps:
- uses: actions/checkout@v2
- run: docker build . --file ./rpcl2/tests/Dockerfile_rclrs_iron --tag rclrs_iron
- run: docker run rclrs_iron cargo test --features derive,nalgebra,rayon
- run: docker run rclrs_iron cargo test --features derive,nalgebra,rayon,serde

View File

@ -18,4 +18,4 @@ jobs:
steps:
- uses: actions/checkout@v2
- run: docker build . --file ./rpcl2/tests/Dockerfile_rclrs_jazzy --tag rclrs_jazzy
- run: docker run rclrs_jazzy cargo test --features derive,nalgebra,rayon
- run: docker run rclrs_jazzy cargo test --features derive,nalgebra,rayon,serde

View File

@ -105,4 +105,4 @@ jobs:
- name: test
run: |
source /opt/ros/$ROS_DISTRO/setup.bash
cargo test --features rosrust_msg,derive,nalgebra,rayon
cargo test --features rosrust_msg,derive,nalgebra,rayon,serde

View File

@ -21,8 +21,8 @@ jobs:
with:
components: clippy
- name: Linting
run: cargo clippy --all-targets --features derive,nalgebra,rayon -- -D warnings
run: cargo clippy --all-targets --features derive,nalgebra,rayon,serde -- -D warnings
- name: Build examples with features
run: cargo build --examples --features derive,nalgebra,rayon
run: cargo build --examples --features derive,nalgebra,rayon,serde
- name: Test library
run: cargo test --features derive,nalgebra,rayon
run: cargo test --features derive,nalgebra,rayon,serde

2
.gitignore vendored
View File

@ -1,3 +1,3 @@
Cargo.lock
Cargo.lock*
.idea/
target/

View File

@ -5,6 +5,15 @@
</p>
</p>
> [!IMPORTANT]
> The optional rosrust dependency currently breaks the build of this crate because of a yanked transitive dependency on crates.io.
> Use [this workaround](https://github.com/adnanademovic/rosrust/issues/210#issuecomment-2609494830) in your project when rosrust is needed.
> If you are not using rosrust at all, you can also use the main branch of this repository, where the integration is removed at the moment.
> ```toml
> [dependencies]
> ros_pointcloud2 = { version = "0.5.2", git = "https://github.com/stelzo/ros_pointcloud2.git" }
> ```
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](https://docs.rs/ros_pointcloud2/0.5.1/) for a complete guide.

View File

@ -17,3 +17,7 @@ categories = [
[dependencies]
ros_pointcloud2 = { path = "../rpcl2", features = ["std", "derive"] }
rpcl2-derive = { path = "../rpcl2-derive" }
[patch.crates-io]
# Fixes https://github.com/adnanademovic/rosrust/issues/210
xml-rpc = { git = "https://github.com/locusrobotics/xml-rpc-rs", branch = "minimum-update" }

View File

@ -31,12 +31,13 @@ exclude = [
rust-version = "1.77"
[dependencies]
rosrust_msg = { version = "0.1", optional = true }
rosrust = { version = "0.9.11", optional = true }
#rosrust_msg = { version = "0.1", optional = true }
#rosrust = { version = "0.9.11", optional = true }
r2r = { version = "0.9", optional = true }
rayon = { version = "1", optional = true }
nalgebra = { version = "0.33", optional = true, default-features = false }
rpcl2-derive = { version = "0.4", optional = true, path = "../rpcl2-derive" }
serde = { version = "1.0", features = ["derive"], optional = true }
[dev-dependencies]
rand = "0.8"
@ -49,7 +50,8 @@ harness = false
path = "benches/roundtrip.rs"
[features]
rosrust_msg = ["dep:rosrust_msg", "dep:rosrust"]
serde = ["dep:serde", "nalgebra/serde-serialize-no-std"]
#rosrust_msg = ["dep:rosrust_msg"]
r2r_msg = ["dep:r2r"]
rayon = ["dep:rayon"]
derive = ["dep:rpcl2-derive"]
@ -59,6 +61,6 @@ std = ["nalgebra/std"]
default = ["std"]
[package.metadata.docs.rs]
features = ["derive", "nalgebra", "rayon"]
features = ["derive", "nalgebra", "rayon", "serde"]
default-target = "x86_64-unknown-linux-gnu"
rustdoc-args = ["--cfg", "docsrs"]

View File

@ -139,6 +139,7 @@
#![cfg_attr(not(feature = "std"), no_std)]
// Setup an allocator with #[global_allocator]
// see: https://doc.rust-lang.org/std/alloc/trait.GlobalAlloc.html
#![allow(unexpected_cfgs)]
pub mod points;
pub mod prelude;
@ -150,6 +151,9 @@ use crate::ros::{HeaderMsg, PointFieldMsg};
use core::str::FromStr;
#[cfg(feature = "serde")]
use serde::{Deserialize, Serialize};
#[macro_use]
extern crate alloc;
use alloc::string::String;
@ -281,6 +285,7 @@ impl LayoutField {
/// To assert consistency, the type should be build with the [`PointCloud2MsgBuilder`].
/// See the offical [ROS message description](https://docs.ros2.org/latest/api/sensor_msgs/msg/PointCloud2.html) for more information on the fields.
#[derive(Clone, Debug)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct PointCloud2Msg {
pub header: HeaderMsg,
pub dimensions: CloudDimensions,
@ -294,6 +299,7 @@ pub struct PointCloud2Msg {
/// Endianess encoding hint for the message.
#[derive(Default, Clone, Debug, PartialEq, Copy)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub enum Endian {
Big,
#[default]
@ -302,6 +308,7 @@ pub enum Endian {
/// Density flag for the message. Writing sparse point clouds is not supported.
#[derive(Default, Clone, Debug, PartialEq, Copy)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub enum Denseness {
#[default]
Dense,
@ -458,6 +465,7 @@ impl PointCloud2MsgBuilder {
/// Dimensions of the point cloud as width and height.
#[derive(Clone, Debug, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct CloudDimensions {
pub width: u32,
pub height: u32,

View File

@ -1,6 +1,9 @@
//! Predefined point types commonly used in ROS.
use crate::{LayoutDescription, LayoutField, PointConvertible, RPCL2Point};
#[cfg(feature = "serde")]
use serde::{Deserialize, Serialize};
/// Packed RGB color encoding as used in ROS tools.
#[derive(Clone, Copy)]
#[repr(C, align(4))]
@ -9,6 +12,29 @@ pub union RGB {
unpacked: [u8; 4], // Padding
}
#[cfg(feature = "serde")]
#[cfg_attr(docsrs, doc(cfg(feature = "serde")))]
impl<'de> Deserialize<'de> for RGB {
fn deserialize<D>(deserializer: D) -> Result<RGB, D::Error>
where
D: serde::Deserializer<'de>,
{
let packed = f32::deserialize(deserializer)?;
Ok(RGB::new_from_packed_f32(packed))
}
}
#[cfg(feature = "serde")]
#[cfg_attr(docsrs, doc(cfg(feature = "serde")))]
impl Serialize for RGB {
fn serialize<S>(&self, serializer: S) -> Result<S::Ok, S::Error>
where
S: serde::Serializer,
{
f32::from(*self).serialize(serializer)
}
}
unsafe impl Send for RGB {}
unsafe impl Sync for RGB {}
@ -106,6 +132,7 @@ impl From<f32> for RGB {
/// 3D point with x, y, z coordinates, commonly used in ROS with PCL.
#[derive(Clone, Debug, PartialEq, Copy, Default)]
#[repr(C, align(16))]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct PointXYZ {
pub x: f32,
pub y: f32,
@ -248,6 +275,7 @@ unsafe impl PointConvertible<3> for PointXYZ {
/// 3D point with x, y, z coordinates and an intensity value, commonly used in ROS with PCL.
#[derive(Clone, Debug, PartialEq, Copy, Default)]
#[repr(C, align(16))]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct PointXYZI {
pub x: f32,
pub y: f32,
@ -321,6 +349,7 @@ unsafe impl PointConvertible<4> for PointXYZI {
/// 3D point with x, y, z coordinates and a label, commonly used in ROS with PCL.
#[derive(Clone, Debug, PartialEq, Copy, Default)]
#[repr(C, align(16))]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct PointXYZL {
pub x: f32,
pub y: f32,
@ -394,6 +423,7 @@ unsafe impl PointConvertible<4> for PointXYZL {
/// 3D point with x, y, z coordinates and an RGB color value, commonly used in ROS with PCL.
#[derive(Clone, Debug, PartialEq, Copy, Default)]
#[repr(C, align(16))]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct PointXYZRGB {
pub x: f32,
pub y: f32,
@ -485,6 +515,7 @@ unsafe impl PointConvertible<4> for PointXYZRGB {
/// The alpha channel is commonly used as padding but this crate uses every channel and no padding.
#[derive(Clone, Debug, PartialEq, Copy, Default)]
#[repr(C, align(16))]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct PointXYZRGBA {
pub x: f32,
pub y: f32,
@ -580,6 +611,7 @@ unsafe impl PointConvertible<5> for PointXYZRGBA {
/// 3D point with x, y, z coordinates, an RGB color value and a normal vector, commonly used in ROS with PCL.
#[derive(Clone, Debug, PartialEq, Copy, Default)]
#[repr(C, align(16))]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct PointXYZRGBNormal {
pub x: f32,
pub y: f32,
@ -698,6 +730,7 @@ unsafe impl PointConvertible<7> for PointXYZRGBNormal {
/// 3D point with x, y, z coordinates, an intensity value and a normal vector, commonly used in ROS with PCL.
#[derive(Clone, Debug, PartialEq, Copy, Default)]
#[repr(C, align(16))]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct PointXYZINormal {
pub x: f32,
pub y: f32,
@ -801,6 +834,7 @@ unsafe impl PointConvertible<7> for PointXYZINormal {
/// 3D point with x, y, z coordinates and a label, commonly used in ROS with PCL.
#[derive(Clone, Debug, PartialEq, Copy, Default)]
#[repr(C, align(16))]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct PointXYZRGBL {
pub x: f32,
pub y: f32,
@ -902,6 +936,7 @@ unsafe impl PointConvertible<5> for PointXYZRGBL {
/// 3D point with x, y, z coordinates and a normal vector, commonly used in ROS with PCL.
#[derive(Clone, Debug, PartialEq, Copy, Default)]
#[repr(C, align(16))]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct PointXYZNormal {
pub x: f32,
pub y: f32,

View File

@ -25,8 +25,12 @@
use alloc::string::String;
#[cfg(feature = "serde")]
use serde::{Deserialize, Serialize};
/// [Time](https://docs.ros2.org/latest/api/builtin_interfaces/msg/Time.html) representation for ROS messages.
#[derive(Clone, Debug, Default)]
#[derive(Clone, Debug, Default, Copy)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct TimeMsg {
pub sec: i32,
pub nanosec: u32,
@ -44,6 +48,7 @@ impl From<rosrust::Time> for TimeMsg {
/// Represents the [header of a ROS message](https://docs.ros2.org/latest/api/std_msgs/msg/Header.html).
#[derive(Clone, Debug, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct HeaderMsg {
pub seq: u32,
pub stamp: TimeMsg,
@ -52,6 +57,7 @@ pub struct HeaderMsg {
/// Describing a point encoded in the byte buffer of a PointCloud2 message. See the [official message description](https://docs.ros2.org/latest/api/sensor_msgs/msg/PointField.html) for more information.
#[derive(Clone, Debug)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct PointFieldMsg {
pub name: String,
pub offset: u32,

View File

@ -1,3 +1,5 @@
#![allow(unexpected_cfgs)] // TODO remove when rosrust is fixed
#[cfg(feature = "rosrust_msg")]
#[test]
fn convertxyz_rosrust_msg() {