use core offset, xyz casting
This commit is contained in:
parent
15a1db79d6
commit
46771bfdd0
|
|
@ -1,7 +1,7 @@
|
|||
[package]
|
||||
name = "rpcl2-derive"
|
||||
description = "Derive macros for ros_pointcloud2 crate."
|
||||
version = "0.3.0"
|
||||
version = "0.4.0"
|
||||
edition = "2021"
|
||||
authors = ["Christopher Sieh <stelzo@steado.de>"]
|
||||
homepage = "https://github.com/stelzo/ros_pointcloud2"
|
||||
|
|
|
|||
|
|
@ -188,7 +188,7 @@ fn layout_of_type(struct_name: &Ident, data: &Data) -> proc_macro2::TokenStream
|
|||
|
||||
quote! {
|
||||
let size = ::core::mem::size_of::<#field_ty>();
|
||||
let offset = ::ros_pointcloud2::memoffset::offset_of!(#struct_name, #field_name);
|
||||
let offset = ::core::mem::offset_of!(#struct_name, #field_name);
|
||||
if offset > last_field_end {
|
||||
fields.push((1, "", offset - last_field_end));
|
||||
}
|
||||
|
|
|
|||
|
|
@ -1,6 +1,6 @@
|
|||
[package]
|
||||
name = "ros_pointcloud2"
|
||||
version = "0.5.1"
|
||||
version = "0.5.2"
|
||||
edition = "2021"
|
||||
authors = ["Christopher Sieh <stelzo@steado.de>"]
|
||||
description = "Customizable conversions for working with sensor_msgs/PointCloud2."
|
||||
|
|
@ -28,7 +28,7 @@ exclude = [
|
|||
"**/doc/**",
|
||||
"**/ensure_no_std/**",
|
||||
]
|
||||
rust-version = "1.63"
|
||||
rust-version = "1.77"
|
||||
|
||||
[dependencies]
|
||||
rosrust_msg = { version = "0.1", optional = true }
|
||||
|
|
@ -36,8 +36,7 @@ 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.3", optional = true, path = "../rpcl2-derive" }
|
||||
memoffset = { version = "0.9", optional = true }
|
||||
rpcl2-derive = { version = "0.4", optional = true, path = "../rpcl2-derive" }
|
||||
|
||||
[dev-dependencies]
|
||||
rand = "0.8"
|
||||
|
|
@ -53,7 +52,7 @@ path = "benches/roundtrip.rs"
|
|||
rosrust_msg = ["dep:rosrust_msg", "dep:rosrust"]
|
||||
r2r_msg = ["dep:r2r"]
|
||||
rayon = ["dep:rayon"]
|
||||
derive = ["dep:rpcl2-derive", "dep:memoffset"]
|
||||
derive = ["dep:rpcl2-derive"]
|
||||
nalgebra = ["dep:nalgebra"]
|
||||
std = ["nalgebra/std"]
|
||||
|
||||
|
|
|
|||
|
|
@ -148,10 +148,6 @@ pub mod iterator;
|
|||
|
||||
use crate::ros::{HeaderMsg, PointFieldMsg};
|
||||
|
||||
#[cfg(feature = "derive")]
|
||||
#[doc(hidden)]
|
||||
pub use memoffset;
|
||||
|
||||
use core::str::FromStr;
|
||||
|
||||
#[macro_use]
|
||||
|
|
|
|||
|
|
@ -113,6 +113,7 @@ pub struct PointXYZ {
|
|||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
impl From<nalgebra::Point3<f32>> for PointXYZ {
|
||||
fn from(point: nalgebra::Point3<f32>) -> Self {
|
||||
Self {
|
||||
|
|
@ -124,12 +125,73 @@ impl From<nalgebra::Point3<f32>> for PointXYZ {
|
|||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
impl From<&nalgebra::Point3<f32>> for PointXYZ {
|
||||
fn from(point: &nalgebra::Point3<f32>) -> Self {
|
||||
Self {
|
||||
x: point.x,
|
||||
y: point.y,
|
||||
z: point.z,
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
impl From<nalgebra::Point3<f64>> for PointXYZ {
|
||||
fn from(point: nalgebra::Point3<f64>) -> Self {
|
||||
Self {
|
||||
x: point.x as f32,
|
||||
y: point.y as f32,
|
||||
z: point.z as f32,
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
impl From<&nalgebra::Point3<f64>> for PointXYZ {
|
||||
fn from(point: &nalgebra::Point3<f64>) -> Self {
|
||||
Self {
|
||||
x: point.x as f32,
|
||||
y: point.y as f32,
|
||||
z: point.z as f32,
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
impl From<PointXYZ> for nalgebra::Point3<f32> {
|
||||
fn from(point: PointXYZ) -> Self {
|
||||
nalgebra::Point3::new(point.x, point.y, point.z)
|
||||
}
|
||||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
impl From<&PointXYZ> for nalgebra::Point3<f32> {
|
||||
fn from(point: &PointXYZ) -> Self {
|
||||
nalgebra::Point3::new(point.x, point.y, point.z)
|
||||
}
|
||||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
impl From<PointXYZ> for nalgebra::Point3<f64> {
|
||||
fn from(point: PointXYZ) -> Self {
|
||||
nalgebra::Point3::new(point.x as f64, point.y as f64, point.z as f64)
|
||||
}
|
||||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
impl From<&PointXYZ> for nalgebra::Point3<f64> {
|
||||
fn from(point: &PointXYZ) -> Self {
|
||||
nalgebra::Point3::new(point.x as f64, point.y as f64, point.z as f64)
|
||||
}
|
||||
}
|
||||
|
||||
impl PointXYZ {
|
||||
#[must_use]
|
||||
pub fn new(x: f32, y: f32, z: f32) -> Self {
|
||||
|
|
@ -138,9 +200,22 @@ impl PointXYZ {
|
|||
|
||||
/// Get the coordinates as a nalgebra Point3.
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[deprecated]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz(&self) -> nalgebra::Point3<f32> {
|
||||
nalgebra::Point3::new(self.x, self.y, self.z)
|
||||
self.xyz_f32()
|
||||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz_f32(&self) -> nalgebra::Point3<f32> {
|
||||
self.into()
|
||||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz_f64(&self) -> nalgebra::Point3<f64> {
|
||||
self.into()
|
||||
}
|
||||
}
|
||||
|
||||
|
|
@ -187,10 +262,23 @@ impl PointXYZI {
|
|||
|
||||
/// Get the coordinates as a nalgebra Point3.
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[deprecated]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz(&self) -> nalgebra::Point3<f32> {
|
||||
self.xyz_f32()
|
||||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz_f32(&self) -> nalgebra::Point3<f32> {
|
||||
nalgebra::Point3::new(self.x, self.y, self.z)
|
||||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz_f64(&self) -> nalgebra::Point3<f64> {
|
||||
nalgebra::Point3::new(self.x as f64, self.y as f64, self.z as f64)
|
||||
}
|
||||
}
|
||||
|
||||
unsafe impl Send for PointXYZI {}
|
||||
|
|
@ -247,10 +335,23 @@ impl PointXYZL {
|
|||
|
||||
/// Get the coordinates as a nalgebra Point3.
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[deprecated]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz(&self) -> nalgebra::Point3<f32> {
|
||||
self.xyz_f32()
|
||||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz_f32(&self) -> nalgebra::Point3<f32> {
|
||||
nalgebra::Point3::new(self.x, self.y, self.z)
|
||||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz_f64(&self) -> nalgebra::Point3<f64> {
|
||||
nalgebra::Point3::new(self.x as f64, self.y as f64, self.z as f64)
|
||||
}
|
||||
}
|
||||
|
||||
unsafe impl Send for PointXYZL {}
|
||||
|
|
@ -324,10 +425,23 @@ impl PointXYZRGB {
|
|||
|
||||
/// Get the coordinates as a nalgebra Point3.
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[deprecated]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz(&self) -> nalgebra::Point3<f32> {
|
||||
self.xyz_f32()
|
||||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz_f32(&self) -> nalgebra::Point3<f32> {
|
||||
nalgebra::Point3::new(self.x, self.y, self.z)
|
||||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz_f64(&self) -> nalgebra::Point3<f64> {
|
||||
nalgebra::Point3::new(self.x as f64, self.y as f64, self.z as f64)
|
||||
}
|
||||
}
|
||||
|
||||
unsafe impl Send for PointXYZRGB {}
|
||||
|
|
@ -403,10 +517,23 @@ impl PointXYZRGBA {
|
|||
|
||||
/// Get the coordinates as a nalgebra Point3.
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[deprecated]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz(&self) -> nalgebra::Point3<f32> {
|
||||
self.xyz_f32()
|
||||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz_f32(&self) -> nalgebra::Point3<f32> {
|
||||
nalgebra::Point3::new(self.x, self.y, self.z)
|
||||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz_f64(&self) -> nalgebra::Point3<f64> {
|
||||
nalgebra::Point3::new(self.x as f64, self.y as f64, self.z as f64)
|
||||
}
|
||||
}
|
||||
|
||||
unsafe impl Send for PointXYZRGBA {}
|
||||
|
|
@ -502,10 +629,23 @@ impl PointXYZRGBNormal {
|
|||
|
||||
/// Get the coordinates as a nalgebra Point3.
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[deprecated]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz(&self) -> nalgebra::Point3<f32> {
|
||||
self.xyz_f32()
|
||||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz_f32(&self) -> nalgebra::Point3<f32> {
|
||||
nalgebra::Point3::new(self.x, self.y, self.z)
|
||||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz_f64(&self) -> nalgebra::Point3<f64> {
|
||||
nalgebra::Point3::new(self.x as f64, self.y as f64, self.z as f64)
|
||||
}
|
||||
}
|
||||
|
||||
unsafe impl Send for PointXYZRGBNormal {}
|
||||
|
|
@ -592,10 +732,23 @@ impl PointXYZINormal {
|
|||
|
||||
/// Get the coordinates as a nalgebra Point3.
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[deprecated]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz(&self) -> nalgebra::Point3<f32> {
|
||||
self.xyz_f32()
|
||||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz_f32(&self) -> nalgebra::Point3<f32> {
|
||||
nalgebra::Point3::new(self.x, self.y, self.z)
|
||||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz_f64(&self) -> nalgebra::Point3<f64> {
|
||||
nalgebra::Point3::new(self.x as f64, self.y as f64, self.z as f64)
|
||||
}
|
||||
}
|
||||
|
||||
unsafe impl Send for PointXYZINormal {}
|
||||
|
|
@ -689,10 +842,23 @@ impl PointXYZRGBL {
|
|||
|
||||
/// Get the coordinates as a nalgebra Point3.
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[deprecated]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz(&self) -> nalgebra::Point3<f32> {
|
||||
self.xyz_f32()
|
||||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz_f32(&self) -> nalgebra::Point3<f32> {
|
||||
nalgebra::Point3::new(self.x, self.y, self.z)
|
||||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz_f64(&self) -> nalgebra::Point3<f64> {
|
||||
nalgebra::Point3::new(self.x as f64, self.y as f64, self.z as f64)
|
||||
}
|
||||
}
|
||||
|
||||
impl From<RPCL2Point<5>> for PointXYZRGBL {
|
||||
|
|
@ -760,10 +926,23 @@ impl PointXYZNormal {
|
|||
|
||||
/// Get the coordinates as a nalgebra Point3.
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[deprecated]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz(&self) -> nalgebra::Point3<f32> {
|
||||
self.xyz_f32()
|
||||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz_f32(&self) -> nalgebra::Point3<f32> {
|
||||
nalgebra::Point3::new(self.x, self.y, self.z)
|
||||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz_f64(&self) -> nalgebra::Point3<f64> {
|
||||
nalgebra::Point3::new(self.x as f64, self.y as f64, self.z as f64)
|
||||
}
|
||||
}
|
||||
|
||||
unsafe impl Send for PointXYZNormal {}
|
||||
|
|
|
|||
Loading…
Reference in New Issue