add 0.5.2 main changes
This commit is contained in:
parent
64f1c7cb95
commit
23ede229c7
39
Cargo.toml
39
Cargo.toml
|
|
@ -8,46 +8,47 @@ repository = "https://github.com/stelzo/ros_pointcloud2"
|
||||||
license = "MIT OR Apache-2.0"
|
license = "MIT OR Apache-2.0"
|
||||||
keywords = ["ros", "pointcloud2", "pointcloud", "message"]
|
keywords = ["ros", "pointcloud2", "pointcloud", "message"]
|
||||||
categories = [
|
categories = [
|
||||||
"science::robotics",
|
"science::robotics",
|
||||||
"encoding",
|
"encoding",
|
||||||
"data-structures",
|
"data-structures",
|
||||||
"api-bindings",
|
"api-bindings",
|
||||||
]
|
]
|
||||||
readme = "README.md"
|
readme = "README.md"
|
||||||
documentation = "https://docs.rs/ros_pointcloud2"
|
documentation = "https://docs.rs/ros_pointcloud2"
|
||||||
homepage = "https://github.com/stelzo/ros_pointcloud2"
|
homepage = "https://github.com/stelzo/ros_pointcloud2"
|
||||||
exclude = [
|
exclude = [
|
||||||
"**/.github/**",
|
"**/.github/**",
|
||||||
"**/tests/**",
|
"**/tests/**",
|
||||||
"**/examples/**",
|
"**/examples/**",
|
||||||
"**/benches/**",
|
"**/benches/**",
|
||||||
"**/target/**",
|
"**/target/**",
|
||||||
"**/build/**",
|
"**/build/**",
|
||||||
"**/dist/**",
|
"**/dist/**",
|
||||||
"**/docs/**",
|
"**/docs/**",
|
||||||
"**/doc/**",
|
"**/doc/**",
|
||||||
]
|
]
|
||||||
rust-version = "1.63"
|
rust-version = "1.77"
|
||||||
|
|
||||||
[dependencies]
|
[dependencies]
|
||||||
rosrust_msg = { version = "0.1", optional = true }
|
rosrust_msg = { version = "0.1.8", optional = true }
|
||||||
rosrust = { version = "0.9.11", optional = true }
|
rosrust = { version = "0.9.12", optional = true }
|
||||||
r2r = { version = "0.9", optional = true }
|
r2r = { version = "0.9", optional = true }
|
||||||
rayon = { version = "1", optional = true }
|
rayon = { version = "1", optional = true }
|
||||||
nalgebra = { version = "0.33", optional = true, default-features = false }
|
nalgebra = { version = "0.33", optional = true, default-features = false }
|
||||||
rpcl2-derive = { version = "0.3", optional = true }
|
rpcl2-derive = { version = "0.4", optional = true }
|
||||||
memoffset = { version = "0.9", optional = true }
|
memoffset = { version = "0.9", optional = true }
|
||||||
|
serde = { version = "1.0", features = ["derive"], optional = true }
|
||||||
|
|
||||||
sensor_msgs = { version = "*", optional = true }
|
sensor_msgs = { version = "*", optional = true }
|
||||||
std_msgs = { version = "*", optional = true }
|
std_msgs = { version = "*", optional = true }
|
||||||
builtin_interfaces = { version = "*", optional = true }
|
builtin_interfaces = { version = "*", optional = true }
|
||||||
|
|
||||||
[dev-dependencies]
|
[dev-dependencies]
|
||||||
rand = "0.8"
|
|
||||||
criterion = { version = "0.5", features = ["html_reports"] }
|
criterion = { version = "0.5", features = ["html_reports"] }
|
||||||
pretty_assertions = "1.0"
|
pretty_assertions = "1.0"
|
||||||
|
|
||||||
[features]
|
[features]
|
||||||
|
serde = ["dep:serde", "nalgebra/serde-serialize-no-std"]
|
||||||
rclrs_msg = ["dep:sensor_msgs", "dep:std_msgs", "dep:builtin_interfaces"]
|
rclrs_msg = ["dep:sensor_msgs", "dep:std_msgs", "dep:builtin_interfaces"]
|
||||||
rosrust_msg = ["dep:rosrust_msg", "dep:rosrust"]
|
rosrust_msg = ["dep:rosrust_msg", "dep:rosrust"]
|
||||||
r2r_msg = ["dep:r2r"]
|
r2r_msg = ["dep:r2r"]
|
||||||
|
|
@ -59,6 +60,6 @@ std = ["nalgebra/std"]
|
||||||
default = ["std", "rclrs_msg"]
|
default = ["std", "rclrs_msg"]
|
||||||
|
|
||||||
[package.metadata.docs.rs]
|
[package.metadata.docs.rs]
|
||||||
features = ["derive", "nalgebra", "rayon"]
|
features = ["derive", "nalgebra", "rayon", "serde"]
|
||||||
default-target = "x86_64-unknown-linux-gnu"
|
default-target = "x86_64-unknown-linux-gnu"
|
||||||
rustdoc-args = ["--cfg", "docsrs"]
|
rustdoc-args = ["--cfg", "docsrs"]
|
||||||
|
|
|
||||||
|
|
@ -7,7 +7,7 @@
|
||||||
|
|
||||||
ros_pointcloud2 uses its own type for the message `PointCloud2Msg` to keep the library framework agnostic. ROS1 and ROS2 are supported with feature flags.
|
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.
|
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.2/) for a complete guide.
|
||||||
|
|
||||||
## Quickstart
|
## Quickstart
|
||||||
|
|
||||||
|
|
@ -68,7 +68,7 @@ Features do not work properly with `rcrls` because the messages are linked exter
|
||||||
|
|
||||||
```toml
|
```toml
|
||||||
[dependencies]
|
[dependencies]
|
||||||
ros_pointcloud2 = { git = "https://github.com/stelzo/ros_pointcloud2", tag = "v0.5.1_rclrs" }
|
ros_pointcloud2 = { git = "https://github.com/stelzo/ros_pointcloud2", tag = "v0.5.2_rclrs" }
|
||||||
```
|
```
|
||||||
|
|
||||||
Also, indicate the following dependencies to your linker inside the `package.xml` of your package.
|
Also, indicate the following dependencies to your linker inside the `package.xml` of your package.
|
||||||
|
|
|
||||||
|
|
@ -148,6 +148,9 @@ pub mod iterator;
|
||||||
|
|
||||||
use crate::ros::{HeaderMsg, PointFieldMsg};
|
use crate::ros::{HeaderMsg, PointFieldMsg};
|
||||||
|
|
||||||
|
#[cfg(feature = "serde")]
|
||||||
|
use serde::{Deserialize, Serialize};
|
||||||
|
|
||||||
#[cfg(feature = "derive")]
|
#[cfg(feature = "derive")]
|
||||||
#[doc(hidden)]
|
#[doc(hidden)]
|
||||||
pub use memoffset;
|
pub use memoffset;
|
||||||
|
|
@ -285,6 +288,7 @@ impl LayoutField {
|
||||||
/// To assert consistency, the type should be build with the [`PointCloud2MsgBuilder`].
|
/// 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.
|
/// 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)]
|
#[derive(Clone, Debug)]
|
||||||
|
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
|
||||||
pub struct PointCloud2Msg {
|
pub struct PointCloud2Msg {
|
||||||
pub header: HeaderMsg,
|
pub header: HeaderMsg,
|
||||||
pub dimensions: CloudDimensions,
|
pub dimensions: CloudDimensions,
|
||||||
|
|
@ -298,6 +302,7 @@ pub struct PointCloud2Msg {
|
||||||
|
|
||||||
/// Endianess encoding hint for the message.
|
/// Endianess encoding hint for the message.
|
||||||
#[derive(Default, Clone, Debug, PartialEq, Copy)]
|
#[derive(Default, Clone, Debug, PartialEq, Copy)]
|
||||||
|
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
|
||||||
pub enum Endian {
|
pub enum Endian {
|
||||||
Big,
|
Big,
|
||||||
#[default]
|
#[default]
|
||||||
|
|
@ -306,6 +311,7 @@ pub enum Endian {
|
||||||
|
|
||||||
/// Density flag for the message. Writing sparse point clouds is not supported.
|
/// Density flag for the message. Writing sparse point clouds is not supported.
|
||||||
#[derive(Default, Clone, Debug, PartialEq, Copy)]
|
#[derive(Default, Clone, Debug, PartialEq, Copy)]
|
||||||
|
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
|
||||||
pub enum Denseness {
|
pub enum Denseness {
|
||||||
#[default]
|
#[default]
|
||||||
Dense,
|
Dense,
|
||||||
|
|
@ -461,6 +467,7 @@ impl PointCloud2MsgBuilder {
|
||||||
|
|
||||||
/// Dimensions of the point cloud as width and height.
|
/// Dimensions of the point cloud as width and height.
|
||||||
#[derive(Clone, Debug, Default)]
|
#[derive(Clone, Debug, Default)]
|
||||||
|
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
|
||||||
pub struct CloudDimensions {
|
pub struct CloudDimensions {
|
||||||
pub width: u32,
|
pub width: u32,
|
||||||
pub height: u32,
|
pub height: u32,
|
||||||
|
|
|
||||||
217
src/points.rs
217
src/points.rs
|
|
@ -1,6 +1,9 @@
|
||||||
//! Predefined point types commonly used in ROS.
|
//! Predefined point types commonly used in ROS.
|
||||||
use crate::{LayoutDescription, LayoutField, PointConvertible, RPCL2Point};
|
use crate::{LayoutDescription, LayoutField, PointConvertible, RPCL2Point};
|
||||||
|
|
||||||
|
#[cfg(feature = "serde")]
|
||||||
|
use serde::{Deserialize, Serialize};
|
||||||
|
|
||||||
/// A packed RGB color encoding as used in ROS tools.
|
/// A packed RGB color encoding as used in ROS tools.
|
||||||
#[derive(Clone, Copy)]
|
#[derive(Clone, Copy)]
|
||||||
#[repr(C, align(4))]
|
#[repr(C, align(4))]
|
||||||
|
|
@ -40,6 +43,29 @@ impl core::fmt::Debug for RGB {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#[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)
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
impl RGB {
|
impl RGB {
|
||||||
#[must_use]
|
#[must_use]
|
||||||
pub fn new(r: u8, g: u8, b: u8) -> Self {
|
pub fn new(r: u8, g: u8, b: u8) -> Self {
|
||||||
|
|
@ -107,6 +133,7 @@ impl From<f32> for RGB {
|
||||||
/// This is a 3D point with x, y, z coordinates.
|
/// This is a 3D point with x, y, z coordinates.
|
||||||
#[derive(Clone, Debug, PartialEq, Copy, Default)]
|
#[derive(Clone, Debug, PartialEq, Copy, Default)]
|
||||||
#[repr(C, align(16))]
|
#[repr(C, align(16))]
|
||||||
|
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
|
||||||
pub struct PointXYZ {
|
pub struct PointXYZ {
|
||||||
pub x: f32,
|
pub x: f32,
|
||||||
pub y: f32,
|
pub y: f32,
|
||||||
|
|
@ -114,6 +141,7 @@ pub struct PointXYZ {
|
||||||
}
|
}
|
||||||
|
|
||||||
#[cfg(feature = "nalgebra")]
|
#[cfg(feature = "nalgebra")]
|
||||||
|
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||||
impl From<nalgebra::Point3<f32>> for PointXYZ {
|
impl From<nalgebra::Point3<f32>> for PointXYZ {
|
||||||
fn from(point: nalgebra::Point3<f32>) -> Self {
|
fn from(point: nalgebra::Point3<f32>) -> Self {
|
||||||
Self {
|
Self {
|
||||||
|
|
@ -125,12 +153,73 @@ impl From<nalgebra::Point3<f32>> for PointXYZ {
|
||||||
}
|
}
|
||||||
|
|
||||||
#[cfg(feature = "nalgebra")]
|
#[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> {
|
impl From<PointXYZ> for nalgebra::Point3<f32> {
|
||||||
fn from(point: PointXYZ) -> Self {
|
fn from(point: PointXYZ) -> Self {
|
||||||
nalgebra::Point3::new(point.x, point.y, point.z)
|
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 {
|
impl PointXYZ {
|
||||||
#[must_use]
|
#[must_use]
|
||||||
pub fn new(x: f32, y: f32, z: f32) -> Self {
|
pub fn new(x: f32, y: f32, z: f32) -> Self {
|
||||||
|
|
@ -139,9 +228,22 @@ impl PointXYZ {
|
||||||
|
|
||||||
/// Get the coordinates as a nalgebra Point3.
|
/// Get the coordinates as a nalgebra Point3.
|
||||||
#[cfg(feature = "nalgebra")]
|
#[cfg(feature = "nalgebra")]
|
||||||
|
#[deprecated(since = "0.5.2", note = "please use `xyz_f32` instead")]
|
||||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||||
pub fn xyz(&self) -> nalgebra::Point3<f32> {
|
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()
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
@ -175,6 +277,7 @@ unsafe impl PointConvertible<3> for PointXYZ {
|
||||||
/// This is a 3D point with x, y, z coordinates and an intensity value.
|
/// This is a 3D point with x, y, z coordinates and an intensity value.
|
||||||
#[derive(Clone, Debug, PartialEq, Copy, Default)]
|
#[derive(Clone, Debug, PartialEq, Copy, Default)]
|
||||||
#[repr(C, align(16))]
|
#[repr(C, align(16))]
|
||||||
|
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
|
||||||
pub struct PointXYZI {
|
pub struct PointXYZI {
|
||||||
pub x: f32,
|
pub x: f32,
|
||||||
pub y: f32,
|
pub y: f32,
|
||||||
|
|
@ -190,9 +293,22 @@ impl PointXYZI {
|
||||||
/// Get the coordinates as a nalgebra Point3.
|
/// Get the coordinates as a nalgebra Point3.
|
||||||
#[cfg(feature = "nalgebra")]
|
#[cfg(feature = "nalgebra")]
|
||||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||||
|
#[deprecated(since = "0.5.2", note = "please use `xyz_f32` instead")]
|
||||||
pub fn xyz(&self) -> nalgebra::Point3<f32> {
|
pub fn xyz(&self) -> nalgebra::Point3<f32> {
|
||||||
nalgebra::Point3::new(self.x, self.y, self.z)
|
nalgebra::Point3::new(self.x, self.y, self.z)
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#[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 {}
|
unsafe impl Send for PointXYZI {}
|
||||||
|
|
@ -236,6 +352,7 @@ unsafe impl PointConvertible<4> for PointXYZI {
|
||||||
/// This is a 3D point with x, y, z coordinates and a label.
|
/// This is a 3D point with x, y, z coordinates and a label.
|
||||||
#[derive(Clone, Debug, PartialEq, Copy, Default)]
|
#[derive(Clone, Debug, PartialEq, Copy, Default)]
|
||||||
#[repr(C, align(16))]
|
#[repr(C, align(16))]
|
||||||
|
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
|
||||||
pub struct PointXYZL {
|
pub struct PointXYZL {
|
||||||
pub x: f32,
|
pub x: f32,
|
||||||
pub y: f32,
|
pub y: f32,
|
||||||
|
|
@ -251,9 +368,22 @@ impl PointXYZL {
|
||||||
/// Get the coordinates as a nalgebra Point3.
|
/// Get the coordinates as a nalgebra Point3.
|
||||||
#[cfg(feature = "nalgebra")]
|
#[cfg(feature = "nalgebra")]
|
||||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||||
|
#[deprecated(since = "0.5.2", note = "please use `xyz_f32` instead")]
|
||||||
pub fn xyz(&self) -> nalgebra::Point3<f32> {
|
pub fn xyz(&self) -> nalgebra::Point3<f32> {
|
||||||
nalgebra::Point3::new(self.x, self.y, self.z)
|
nalgebra::Point3::new(self.x, self.y, self.z)
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#[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 {}
|
unsafe impl Send for PointXYZL {}
|
||||||
|
|
@ -297,6 +427,7 @@ unsafe impl PointConvertible<4> for PointXYZL {
|
||||||
/// This is a 3D point with x, y, z coordinates and an RGB color value.
|
/// This is a 3D point with x, y, z coordinates and an RGB color value.
|
||||||
#[derive(Clone, Debug, PartialEq, Copy, Default)]
|
#[derive(Clone, Debug, PartialEq, Copy, Default)]
|
||||||
#[repr(C, align(16))]
|
#[repr(C, align(16))]
|
||||||
|
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
|
||||||
pub struct PointXYZRGB {
|
pub struct PointXYZRGB {
|
||||||
pub x: f32,
|
pub x: f32,
|
||||||
pub y: f32,
|
pub y: f32,
|
||||||
|
|
@ -329,9 +460,22 @@ impl PointXYZRGB {
|
||||||
/// Get the coordinates as a nalgebra Point3.
|
/// Get the coordinates as a nalgebra Point3.
|
||||||
#[cfg(feature = "nalgebra")]
|
#[cfg(feature = "nalgebra")]
|
||||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||||
|
#[deprecated(since = "0.5.2", note = "please use `xyz_f32` instead")]
|
||||||
pub fn xyz(&self) -> nalgebra::Point3<f32> {
|
pub fn xyz(&self) -> nalgebra::Point3<f32> {
|
||||||
nalgebra::Point3::new(self.x, self.y, self.z)
|
nalgebra::Point3::new(self.x, self.y, self.z)
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#[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 {}
|
unsafe impl Send for PointXYZRGB {}
|
||||||
|
|
@ -376,6 +520,7 @@ unsafe impl PointConvertible<4> for PointXYZRGB {
|
||||||
/// The alpha channel is commonly used as padding but this crate uses every channel and no padding.
|
/// The alpha channel is commonly used as padding but this crate uses every channel and no padding.
|
||||||
#[derive(Clone, Debug, PartialEq, Copy, Default)]
|
#[derive(Clone, Debug, PartialEq, Copy, Default)]
|
||||||
#[repr(C, align(16))]
|
#[repr(C, align(16))]
|
||||||
|
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
|
||||||
pub struct PointXYZRGBA {
|
pub struct PointXYZRGBA {
|
||||||
pub x: f32,
|
pub x: f32,
|
||||||
pub y: f32,
|
pub y: f32,
|
||||||
|
|
@ -409,9 +554,22 @@ impl PointXYZRGBA {
|
||||||
/// Get the coordinates as a nalgebra Point3.
|
/// Get the coordinates as a nalgebra Point3.
|
||||||
#[cfg(feature = "nalgebra")]
|
#[cfg(feature = "nalgebra")]
|
||||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||||
|
#[deprecated(since = "0.5.2", note = "please use `xyz_f32` instead")]
|
||||||
pub fn xyz(&self) -> nalgebra::Point3<f32> {
|
pub fn xyz(&self) -> nalgebra::Point3<f32> {
|
||||||
nalgebra::Point3::new(self.x, self.y, self.z)
|
nalgebra::Point3::new(self.x, self.y, self.z)
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#[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 {}
|
unsafe impl Send for PointXYZRGBA {}
|
||||||
|
|
@ -459,6 +617,7 @@ unsafe impl PointConvertible<5> for PointXYZRGBA {
|
||||||
/// This is a 3D point with x, y, z coordinates, an RGB color value and a normal vector.
|
/// This is a 3D point with x, y, z coordinates, an RGB color value and a normal vector.
|
||||||
#[derive(Clone, Debug, PartialEq, Copy, Default)]
|
#[derive(Clone, Debug, PartialEq, Copy, Default)]
|
||||||
#[repr(C, align(16))]
|
#[repr(C, align(16))]
|
||||||
|
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
|
||||||
pub struct PointXYZRGBNormal {
|
pub struct PointXYZRGBNormal {
|
||||||
pub x: f32,
|
pub x: f32,
|
||||||
pub y: f32,
|
pub y: f32,
|
||||||
|
|
@ -509,9 +668,22 @@ impl PointXYZRGBNormal {
|
||||||
/// Get the coordinates as a nalgebra Point3.
|
/// Get the coordinates as a nalgebra Point3.
|
||||||
#[cfg(feature = "nalgebra")]
|
#[cfg(feature = "nalgebra")]
|
||||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||||
|
#[deprecated(since = "0.5.2", note = "please use `xyz_f32` instead")]
|
||||||
pub fn xyz(&self) -> nalgebra::Point3<f32> {
|
pub fn xyz(&self) -> nalgebra::Point3<f32> {
|
||||||
nalgebra::Point3::new(self.x, self.y, self.z)
|
nalgebra::Point3::new(self.x, self.y, self.z)
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#[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 {}
|
unsafe impl Send for PointXYZRGBNormal {}
|
||||||
|
|
@ -565,6 +737,7 @@ unsafe impl PointConvertible<7> for PointXYZRGBNormal {
|
||||||
/// This is a 3D point with x, y, z coordinates, an intensity value and a normal vector.
|
/// This is a 3D point with x, y, z coordinates, an intensity value and a normal vector.
|
||||||
#[derive(Clone, Debug, PartialEq, Copy, Default)]
|
#[derive(Clone, Debug, PartialEq, Copy, Default)]
|
||||||
#[repr(C, align(16))]
|
#[repr(C, align(16))]
|
||||||
|
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
|
||||||
pub struct PointXYZINormal {
|
pub struct PointXYZINormal {
|
||||||
pub x: f32,
|
pub x: f32,
|
||||||
pub y: f32,
|
pub y: f32,
|
||||||
|
|
@ -600,9 +773,21 @@ impl PointXYZINormal {
|
||||||
/// Get the coordinates as a nalgebra Point3.
|
/// Get the coordinates as a nalgebra Point3.
|
||||||
#[cfg(feature = "nalgebra")]
|
#[cfg(feature = "nalgebra")]
|
||||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||||
|
#[deprecated(since = "0.5.2", note = "please use `xyz_f32` instead")]
|
||||||
pub fn xyz(&self) -> nalgebra::Point3<f32> {
|
pub fn xyz(&self) -> nalgebra::Point3<f32> {
|
||||||
nalgebra::Point3::new(self.x, self.y, self.z)
|
nalgebra::Point3::new(self.x, self.y, self.z)
|
||||||
}
|
}
|
||||||
|
#[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 {}
|
unsafe impl Send for PointXYZINormal {}
|
||||||
|
|
@ -656,6 +841,7 @@ unsafe impl PointConvertible<7> for PointXYZINormal {
|
||||||
/// This is a 3D point with x, y, z coordinates and a label.
|
/// This is a 3D point with x, y, z coordinates and a label.
|
||||||
#[derive(Clone, Debug, PartialEq, Copy, Default)]
|
#[derive(Clone, Debug, PartialEq, Copy, Default)]
|
||||||
#[repr(C, align(16))]
|
#[repr(C, align(16))]
|
||||||
|
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
|
||||||
pub struct PointXYZRGBL {
|
pub struct PointXYZRGBL {
|
||||||
pub x: f32,
|
pub x: f32,
|
||||||
pub y: f32,
|
pub y: f32,
|
||||||
|
|
@ -698,9 +884,22 @@ impl PointXYZRGBL {
|
||||||
/// Get the coordinates as a nalgebra Point3.
|
/// Get the coordinates as a nalgebra Point3.
|
||||||
#[cfg(feature = "nalgebra")]
|
#[cfg(feature = "nalgebra")]
|
||||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||||
|
#[deprecated(since = "0.5.2", note = "please use `xyz_f32` instead")]
|
||||||
pub fn xyz(&self) -> nalgebra::Point3<f32> {
|
pub fn xyz(&self) -> nalgebra::Point3<f32> {
|
||||||
nalgebra::Point3::new(self.x, self.y, self.z)
|
nalgebra::Point3::new(self.x, self.y, self.z)
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#[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 {
|
impl From<RPCL2Point<5>> for PointXYZRGBL {
|
||||||
|
|
@ -745,6 +944,7 @@ unsafe impl PointConvertible<5> for PointXYZRGBL {
|
||||||
/// This is a 3D point with x, y, z coordinates and a normal vector.
|
/// This is a 3D point with x, y, z coordinates and a normal vector.
|
||||||
#[derive(Clone, Debug, PartialEq, Copy, Default)]
|
#[derive(Clone, Debug, PartialEq, Copy, Default)]
|
||||||
#[repr(C, align(16))]
|
#[repr(C, align(16))]
|
||||||
|
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
|
||||||
pub struct PointXYZNormal {
|
pub struct PointXYZNormal {
|
||||||
pub x: f32,
|
pub x: f32,
|
||||||
pub y: f32,
|
pub y: f32,
|
||||||
|
|
@ -770,9 +970,22 @@ impl PointXYZNormal {
|
||||||
/// Get the coordinates as a nalgebra Point3.
|
/// Get the coordinates as a nalgebra Point3.
|
||||||
#[cfg(feature = "nalgebra")]
|
#[cfg(feature = "nalgebra")]
|
||||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||||
|
#[deprecated(since = "0.5.2", note = "please use `xyz_f32` instead")]
|
||||||
pub fn xyz(&self) -> nalgebra::Point3<f32> {
|
pub fn xyz(&self) -> nalgebra::Point3<f32> {
|
||||||
nalgebra::Point3::new(self.x, self.y, self.z)
|
nalgebra::Point3::new(self.x, self.y, self.z)
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#[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 {}
|
unsafe impl Send for PointXYZNormal {}
|
||||||
|
|
@ -817,4 +1030,4 @@ unsafe impl PointConvertible<6> for PointXYZNormal {
|
||||||
LayoutField::padding(8),
|
LayoutField::padding(8),
|
||||||
])
|
])
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
||||||
|
|
@ -25,9 +25,13 @@
|
||||||
|
|
||||||
use alloc::string::String;
|
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.
|
/// [Time](https://docs.ros2.org/latest/api/builtin_interfaces/msg/Time.html) representation for ROS messages.
|
||||||
#[cfg(not(any(feature = "rclrs_msg")))]
|
#[cfg(not(any(feature = "rclrs_msg")))]
|
||||||
#[derive(Clone, Debug, Default)]
|
#[derive(Clone, Debug, Default, Copy)]
|
||||||
|
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
|
||||||
pub struct TimeMsg {
|
pub struct TimeMsg {
|
||||||
pub sec: i32,
|
pub sec: i32,
|
||||||
pub nanosec: u32,
|
pub nanosec: u32,
|
||||||
|
|
@ -48,6 +52,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).
|
/// Represents the [header of a ROS message](https://docs.ros2.org/latest/api/std_msgs/msg/Header.html).
|
||||||
#[derive(Clone, Debug, Default)]
|
#[derive(Clone, Debug, Default)]
|
||||||
|
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
|
||||||
pub struct HeaderMsg {
|
pub struct HeaderMsg {
|
||||||
pub seq: u32,
|
pub seq: u32,
|
||||||
pub stamp: TimeMsg,
|
pub stamp: TimeMsg,
|
||||||
|
|
@ -56,6 +61,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.
|
/// 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)]
|
#[derive(Clone, Debug)]
|
||||||
|
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
|
||||||
pub struct PointFieldMsg {
|
pub struct PointFieldMsg {
|
||||||
pub name: String,
|
pub name: String,
|
||||||
pub offset: u32,
|
pub offset: u32,
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue