add serde
This commit is contained in:
parent
83e9d1019e
commit
54c5e8f6bb
|
|
@ -37,6 +37,7 @@ 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,6 +50,7 @@ harness = false
|
|||
path = "benches/roundtrip.rs"
|
||||
|
||||
[features]
|
||||
serde = ["dep:serde", "nalgebra/serde-serialize-no-std"]
|
||||
rosrust_msg = ["dep:rosrust_msg", "dep:rosrust"]
|
||||
r2r_msg = ["dep:r2r"]
|
||||
rayon = ["dep:rayon"]
|
||||
|
|
@ -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"]
|
||||
|
|
|
|||
|
|
@ -150,6 +150,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 +284,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 +298,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 +307,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 +464,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,
|
||||
|
|
|
|||
|
|
@ -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,
|
||||
|
|
|
|||
|
|
@ -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,
|
||||
|
|
|
|||
Loading…
Reference in New Issue