Compare commits

...

48 Commits

Author SHA1 Message Date
stelzo 23ede229c7 add 0.5.2 main changes 2025-02-04 15:43:34 +01:00
stelzo 64f1c7cb95 bump version 2024-10-04 14:40:18 +02:00
stelzo a02016e3dd fix subtype iterator mapping 2024-10-04 13:04:23 +02:00
stelzo e6b7649a88 merge 2024-06-24 11:28:38 +02:00
stelzo 4c0db66585 bump derive 2024-06-24 11:24:49 +02:00
stelzo 43f3d4e42b
bump version 2024-06-23 19:51:09 +02:00
stelzo 10eb323074
bump version 2024-06-23 19:45:58 +02:00
stelzo a2076137c6
missing dep 2024-06-23 19:34:32 +02:00
stelzo e9591cb70e
override pip sys deps for colcon 2024-06-23 19:25:00 +02:00
stelzo d72a4491d4
unsafe impl in tests 2024-06-23 19:20:29 +02:00
stelzo 4b9a4ddae3
fix subfolder 2024-06-23 19:10:15 +02:00
stelzo 7d0d7d53a0
rclrs jazzy tests 2024-06-23 19:05:41 +02:00
Christopher Sieh ff5452f6b5
merge main 2024-06-22 11:14:06 +02:00
stelzo b5fc791776 rc.3 2024-05-21 13:34:25 +02:00
stelzo d7d51e0cc2
merge main 2024-05-20 01:20:39 +02:00
stelzo f69dfe93f2
merge main toml 2024-05-20 01:14:27 +02:00
stelzo e84a32fcf7 remove warning 2024-05-17 14:37:28 +02:00
stelzo 1654cdedfd tidy for tag support 2024-05-17 14:28:14 +02:00
stelzo 91a81436c7
merge main 2024-05-16 00:04:21 +02:00
stelzo 0f5f481962
merge main 2024-05-15 23:01:48 +02:00
stelzo acab42d203
prepare version 2024-05-15 22:56:55 +02:00
stelzo d67518abff
specify licensing 2024-05-15 22:02:39 +02:00
stelzo 806536762e
move to dual license, inline crate for syn2 2024-05-15 21:46:00 +02:00
stelzo 940c7b1623
add cfg docs 2024-05-15 21:27:10 +02:00
stelzo 756647e44f merge no_std 2024-05-15 18:42:45 +02:00
stelzo 529c7e1a77 no_std compatible 2024-05-15 18:36:53 +02:00
stelzo b2e9209333
merge main 2024-05-14 21:50:28 +02:00
stelzo fe73a1b613
merge main 2024-04-29 23:09:33 +02:00
stelzo 12d0716b9b
no unwrap needed anymore 2024-04-29 21:52:49 +02:00
stelzo be7c7691ff
fix imports 2024-04-29 21:43:03 +02:00
stelzo 2bb8bab5f0
merge iterator 2024-04-29 21:30:46 +02:00
stelzo d0745c4390
no optional point collect 2024-04-29 21:16:01 +02:00
stelzo 01cf6f2ded
no convert 2024-04-29 20:58:20 +02:00
stelzo 212f7b05cc
fix rosrust time 2024-04-29 20:45:01 +02:00
stelzo 91b0ae7ecf
docs and clippy 2024-04-29 20:32:55 +02:00
stelzo 77c222414f
redo api 2024-04-29 17:27:32 +02:00
stelzo 6f55407a20
add iterator impl 2024-04-26 21:50:23 +02:00
stelzo 3cd237037f bump version 2024-03-25 15:16:12 +01:00
stelzo ae71306e54 iron testing 2024-03-25 13:07:58 +01:00
stelzo b5f008a71d no feature needed 2024-03-25 13:05:51 +01:00
stelzo 8d951d46ef run clippy in docker 2024-03-25 12:51:49 +01:00
stelzo e8776b5e17 clean actions 2024-03-25 12:46:27 +01:00
stelzo 58bd17ab6b add testing deps 2024-03-25 12:37:34 +01:00
stelzo f2023286eb Merge branch 'rclrs-instructions' into rclrs 2024-03-25 11:50:12 +01:00
stelzo 32bdd072c8 default param to simplify instructions 2024-03-25 11:50:09 +01:00
Christopher Sieh 40b6ce6653 add rclrs usage 2024-03-25 11:33:33 +01:00
Christopher Sieh 6d5e067bf6 fix stamp naming 2024-03-21 16:43:11 +01:00
Christopher Sieh 0d99a2e5c1 adds rclrs support 2024-03-21 16:32:33 +01:00
25 changed files with 1135 additions and 2242 deletions

21
.github/workflows/rclrs_jazzy.yml vendored Normal file
View File

@ -0,0 +1,21 @@
name: rclrs_jazzy
on:
push:
branches:
- rclrs
pull_request:
branches:
- rclrs
workflow_dispatch:
env:
CARGO_TERM_COLOR: always
jobs:
tests_jazzy:
runs-on: ubuntu-latest
steps:
- uses: actions/checkout@v2
- run: docker build . --file ./tests/Dockerfile_rclrs_jazzy --tag rclrs_jazzy
- run: docker run rclrs_jazzy cargo test --features derive,nalgebra,rayon

View File

@ -1,6 +1,6 @@
[package]
name = "ros_pointcloud2"
version = "0.5.0-rc.1"
version = "0.5.1"
edition = "2021"
authors = ["Christopher Sieh <stelzo@steado.de>"]
description = "Customizable conversions for working with sensor_msgs/PointCloud2."
@ -8,56 +8,58 @@ repository = "https://github.com/stelzo/ros_pointcloud2"
license = "MIT OR Apache-2.0"
keywords = ["ros", "pointcloud2", "pointcloud", "message"]
categories = [
"science::robotics",
"encoding",
"data-structures",
"api-bindings",
"science::robotics",
"encoding",
"data-structures",
"api-bindings",
]
readme = "README.md"
documentation = "https://docs.rs/ros_pointcloud2"
homepage = "https://github.com/stelzo/ros_pointcloud2"
exclude = [
"**/.github/**",
"**/tests/**",
"**/examples/**",
"**/benches/**",
"**/target/**",
"**/build/**",
"**/dist/**",
"**/docs/**",
"**/doc/**",
"**/.github/**",
"**/tests/**",
"**/examples/**",
"**/benches/**",
"**/target/**",
"**/build/**",
"**/dist/**",
"**/docs/**",
"**/doc/**",
]
rust-version = "1.63"
rust-version = "1.77"
[dependencies]
rosrust_msg = { version = "0.1", optional = true }
rosrust = { version = "0.9.11", optional = true }
r2r = { version = "0.8.4", optional = true }
rosrust_msg = { version = "0.1.8", optional = true }
rosrust = { version = "0.9.12", optional = true }
r2r = { version = "0.9", optional = true }
rayon = { version = "1", optional = true }
nalgebra = { version = "0.32.5", optional = true, default-features = false }
rpcl2_derive = { path = "rpcl2_derive", optional = true }
type-layout = { path = "type-layout", optional = true }
nalgebra = { version = "0.33", optional = true, default-features = false }
rpcl2-derive = { version = "0.4", optional = true }
memoffset = { version = "0.9", optional = true }
serde = { version = "1.0", features = ["derive"], optional = true }
sensor_msgs = { version = "*", optional = true }
std_msgs = { version = "*", optional = true }
builtin_interfaces = { version = "*", optional = true }
[dev-dependencies]
rand = "0.8"
criterion = { version = "0.5", features = ["html_reports"] }
[[bench]]
name = "roundtrip"
harness = false
pretty_assertions = "1.0"
[features]
serde = ["dep:serde", "nalgebra/serde-serialize-no-std"]
rclrs_msg = ["dep:sensor_msgs", "dep:std_msgs", "dep:builtin_interfaces"]
rosrust_msg = ["dep:rosrust_msg", "dep:rosrust"]
r2r_msg = ["dep:r2r"]
rayon = ["dep:rayon"]
derive = ["dep:rpcl2_derive", "dep:type-layout"]
derive = ["dep:rpcl2-derive", "dep:memoffset"]
nalgebra = ["dep:nalgebra"]
std = ["nalgebra/std"]
default = ["std", "derive"]
default = ["std", "rclrs_msg"]
[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

@ -1,6 +1,3 @@
> [!NOTE]
> This library is currently in preparation for v0.5 with many breaking changes. For the documentation of the current crates.io v0.4.0, visit the [docs](https://docs.rs/ros_pointcloud2/0.4.0/ros_pointcloud2/). Since rclrs still needs a workaround, the version number must be changed to your desired version which supports rclrs (currently only v0.4.0) — regardless of the version number shown in this Readme.
<p align="center">
<h3 align="center">ROS PointCloud2</h3>
<p align="center">A PointCloud2 message conversion library.</p>
@ -10,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.
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.0-rc.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
@ -60,9 +57,9 @@ You can use `rosrust` and `r2r` by enabling the respective feature:
```toml
[dependencies]
ros_pointcloud2 = { version = "*", features = ["r2r_msg", "derive"]}
ros_pointcloud2 = { version = "*", features = ["r2r_msg"]}
# or
ros_pointcloud2 = { version = "*", features = ["rosrust_msg", "derive"]}
ros_pointcloud2 = { version = "*", features = ["rosrust_msg"]}
```
### rclrs (ros2_rust)
@ -71,7 +68,7 @@ Features do not work properly with `rcrls` because the messages are linked exter
```toml
[dependencies]
ros_pointcloud2 = { git = "https://github.com/stelzo/ros_pointcloud2", tag = "v0.5.0-rc.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.
@ -87,30 +84,21 @@ 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](https://github.com/stelzo/ros_pcl_conv_bench).
See [this repository](https://github.com/stelzo/ros_pcl_conv_bench) for a detailed benchmark.
For minimizing the conversion overhead in general, always use the functions that best fit your use case.
## `no_std` Environments
### License
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.
<sup>
Licensed under either of <a href="LICENSE-APACHE">Apache License, Version
2.0</a> or <a href="LICENSE-MIT">MIT license</a> at your option.
</sup>
## License
<br>
Licensed under either of
- Apache License, Version 2.0, ([LICENSE-APACHE](LICENSE-APACHE) or http://www.apache.org/licenses/LICENSE-2.0)
- MIT license ([LICENSE-MIT](LICENSE-MIT) or http://opensource.org/licenses/MIT)
at your option.
### type-layout
For compatibility reasons, a patched version of `type-layout` is included in this repository. The original crate can be found [here](https://crates.io/crates/type-layout). After the patch is applied on the original `type-layout` crate ([PR](https://github.com/LPGhatguy/type-layout/pull/9)), the local dependency will be changed to the original crate.
`type-layout` is licensed under MIT or Apache-2.0 and Copyright by Lucien Greathouse. The changes are highlighted in the diff of the PR.
### 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.
<sub>
Unless you explicitly state otherwise, any contribution intentionally submitted
for inclusion in this crate by you, as defined in the Apache-2.0 license, shall
be dual licensed as above, without any additional terms or conditions.
</sub>

View File

@ -1,695 +0,0 @@
use criterion::{black_box, criterion_group, criterion_main, Criterion};
use ros_pointcloud2::prelude::*;
use rand::Rng;
pub type PointXYZB = PointXYZINormal;
pub fn distance_to_origin(point: &PointXYZ) -> f32 {
((point.x.powi(2)) + (point.y.powi(2)) + (point.z.powi(2))).sqrt()
}
pub fn dot_product(point1: &PointXYZ, point2: &PointXYZ) -> f32 {
point1.x * point2.x + point1.y * point2.y + point1.z * point2.z
}
pub fn cross_product(point1: &PointXYZ, point2: &PointXYZ) -> PointXYZ {
PointXYZ {
x: point1.y * point2.z - point1.z * point2.y,
y: point1.z * point2.x - point1.x * point2.z,
z: point1.x * point2.y - point1.y * point2.x,
}
}
pub fn scalar_multiply(point: &PointXYZ, scalar: f32) -> PointXYZ {
PointXYZ {
x: point.x * scalar,
y: point.y * scalar,
z: point.z * scalar,
}
}
pub fn magnitude_squared(point: &PointXYZ) -> f32 {
(point.x.powi(2)) + (point.y.powi(2)) + (point.z.powi(2))
}
pub fn reflection_through_plane(
point: &PointXYZ,
normal: &PointXYZ,
point_on_plane: &PointXYZ,
) -> PointXYZ {
PointXYZ {
x: point.x
- 2.0
* ((point.x - point_on_plane.x) * normal.x
+ (point.y - point_on_plane.y) * normal.y
+ (point.z - point_on_plane.z) * normal.z),
y: point.y
- 2.0
* ((point.x - point_on_plane.x) * normal.x
+ (point.y - point_on_plane.y) * normal.y
+ (point.z - point_on_plane.z) * normal.z),
z: point.z
- 2.0
* ((point.x - point_on_plane.x) * normal.x
+ (point.y - point_on_plane.y) * normal.y
+ (point.z - point_on_plane.z) * normal.z),
}
}
pub fn rotation_about_x(point: &PointXYZ, angle: f32) -> PointXYZ {
let c = f32::cos(angle);
let s = f32::sin(angle);
PointXYZ {
x: point.x,
y: point.y * c - point.z * s,
z: point.y * s + point.z * c,
}
}
pub fn closest_point_on_line(
point: &PointXYZ,
line_point: &PointXYZ,
line_direction: &PointXYZ,
) -> PointXYZ {
PointXYZ {
x: line_point.x
+ (line_point.x - point.x) * ((line_point.x - point.x).powi(2))
/ ((line_direction.x * 2.0).powi(2))
+ (line_direction.y * 2.0) * (point.z - line_point.z)
/ ((line_direction.z * 2.0).powi(2)),
y: line_point.y
+ (line_point.y - point.y) * ((line_point.y - point.y).powi(2))
/ ((line_direction.y * 2.0).powi(2))
+ (line_direction.x * 2.0) * (point.x - line_point.x)
/ ((line_direction.x * 2.0).powi(2)),
z: line_point.z
+ (line_point.z - point.z) * ((line_point.z - point.z).powi(2))
/ ((line_direction.z * 2.0).powi(2))
+ (line_direction.y * 2.0) * (point.y - line_point.y)
/ ((line_direction.y * 2.0).powi(2)),
}
}
fn minus(point1: &PointXYZ, point2: &PointXYZ) -> PointXYZ {
PointXYZ {
x: point1.x - point2.x,
y: point1.y - point2.y,
z: point1.z - point2.z,
}
}
pub fn generate_random_pointcloud(num_points: usize, min: f32, max: f32) -> Vec<PointXYZB> {
let mut rng = rand::thread_rng();
let mut pointcloud = Vec::with_capacity(num_points);
for _ in 0..num_points {
let point = PointXYZB {
x: rng.gen_range(min..max),
y: rng.gen_range(min..max),
z: rng.gen_range(min..max),
..Default::default()
};
pointcloud.push(point);
}
pointcloud
}
pub fn heavy_computing(point: &PointXYZ, iterations: u32) -> f32 {
let mut result = distance_to_origin(point);
for _ in 0..iterations {
result += dot_product(
point,
&PointXYZ {
x: 1.0,
y: 2.0,
z: 3.0,
},
);
result += cross_product(
point,
&PointXYZ {
x: 4.0,
y: 5.0,
z: 6.0,
},
)
.x;
result = result + (result * 10.0).sqrt();
let reflected_point = reflection_through_plane(
point,
&PointXYZ {
x: 7.0,
y: 8.0,
z: 9.0,
},
&PointXYZ {
x: 3.0,
y: 4.0,
z: 5.0,
},
);
let rotated_point = rotation_about_x(
&PointXYZ {
x: 10.0,
y: 11.0,
z: 12.0,
},
std::f32::consts::PI / 2.0,
);
result += magnitude_squared(&minus(&reflected_point, &rotated_point));
}
result
}
#[cfg(feature = "derive")]
fn roundtrip_vec(cloud: Vec<PointXYZB>) -> bool {
let orig_len = cloud.len();
let internal_msg = PointCloud2Msg::try_from_vec(cloud).unwrap();
let total: Vec<PointXYZ> = internal_msg.try_into_vec().unwrap();
orig_len == total.len()
}
fn roundtrip(cloud: Vec<PointXYZB>) -> bool {
let orig_len = cloud.len();
let internal_msg = PointCloud2Msg::try_from_iter(cloud).unwrap();
let total = internal_msg
.try_into_iter()
.unwrap()
.collect::<Vec<PointXYZ>>();
orig_len == total.len()
}
#[cfg(feature = "derive")]
fn roundtrip_filter_vec(cloud: Vec<PointXYZB>) -> bool {
let orig_len = cloud.len();
let internal_msg = PointCloud2Msg::try_from_vec(cloud).unwrap();
let total = internal_msg
.try_into_iter()
.unwrap()
.filter(|point: &PointXYZ| distance_to_origin(point) < 69.9)
.fold(PointXYZ::default(), |acc, point| PointXYZ {
x: acc.x + point.x,
y: acc.y + point.y,
z: acc.z + point.z,
});
orig_len == total.x as usize
}
fn roundtrip_filter(cloud: Vec<PointXYZB>) -> bool {
let orig_len = cloud.len();
let internal_msg = PointCloud2Msg::try_from_iter(cloud).unwrap();
let total = internal_msg
.try_into_iter()
.unwrap()
.filter(|point: &PointXYZ| distance_to_origin(point) < 69.9)
.fold(PointXYZ::default(), |acc, point| PointXYZ {
x: acc.x + point.x,
y: acc.y + point.y,
z: acc.z + point.z,
});
orig_len == total.x as usize
}
fn roundtrip_computing(cloud: Vec<PointXYZB>) -> bool {
let internal_msg = PointCloud2Msg::try_from_iter(cloud).unwrap();
let total = internal_msg
.try_into_iter()
.unwrap()
.map(|point: PointXYZ| heavy_computing(&point, 100))
.sum::<f32>();
total > 0.0
}
#[cfg(feature = "rayon")]
fn roundtrip_computing_par(cloud: Vec<PointXYZB>) -> bool {
let internal_msg = PointCloud2Msg::try_from_iter(cloud).unwrap();
let total = internal_msg
.try_into_par_iter()
.unwrap()
.map(|point: PointXYZ| heavy_computing(&point, 100))
.sum::<f32>();
total > 0.0
}
#[cfg(feature = "rayon")]
fn roundtrip_computing_par_par(cloud: Vec<PointXYZB>) -> bool {
let internal_msg = PointCloud2Msg::try_from_par_iter(cloud.into_par_iter()).unwrap();
let total = internal_msg
.try_into_par_iter()
.unwrap()
.map(|point: PointXYZ| heavy_computing(&point, 100))
.sum::<f32>();
total > 0.0
}
#[cfg(feature = "derive")]
fn roundtrip_computing_vec(cloud: Vec<PointXYZB>) -> bool {
let internal_msg = PointCloud2Msg::try_from_vec(cloud).unwrap();
let total: f32 = internal_msg
.try_into_vec()
.unwrap()
.into_iter()
.map(|point: PointXYZ| heavy_computing(&point, 100))
.sum();
total > 0.0
}
#[cfg(feature = "rayon")]
fn roundtrip_par(cloud: Vec<PointXYZB>) -> bool {
let orig_len = cloud.len();
let internal_msg = PointCloud2Msg::try_from_iter(cloud).unwrap();
let total = internal_msg
.try_into_par_iter()
.unwrap()
.collect::<Vec<PointXYZ>>();
orig_len != total.len()
}
#[cfg(feature = "rayon")]
fn roundtrip_par_par(cloud: Vec<PointXYZB>) -> bool {
let orig_len = cloud.len();
let internal_msg = PointCloud2Msg::try_from_par_iter(cloud.into_par_iter()).unwrap();
let total = internal_msg
.try_into_par_iter()
.unwrap()
.collect::<Vec<PointXYZ>>();
orig_len != total.len()
}
#[cfg(feature = "rayon")]
fn roundtrip_filter_par(cloud: Vec<PointXYZB>) -> bool {
let orig_len: usize = cloud.len();
let internal_msg = PointCloud2Msg::try_from_iter(cloud).unwrap();
let total = internal_msg
.try_into_par_iter()
.unwrap()
.filter(|point: &PointXYZ| distance_to_origin(point) < 69.9)
.reduce(PointXYZ::default, |acc, point| PointXYZ {
x: acc.x + point.x,
y: acc.y + point.y,
z: acc.z + point.z,
});
orig_len == total.x as usize
}
#[cfg(feature = "rayon")]
fn roundtrip_filter_par_par(cloud: Vec<PointXYZB>) -> bool {
let orig_len: usize = cloud.len();
let internal_msg = PointCloud2Msg::try_from_par_iter(cloud.into_par_iter()).unwrap();
let total = internal_msg
.try_into_par_iter()
.unwrap()
.filter(|point: &PointXYZ| distance_to_origin(point) < 69.9)
.reduce(PointXYZ::default, |acc, point| PointXYZ {
x: acc.x + point.x,
y: acc.y + point.y,
z: acc.z + point.z,
});
orig_len == total.x as usize
}
fn roundtrip_benchmark(c: &mut Criterion) {
let cloud_points_16k = generate_random_pointcloud(16_000, f32::MIN / 2.0, f32::MAX / 2.0);
let cloud_points_60k = generate_random_pointcloud(60_000, f32::MIN / 2.0, f32::MAX / 2.0);
let cloud_points_120k = generate_random_pointcloud(120_000, f32::MIN / 2.0, f32::MAX / 2.0);
let cloud_points_500k = generate_random_pointcloud(500_000, f32::MIN / 2.0, f32::MAX / 2.0);
let cloud_points_1_5m = generate_random_pointcloud(1_500_000, f32::MIN / 2.0, f32::MAX / 2.0);
// 16k points (Velodyne with 16 beams)
// Moving memory
c.bench_function("16k iter", |b| {
b.iter(|| {
black_box(roundtrip(cloud_points_16k.clone()));
})
});
#[cfg(feature = "rayon")]
c.bench_function("16k iter_par", |b| {
b.iter(|| {
black_box(roundtrip_par(cloud_points_16k.clone()));
})
});
#[cfg(feature = "rayon")]
c.bench_function("16k iter_par_par", |b| {
b.iter(|| {
black_box(roundtrip_par_par(cloud_points_16k.clone()));
})
});
#[cfg(feature = "derive")]
c.bench_function("16k vec", |b| {
b.iter(|| {
black_box(roundtrip_vec(cloud_points_16k.clone()));
})
});
// Simple distance filter
c.bench_function("16k iter_filter", |b| {
b.iter(|| {
roundtrip_filter(black_box(cloud_points_16k.clone()));
})
});
#[cfg(feature = "rayon")]
c.bench_function("16k filter_par", |b| {
b.iter(|| {
roundtrip_filter_par(black_box(cloud_points_16k.clone()));
})
});
#[cfg(feature = "rayon")]
c.bench_function("16k filter_par_par", |b| {
b.iter(|| {
black_box(roundtrip_filter_par_par(cloud_points_16k.clone()));
})
});
#[cfg(feature = "derive")]
c.bench_function("16k vec_filter", |b| {
b.iter(|| {
roundtrip_filter_vec(black_box(cloud_points_16k.clone()));
})
});
// Heavy computing
c.bench_function("16k iter_compute", |b| {
b.iter(|| {
roundtrip_computing(black_box(cloud_points_16k.clone()));
})
});
#[cfg(feature = "rayon")]
c.bench_function("16k iter_compute_par", |b| {
b.iter(|| {
roundtrip_computing_par(black_box(cloud_points_16k.clone()));
})
});
#[cfg(feature = "rayon")]
c.bench_function("16k iter_compute_par_par", |b| {
b.iter(|| {
roundtrip_computing_par_par(black_box(cloud_points_16k.clone()));
})
});
#[cfg(feature = "derive")]
c.bench_function("16k vec_compute", |b| {
b.iter(|| {
roundtrip_computing_vec(black_box(cloud_points_16k.clone()));
})
});
// 60k points (Ouster with 64 beams)
// Moving memory
c.bench_function("60k iter", |b| {
b.iter(|| {
black_box(roundtrip(cloud_points_60k.clone()));
})
});
#[cfg(feature = "rayon")]
c.bench_function("60k iter_par", |b| {
b.iter(|| {
black_box(roundtrip_par(cloud_points_60k.clone()));
})
});
#[cfg(feature = "rayon")]
c.bench_function("60k iter_par_par", |b| {
b.iter(|| {
black_box(roundtrip_par_par(cloud_points_60k.clone()));
})
});
#[cfg(feature = "derive")]
c.bench_function("60k vec", |b| {
b.iter(|| {
black_box(roundtrip_vec(cloud_points_60k.clone()));
})
});
// 120k points (Ouster with 128 beams)
// Moving memory
c.bench_function("120k iter", |b| {
b.iter(|| {
black_box(roundtrip(cloud_points_120k.clone()));
})
});
#[cfg(feature = "rayon")]
c.bench_function("120k iter_par", |b| {
b.iter(|| {
black_box(roundtrip_par(cloud_points_120k.clone()));
})
});
#[cfg(feature = "rayon")]
c.bench_function("120k iter_par_par", |b| {
b.iter(|| {
black_box(roundtrip_par_par(cloud_points_120k.clone()));
})
});
#[cfg(feature = "derive")]
c.bench_function("120k vec", |b| {
b.iter(|| {
black_box(roundtrip_vec(cloud_points_120k.clone()));
})
});
// Simple distance filter
c.bench_function("120k iter_filter", |b| {
b.iter(|| {
roundtrip_filter(black_box(cloud_points_120k.clone()));
})
});
#[cfg(feature = "rayon")]
c.bench_function("120k filter_par", |b| {
b.iter(|| {
roundtrip_filter_par(black_box(cloud_points_120k.clone()));
})
});
#[cfg(feature = "rayon")]
c.bench_function("120k filter_par_par", |b| {
b.iter(|| {
black_box(roundtrip_filter_par_par(cloud_points_120k.clone()));
})
});
#[cfg(feature = "derive")]
c.bench_function("120k vec_filter", |b| {
b.iter(|| {
roundtrip_filter_vec(black_box(cloud_points_120k.clone()));
})
});
// Heavy computing
c.bench_function("120k iter_compute", |b| {
b.iter(|| {
roundtrip_computing(black_box(cloud_points_120k.clone()));
})
});
#[cfg(feature = "rayon")]
c.bench_function("120k iter_compute_par", |b| {
b.iter(|| {
roundtrip_computing_par(black_box(cloud_points_120k.clone()));
})
});
#[cfg(feature = "rayon")]
c.bench_function("120k iter_compute_par_par", |b| {
b.iter(|| {
roundtrip_computing_par_par(black_box(cloud_points_120k.clone()));
})
});
#[cfg(feature = "derive")]
c.bench_function("120k vec_compute", |b| {
b.iter(|| {
roundtrip_computing_vec(black_box(cloud_points_120k.clone()));
})
});
// 500k points (just to show how it scales)
// Moving memory
c.bench_function("500k iter", |b| {
b.iter(|| {
black_box(roundtrip(cloud_points_500k.clone()));
})
});
#[cfg(feature = "rayon")]
c.bench_function("500k iter_par", |b| {
b.iter(|| {
black_box(roundtrip_par(cloud_points_500k.clone()));
})
});
#[cfg(feature = "rayon")]
c.bench_function("500k iter_par_par", |b| {
b.iter(|| {
black_box(roundtrip_par_par(cloud_points_500k.clone()));
})
});
#[cfg(feature = "derive")]
c.bench_function("500k vec", |b| {
b.iter(|| {
black_box(roundtrip_vec(cloud_points_500k.clone()));
})
});
// Simple distance filter
c.bench_function("500k iter_filter", |b| {
b.iter(|| {
roundtrip_filter(black_box(cloud_points_500k.clone()));
})
});
#[cfg(feature = "rayon")]
c.bench_function("500k filter_par", |b| {
b.iter(|| {
roundtrip_filter_par(black_box(cloud_points_500k.clone()));
})
});
#[cfg(feature = "rayon")]
c.bench_function("500k filter_par_par", |b| {
b.iter(|| {
black_box(roundtrip_filter_par_par(cloud_points_500k.clone()));
})
});
#[cfg(feature = "derive")]
c.bench_function("500k vec_filter", |b| {
b.iter(|| {
roundtrip_filter_vec(black_box(cloud_points_500k.clone()));
})
});
// Heavy computing
c.bench_function("500k iter_compute", |b| {
b.iter(|| {
roundtrip_computing(black_box(cloud_points_500k.clone()));
})
});
#[cfg(feature = "rayon")]
c.bench_function("500k iter_compute_par", |b| {
b.iter(|| {
roundtrip_computing_par(black_box(cloud_points_500k.clone()));
})
});
#[cfg(feature = "rayon")]
c.bench_function("500k iter_compute_par_par", |b| {
b.iter(|| {
roundtrip_computing_par_par(black_box(cloud_points_500k.clone()));
})
});
#[cfg(feature = "derive")]
c.bench_function("500k vec_compute", |b| {
b.iter(|| {
roundtrip_computing_vec(black_box(cloud_points_500k.clone()));
})
});
// 1.5m points (scale of small localmaps in SLAM)
// Moving memory
c.bench_function("1.5m iter", |b| {
b.iter(|| {
black_box(roundtrip(cloud_points_1_5m.clone()));
})
});
#[cfg(feature = "rayon")]
c.bench_function("1.5m iter_par", |b| {
b.iter(|| {
black_box(roundtrip_par(cloud_points_1_5m.clone()));
})
});
#[cfg(feature = "rayon")]
c.bench_function("1.5m iter_par_par", |b| {
b.iter(|| {
black_box(roundtrip_par_par(cloud_points_1_5m.clone()));
})
});
#[cfg(feature = "derive")]
c.bench_function("1.5m vec", |b| {
b.iter(|| {
black_box(roundtrip_vec(cloud_points_1_5m.clone()));
})
});
// Simple distance filter
c.bench_function("1.5m iter_filter", |b| {
b.iter(|| {
roundtrip_filter(black_box(cloud_points_1_5m.clone()));
})
});
#[cfg(feature = "rayon")]
c.bench_function("1.5m iter_par_filter", |b| {
b.iter(|| {
black_box(roundtrip_filter_par(cloud_points_1_5m.clone()));
})
});
#[cfg(feature = "rayon")]
c.bench_function("1.5m iter_par_par_filter", |b| {
b.iter(|| {
black_box(roundtrip_filter_par_par(cloud_points_1_5m.clone()));
})
});
#[cfg(feature = "derive")]
c.bench_function("1.5m vec_filter", |b| {
b.iter(|| {
roundtrip_filter_vec(black_box(cloud_points_1_5m.clone()));
})
});
// Heavy computing
c.bench_function("1.5m iter_compute", |b| {
b.iter(|| {
roundtrip_computing(black_box(cloud_points_1_5m.clone()));
})
});
#[cfg(feature = "rayon")]
c.bench_function("1.5m iter_compute_par", |b| {
b.iter(|| {
roundtrip_computing_par(black_box(cloud_points_1_5m.clone()));
})
});
#[cfg(feature = "rayon")]
c.bench_function("1.5m iter_compute_par_par", |b| {
b.iter(|| {
roundtrip_computing_par_par(black_box(cloud_points_1_5m.clone()));
})
});
#[cfg(feature = "derive")]
c.bench_function("1.5m vec_compute", |b| {
b.iter(|| {
roundtrip_computing_vec(black_box(cloud_points_1_5m.clone()));
})
});
}
criterion_group!(benches, roundtrip_benchmark);
criterion_main!(benches);

View File

@ -1,159 +0,0 @@
/// This example demonstrates how to use a custom point with encoded metadata.
/// The use case is a segmentation point cloud where each point holds a label and we want to filter by it.
/// Since the datatypes for the PointCloud2 message are very limited,
/// we need to encode the enum into a supported type.
/// This needs some manual work to tell the library how to encode and decode the enum.
///
/// Important Note: This example is only possible with disabled `derive` feature,
/// because the library (currently) does not know the size of your chosen supported type at compile time.
/// This makes direct copies impossible.
use ros_pointcloud2::prelude::*;
#[derive(Debug, PartialEq, Clone, Default, Copy)]
enum Label {
#[default]
Human,
Deer,
Car,
}
// Define a custom point with an enum.
// This is normally not supported by PointCloud2 but we will explain the library how to handle it.
#[derive(Debug, PartialEq, Clone, Default)]
struct CustomPoint {
x: f32,
y: f32,
z: f32,
intensity: f32,
my_custom_label: Label,
}
// Some convenience functions to convert between the enum and u8.
impl From<Label> for u8 {
fn from(label: Label) -> Self {
match label {
Label::Human => 0,
Label::Deer => 1,
Label::Car => 2,
}
}
}
impl From<u8> for Label {
fn from(label: u8) -> Self {
match label {
0 => Label::Human,
1 => Label::Deer,
2 => Label::Car,
_ => panic!("Invalid label"),
}
}
}
impl CustomPoint {
fn new(x: f32, y: f32, z: f32, intensity: f32, my_custom_label: Label) -> Self {
Self {
x,
y,
z,
intensity,
my_custom_label,
}
}
}
// We implement the PointConvertible trait (needed for every custom point).
// RPCL2Point is the internal representation. It takes the amount of fields as generic arguments.
impl From<CustomPoint> for RPCL2Point<5> {
fn from(point: CustomPoint) -> Self {
[
point.x.into(),
point.y.into(),
point.z.into(),
point.intensity.into(),
u8::from(point.my_custom_label).into(),
]
.into()
}
}
impl From<RPCL2Point<5>> for CustomPoint {
fn from(point: RPCL2Point<5>) -> Self {
Self::new(
point[0].get(),
point[1].get(),
point[2].get(),
point[3].get(),
point[4].get(),
)
}
}
// Define wow we want to name the fields in the message.
impl Fields<5> for CustomPoint {
fn field_names_ordered() -> [&'static str; 5] {
["x", "y", "z", "intensity", "my_custom_label"]
}
}
// We implemented everything that is needed for PointConvertible so we declare it as a done.
#[cfg(not(feature = "derive"))]
impl PointConvertible<5> for CustomPoint {}
// Now we tell the library how to encode and decode the label.
// You don't need to do this if your CustomPoint has a field that is already supported by PointCloud2.
impl GetFieldDatatype for Label {
fn field_datatype() -> FieldDatatype {
FieldDatatype::U8 // Declare that we want to use u8 as the datatype for the label.
}
}
// Again, you don't need this with only supported field types.
// u8 -> Label
impl FromBytes for Label {
// Technically, PointCloud2 supports big and little endian even though it is rarely used.
// 'be' stands for big endian and 'le' for little endian.
fn from_be_bytes(bytes: PointDataBuffer) -> Self {
u8::from_be_bytes([bytes[0]]).into()
}
fn from_le_bytes(bytes: PointDataBuffer) -> Self {
u8::from_le_bytes([bytes[0]]).into()
}
}
// Label -> u8
impl From<Label> for PointDataBuffer {
fn from(label: Label) -> Self {
[u8::from(label)].into()
}
}
fn main() {
#[cfg(not(feature = "derive"))]
{
let cloud = vec![
CustomPoint::new(1.0, 2.0, 3.0, 4.0, Label::Deer),
CustomPoint::new(4.0, 5.0, 6.0, 7.0, Label::Car),
CustomPoint::new(7.0, 8.0, 9.0, 10.0, Label::Human),
];
println!("Original cloud: {:?}", cloud);
let msg = PointCloud2Msg::try_from_iter(cloud).unwrap();
println!("filtering by label == Deer");
let out = msg
.try_into_iter()
.unwrap()
.filter(|point: &CustomPoint| point.my_custom_label == Label::Deer)
.collect::<Vec<_>>();
println!("Filtered cloud: {:?}", out);
assert_eq!(
vec![CustomPoint::new(1.0, 2.0, 3.0, 4.0, Label::Deer),],
out
);
}
}

View File

@ -1,135 +0,0 @@
use rand::Rng;
/// This example implements a naive benchmark for the library so you can evaluate the use of rayon for parallel processing.
/// It generates a random point cloud and measures the time it takes to iterate over it.
/// The code works mainly as a showcase. For actual benchmarks, check the `benches` directory or run `cargo bench`.
use std::time::Duration;
use ros_pointcloud2::prelude::*;
pub fn generate_random_pointcloud(num_points: usize, min: f32, max: f32) -> Vec<PointXYZ> {
let mut rng = rand::thread_rng();
let mut pointcloud = Vec::with_capacity(num_points);
for _ in 0..num_points {
let point = PointXYZ {
x: rng.gen_range(min..max),
y: rng.gen_range(min..max),
z: rng.gen_range(min..max),
};
pointcloud.push(point);
}
pointcloud
}
fn roundtrip(cloud: Vec<PointXYZ>) -> bool {
let orig_len = cloud.len();
let internal_msg = PointCloud2Msg::try_from_iter(cloud).unwrap();
let total = internal_msg
.try_into_iter()
.unwrap()
.collect::<Vec<PointXYZ>>();
orig_len == total.len()
}
fn roundtrip_filter(cloud: Vec<PointXYZ>) -> bool {
let orig_len = cloud.len();
let internal_msg = PointCloud2Msg::try_from_iter(cloud).unwrap();
let total = internal_msg
.try_into_iter()
.unwrap()
.filter(|point: &PointXYZ| {
(point.x.powi(2) + point.y.powi(2) + point.z.powi(2)).sqrt() < 1.9
})
.fold(PointXYZ::default(), |acc, point| PointXYZ {
x: acc.x + point.x,
y: acc.y + point.y,
z: acc.z + point.z,
});
orig_len == total.x as usize
}
#[cfg(feature = "rayon")]
fn roundtrip_par(cloud: Vec<PointXYZ>) -> bool {
let orig_len = cloud.len();
let internal_msg = PointCloud2Msg::try_from_iter(cloud).unwrap();
let total = internal_msg
.try_into_par_iter()
.unwrap()
.collect::<Vec<PointXYZ>>();
orig_len != total.len()
}
#[cfg(feature = "rayon")]
fn roundtrip_filter_par(cloud: Vec<PointXYZ>) -> bool {
let orig_len: usize = cloud.len();
let internal_msg = PointCloud2Msg::try_from_iter(cloud).unwrap();
let total = internal_msg
.try_into_par_iter()
.unwrap()
.filter(|point: &PointXYZ| {
(point.x.powi(2) + point.y.powi(2) + point.z.powi(2)).sqrt() < 1.9
})
.reduce(PointXYZ::default, |acc, point| PointXYZ {
x: acc.x + point.x,
y: acc.y + point.y,
z: acc.z + point.z,
});
orig_len == total.x as usize
}
// call measure_func X times and print the average time
fn measure_func_avg(
num_iterations: u32,
pcl_size: usize,
func: fn(Vec<PointXYZ>) -> bool,
) -> Duration {
let mut total_time = Duration::new(0, 0);
for _ in 0..num_iterations {
total_time += measure_func(pcl_size, func);
}
total_time / num_iterations
}
fn measure_func<F>(pcl_size: usize, func: F) -> Duration
where
F: Fn(Vec<PointXYZ>) -> bool,
{
let cloud_points = generate_random_pointcloud(pcl_size, f32::MIN / 2.0, f32::MAX / 2.0);
let start = std::time::Instant::now();
let _ = func(cloud_points);
start.elapsed()
}
fn main() {
println!("100k");
let how_many = 10_000;
let how_often = 1_000;
let dur = measure_func_avg(how_often, how_many, roundtrip);
println!("roundtrip: {:?}", dur);
#[cfg(feature = "rayon")]
let dur = measure_func_avg(how_often, how_many, roundtrip_par);
println!("roundtrip_par: {:?}", dur);
println!("200k");
let how_many = 200_000;
let how_often = 100;
let dur = measure_func_avg(how_often, how_many, roundtrip_filter);
println!("roundtrip_filter: {:?}", dur);
#[cfg(feature = "rayon")]
let dur = measure_func_avg(how_often, how_many, roundtrip_filter_par);
println!("roundtrip_filter_par: {:?}", dur);
println!("10m");
let how_many = 10_000_000;
let how_often = 10;
let dur = measure_func_avg(how_often, how_many, roundtrip_filter);
println!("roundtrip_filter: {:?}", dur);
#[cfg(feature = "rayon")]
let dur = measure_func_avg(how_often, how_many, roundtrip_filter_par);
println!("roundtrip_filter_par: {:?}", dur);
}

View File

@ -1,31 +0,0 @@
/// This example demonstrates a very simple distance filter with predefined point types.
/// Note that this example is a simplified version of the custom_enum_field_filter.rs example.
/// Also, it effectively demonstrates a typesafe byte-to-byte buffer filter with a single iteration.
///
/// It also works without any dependencies, making it a good "hello world" example.
use ros_pointcloud2::prelude::*;
fn main() {
let cloud = vec![
PointXYZ::new(1.0, 1.0, 1.0),
PointXYZ::new(2.0, 2.0, 2.0),
PointXYZ::new(3.0, 3.0, 3.0),
];
println!("Original cloud: {:?}", cloud);
let msg = PointCloud2Msg::try_from_iter(cloud).unwrap();
println!("filtering by distance < 1.9m");
let out = msg
.try_into_iter()
.unwrap()
.filter(|point: &PointXYZ| {
(point.x.powi(2) + point.y.powi(2) + point.z.powi(2)).sqrt() < 1.9
})
.collect::<Vec<_>>();
println!("Filtered cloud: {:?}", out);
assert_eq!(vec![PointXYZ::new(1.0, 1.0, 1.0),], out);
}

16
package.xml Normal file
View File

@ -0,0 +1,16 @@
<package format="3">
<name>ros_pointcloud2_tests</name>
<version>0.0.0</version>
<description>Dummy package for linking messages in crate tests.</description>
<maintainer email="user@todo.todo">user</maintainer>
<license>TODO: License declaration</license>
<depend>rclrs</depend>
<depend>sensor_msgs</depend>
<depend>std_msgs</depend>
<depend>builtin_interfaces</depend>
<export>
<build_type>ament_cargo</build_type>
</export>
</package>

View File

@ -1,12 +0,0 @@
[package]
name = "rpcl2_derive"
version = "0.1.0"
edition = "2021"
[lib]
proc-macro = true
[dependencies]
syn = "2.0"
quote = "1.0"
proc-macro2 = "1.0"

View File

@ -1,197 +0,0 @@
extern crate proc_macro;
use std::collections::HashMap;
use proc_macro::TokenStream;
use quote::{quote, ToTokens};
use syn::{parenthesized, parse_macro_input, DeriveInput, LitStr};
fn get_allowed_types() -> HashMap<&'static str, usize> {
let mut allowed_datatypes = HashMap::<&'static str, usize>::new();
allowed_datatypes.insert("f32", std::mem::size_of::<f32>());
allowed_datatypes.insert("f64", std::mem::size_of::<f64>());
allowed_datatypes.insert("i32", std::mem::size_of::<i32>());
allowed_datatypes.insert("u8", std::mem::size_of::<u8>());
allowed_datatypes.insert("u16", std::mem::size_of::<u16>());
allowed_datatypes.insert("u32", std::mem::size_of::<u32>());
allowed_datatypes.insert("i8", std::mem::size_of::<i8>());
allowed_datatypes.insert("i16", std::mem::size_of::<i16>());
allowed_datatypes
}
fn struct_field_rename_array(input: &DeriveInput) -> Vec<String> {
let fields = match input.data {
syn::Data::Struct(ref data) => match data.fields {
syn::Fields::Named(ref fields) => &fields.named,
_ => panic!("StructNames can only be derived for structs with named fields"),
},
_ => panic!("StructNames can only be derived for structs"),
};
let mut field_names = Vec::with_capacity(fields.len());
for f in fields.iter() {
if f.attrs.len() == 0 {
field_names.push(f.ident.as_ref().unwrap().to_token_stream().to_string());
} else {
f.attrs.iter().for_each(|attr| {
if attr.path().is_ident("rpcl2") {
let res = attr.parse_nested_meta(|meta| {
if meta.path.is_ident("rename") {
let new_name;
parenthesized!(new_name in meta.input);
let lit: LitStr = new_name.parse()?;
field_names.push(lit.value());
Ok(())
} else {
panic!("expected `name` attribute");
}
});
if let Err(err) = res {
panic!("Error parsing attribute: {}", err);
}
}
});
}
}
field_names
}
/// This macro implements the `Fields` trait which is a subset of the `PointConvertible` trait.
/// It is useful for points that convert the `From` trait themselves but want to use this macro for not repeating the field names.
///
/// You can rename the fields with the `rename` attribute.
///
/// Use the rename attribute if your struct field name should be different to the ROS field name.
#[proc_macro_derive(Fields, attributes(rpcl2))]
pub fn ros_point_fields_derive(input: TokenStream) -> TokenStream {
let input = parse_macro_input!(input as DeriveInput);
let struct_name = &input.ident;
let field_names = struct_field_rename_array(&input)
.into_iter()
.map(|field_name| {
quote! { #field_name }
});
let field_names_len = field_names.len();
let expanded = quote! {
impl Fields<#field_names_len> for #struct_name {
fn field_names_ordered() -> [&'static str; #field_names_len] {
[
#(#field_names,)*
]
}
}
};
// Return the generated implementation
expanded.into()
}
/// This macro implements the `PointConvertible` trait for your struct so you can use your point for the PointCloud2 conversion.
///
/// The struct field names are used in the message if you do not use the `rename` attribute for a custom name.
///
/// Note that the repr(C) attribute is required for the struct to work efficiently with C++ PCL.
/// With Rust layout optimizations, the struct might not work with the PCL library but the message still conforms to the description of PointCloud2.
/// Furthermore, Rust layout can lead to smaller messages to be send over the network.
///
#[proc_macro_derive(PointConvertible, attributes(rpcl2))]
pub fn ros_point_derive(input: TokenStream) -> TokenStream {
let input = parse_macro_input!(input as DeriveInput);
let name = input.clone().ident;
let fields = match input.data {
syn::Data::Struct(ref data) => data.fields.clone(),
_ => {
return syn::Error::new_spanned(input, "Only structs are supported")
.to_compile_error()
.into()
}
};
let allowed_datatypes = get_allowed_types();
if fields.is_empty() {
return syn::Error::new_spanned(input, "No fields found")
.to_compile_error()
.into();
}
for field in fields.iter() {
let ty = field.ty.to_token_stream().to_string();
if !allowed_datatypes.contains_key(&ty.as_str()) {
return syn::Error::new_spanned(field, "Field type not allowed")
.to_compile_error()
.into();
}
}
let field_len_token: usize = fields.len();
let field_names = struct_field_rename_array(&input)
.into_iter()
.map(|field_name| {
quote! { #field_name }
});
let field_impl = quote! {
impl ros_pointcloud2::Fields<#field_len_token> for #name {
fn field_names_ordered() -> [&'static str; #field_len_token] {
[
#(#field_names,)*
]
}
}
};
let field_names_get = fields
.iter()
.enumerate()
.map(|(idx, f)| {
let field_name = f.ident.as_ref().unwrap();
quote! { #field_name: point[#idx].get() }
})
.collect::<Vec<_>>();
let from_my_point = quote! {
impl From<ros_pointcloud2::RPCL2Point<#field_len_token>> for #name {
fn from(point: ros_pointcloud2::RPCL2Point<#field_len_token>) -> Self {
Self {
#(#field_names_get,)*
}
}
}
};
let field_names_into = fields
.iter()
.map(|f| {
let field_name = f.ident.as_ref().unwrap();
quote! { point.#field_name.into() }
})
.collect::<Vec<_>>();
let from_custom_point = quote! {
impl From<#name> for ros_pointcloud2::RPCL2Point<#field_len_token> {
fn from(point: #name) -> Self {
[ #(#field_names_into,)* ].into()
}
}
};
let convertible = quote! {
impl ros_pointcloud2::PointConvertible<#field_len_token> for #name {}
};
let out = TokenStream::from(quote! {
#field_impl
#from_my_point
#from_custom_point
#convertible
});
TokenStream::from(out)
}

View File

@ -1,6 +1,6 @@
//! Iterator implementations for [`PointCloud2Msg`] including a parallel iterator for rayon.
use crate::{
Endian, FieldDatatype, Fields, MsgConversionError, PointCloud2Msg, PointConvertible, PointData,
Endian, FieldDatatype, MsgConversionError, PointCloud2Msg, PointConvertible, PointData,
RPCL2Point,
};
@ -27,12 +27,12 @@ use alloc::vec::Vec;
///
pub struct PointCloudIterator<const N: usize, C>
where
C: Fields<N>,
C: PointConvertible<N>,
{
iteration: usize,
iteration_back: usize,
data: ByteBufferView<N>,
phantom_c: core::marker::PhantomData<C>, // internally used for pdata names array
_phantom: core::marker::PhantomData<C>,
}
#[cfg(feature = "rayon")]
@ -250,7 +250,7 @@ impl<const N: usize> ByteBufferView<N> {
impl<const N: usize, C> TryFrom<PointCloud2Msg> for PointCloudIterator<N, C>
where
C: Fields<N>,
C: PointConvertible<N>,
{
type Error = MsgConversionError;
@ -260,10 +260,10 @@ where
/// The theoretical time complexity is O(n) where n is the number of fields defined in the message for a single point which is typically small.
/// It therefore has a constant time complexity O(1) for practical purposes.
fn try_from(cloud: PointCloud2Msg) -> Result<Self, Self::Error> {
let mut pdata_with_offsets = vec![(String::default(), FieldDatatype::default(), 0); N];
let fields_only = crate::ordered_field_names::<N, C>();
let not_found_fieldnames = C::field_names_ordered()
.into_iter()
let not_found_fieldnames = fields_only
.iter()
.map(|name| {
let found = cloud.fields.iter().any(|field| field.name == *name);
(name, found)
@ -279,14 +279,14 @@ where
return Err(MsgConversionError::FieldsNotFound(names_not_found));
}
let ordered_fieldnames = C::field_names_ordered();
for (field, with_offset) in cloud.fields.iter().zip(pdata_with_offsets.iter_mut()) {
if ordered_fieldnames.contains(&field.name.as_str()) {
*with_offset = (
let mut pdata_with_offsets = Vec::with_capacity(N);
for field in cloud.fields.iter() {
if fields_only.contains(&field.name) {
pdata_with_offsets.push((
field.name.clone(),
field.datatype.try_into()?,
field.offset as usize,
);
));
}
}
@ -318,9 +318,16 @@ where
return Err(MsgConversionError::DataLengthMismatch);
}
let last_offset = offsets.last().expect("Dimensionality is 0.");
let last_offset = match offsets.last() {
Some(offset) => *offset,
None => return Err(MsgConversionError::DataLengthMismatch),
};
let last_pdata = match pdata.last() {
Some(pdata) => pdata,
None => return Err(MsgConversionError::DataLengthMismatch),
};
let last_pdata = pdata.last().expect("Dimensionality is 0.");
let size_with_last_pdata = last_offset + last_pdata.1.size();
if size_with_last_pdata > point_step_size {
return Err(MsgConversionError::DataLengthMismatch);
@ -342,14 +349,14 @@ where
iteration: 0,
iteration_back: cloud_length - 1,
data,
phantom_c: core::marker::PhantomData,
_phantom: core::marker::PhantomData,
})
}
}
impl<const N: usize, C> PointCloudIterator<N, C>
where
C: Fields<N>,
C: PointConvertible<N>,
{
#[inline]
#[must_use]
@ -358,7 +365,7 @@ where
iteration: 0,
iteration_back: data.len() - 1,
data,
phantom_c: core::marker::PhantomData,
_phantom: core::marker::PhantomData,
}
}

View File

@ -3,19 +3,19 @@
//! The library provides the [`PointCloud2Msg`] type, which implements conversions to and from `Vec` and (parallel) iterators.
//!
//! Vector conversions are optimized for direct copy. They are useful when you just move similar data around. They are usually a good default.
//! - [`try_from_vec`](PointCloud2Msg::try_from_vec) requires `derive` feature (enabled by default)
//! - [`try_into_vec`](PointCloud2Msg::try_into_vec) requires `derive` feature (enabled by default)
//! - [`try_from_vec`](PointCloud2Msg::try_from_vec)
//! - [`try_into_vec`](PointCloud2Msg::try_into_vec)
//!
//! You can use the iterator functions for more control over the conversion process.
//! - [`try_from_iter`](PointCloud2Msg::try_from_iter)
//! - [`try_into_iter`](PointCloud2Msg::try_into_iter)
//!
//! These feature predictable performance but they do not scale well with large clouds. Learn more about that in the [performance section](https://github.com/stelzo/ros_pointcloud2?tab=readme-ov-file#performance) of the repository.
//! The iterators are useful when your conversions are more complex than a simple copy or you the cloud is small enough.
//! The iterators are useful when your conversions are more complex than a simple copy or the cloud is small enough.
//!
//! When the cloud is getting larger or you are doing a lot of processing per point, switch to the parallel iterators.
//! - [`try_into_par_iter`](PointCloud2Msg::try_into_par_iter) requires `rayon` feature
//! - [`try_from_par_iter`](PointCloud2Msg::try_from_par_iter) requires `rayon` + `derive` feature
//! - [`try_from_par_iter`](PointCloud2Msg::try_from_par_iter) requires `rayon` feature
//!
//! For ROS interoperability, there are integrations avialable with feature flags. If you miss a message type, please open an issue or a PR.
//! See the [`ros`] module for more information on how to integrate more libraries.
@ -32,9 +32,9 @@
//! PointXYZI::new(46.0, 5.47, 0.5, 0.1),
//! ];
//! let cloud_copy = cloud_points.clone(); // For equality test later.
//!
//!
//! let out_msg = PointCloud2Msg::try_from_iter(cloud_points).unwrap();
//!
//!
//! // Convert to your ROS crate message type.
//! // let msg: r2r::sensor_msgs::msg::PointCloud2 = in_msg.into();
//! // Publish ...
@ -42,7 +42,7 @@
//! // ... 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 data you want from the point.
//! // Some logic here.
@ -56,24 +56,37 @@
//! - r2r_msg — Integration for the ROS2 library [r2r](https://github.com/sequenceplanner/r2r).
//! - rosrust_msg — Integration with the [rosrust](https://github.com/adnanademovic/rosrust) library for ROS1 message types.
//! - (rclrs_msg) — Integration for ROS2 [rclrs](https://github.com/ros2-rust/ros2_rust) but it currently needs [this workaround](https://github.com/stelzo/ros_pointcloud2?tab=readme-ov-file#rclrs-ros2_rust).
//! - derive *(enabled by default)* — Enables the `_vec` functions and offers helpful custom point derive macros for the [`PointConvertible`] trait.
//! - rayon — Parallel iterator support for `_par_iter` functions. [`PointCloud2Msg::try_from_par_iter`] additionally needs the 'derive' feature.
//! - derive — Offers implementations for the [`PointConvertible`] trait needed for custom points.
//! - rayon — Parallel iterator support for `_par_iter` functions.
//! - nalgebra — Predefined points offer a nalgebra typed getter for coordinates (e.g. [`xyz`](points::PointXYZ::xyz)).
//! - std *(enabled by default)* — Use the standard library. `no_std` only works standalone or with the 'nalgebra' feature.
//! - std *(enabled by default)* — Omit this feature to use this library in no_std environments. ROS integrations and 'rayon' will not work with no_std.
//!
//! # Custom Points
//! Implement [`PointConvertible`] for your point with the `derive` feature or manually.
//!
//! ```
//! use ros_pointcloud2::prelude::*;
//!
//! #[cfg_attr(feature = "derive", derive(PointConvertible, TypeLayout))]
//! #[derive(Clone, Debug, PartialEq, Copy, Default)]
//! ## Derive (recommended)
//! ```ignore
//! #[derive(Clone, Debug, PartialEq, Copy, Default, PointConvertible)]
//! #[repr(C, align(4))]
//! pub struct MyPointXYZI {
//! pub x: f32,
//! pub y: f32,
//! pub z: f32,
//! #[rpcl2(rename("i"))]
//! pub intensity: f32,
//! }
//! ```
//!
//! ## Manual
//! ```
//! use ros_pointcloud2::prelude::*;
//!
//! #[derive(Clone, Debug, PartialEq, Copy, Default)]
//! #[repr(C, align(4))]
//! pub struct MyPointXYZI {
//! pub x: f32,
//! pub y: f32,
//! pub z: f32,
//! #[cfg_attr(feature = "derive", rpcl2(rename("i")))]
//! pub intensity: f32,
//! }
//!
@ -83,30 +96,28 @@
//! }
//! }
//!
//! // Manual implementation of PointConvertible without derive.
//! #[cfg(not(feature = "derive"))]
//! impl Fields<4> for MyPointXYZI {
//! fn field_names_ordered() -> [&'static str; 4] {
//! ["x", "y", "z", "i"] // Note the different field name for intensity.
//! }
//! }
//!
//! #[cfg(not(feature = "derive"))]
//! impl From<RPCL2Point<4>> for MyPointXYZI {
//! fn from(point: RPCL2Point<4>) -> Self {
//! Self::new(point[0].get(), point[1].get(), point[2].get(), point[3].get())
//! }
//! }
//!
//! #[cfg(not(feature = "derive"))]
//! impl From<MyPointXYZI> for RPCL2Point<4> {
//! fn from(point: MyPointXYZI) -> Self {
//! [point.x.into(), point.y.into(), point.z.into(), point.intensity.into()].into()
//! }
//! }
//!
//! #[cfg(not(feature = "derive"))]
//! impl PointConvertible<4> for MyPointXYZI {}
//! unsafe impl PointConvertible<4> for MyPointXYZI {
//! fn layout() -> LayoutDescription {
//! LayoutDescription::new(&[
//! LayoutField::new("x", "f32", 4),
//! LayoutField::new("y", "f32", 4),
//! LayoutField::new("z", "f32", 4),
//! LayoutField::new("intensity", "f32", 4),
//! ])
//! }
//! }
//!
//! let first_p = MyPointXYZI::new(1.0, 2.0, 3.0, 0.5);
//! let cloud_points = vec![first_p, MyPointXYZI::new(4.0, 5.0, 6.0, 0.5)];
@ -114,24 +125,13 @@
//! let cloud_points_out: Vec<MyPointXYZI> = msg_out.try_into_iter().unwrap().collect();
//! assert_eq!(first_p, *cloud_points_out.first().unwrap());
//! ```
//!
//! An example without `#[cfg_attr]` looks like this:
//! ```ignore
//! #[derive(Clone, Debug, PartialEq, Copy, Default, PointConvertible, TypeLayout)]
//! pub struct MyPointXYZI {
//! pub x: f32,
//! pub y: f32,
//! pub z: f32,
//! #[rpcl2(rename("i"))]
//! pub intensity: f32,
//! }
//! ```
#![crate_type = "lib"]
#![cfg_attr(docsrs, feature(doc_cfg))]
#![doc(html_root_url = "https://docs.rs/ros_pointcloud2/0.5.0-rc.1")]
#![doc(html_root_url = "https://docs.rs/ros_pointcloud2/0.5.1")]
#![warn(clippy::print_stderr)]
#![warn(clippy::print_stdout)]
#![warn(clippy::unwrap_used)]
#![warn(clippy::expect_used)]
#![warn(clippy::cargo)]
#![warn(clippy::std_instead_of_core)]
#![warn(clippy::alloc_instead_of_core)]
@ -148,7 +148,13 @@ pub mod iterator;
use crate::ros::{HeaderMsg, PointFieldMsg};
#[cfg(feature = "serde")]
use serde::{Deserialize, Serialize};
#[cfg(feature = "derive")]
#[doc(hidden)]
pub use memoffset;
use core::str::FromStr;
#[macro_use]
@ -168,6 +174,7 @@ pub enum MsgConversionError {
FieldsNotFound(Vec<String>),
UnsupportedFieldCount,
NumberConversion,
ExhaustedSource,
}
impl From<core::num::TryFromIntError> for MsgConversionError {
@ -211,10 +218,17 @@ impl core::fmt::Display for MsgConversionError {
MsgConversionError::NumberConversion => {
write!(f, "The number is too large to be converted into a PointCloud2 supported datatype.")
}
MsgConversionError::ExhaustedSource => {
write!(
f,
"The conversion requests more data from the source type than is available."
)
}
}
}
}
#[allow(clippy::std_instead_of_core)] // will be stable soon (https://github.com/rust-lang/rust/issues/103765)
#[cfg(feature = "std")]
impl std::error::Error for MsgConversionError {
fn source(&self) -> Option<&(dyn std::error::Error + 'static)> {
@ -222,7 +236,6 @@ impl std::error::Error for MsgConversionError {
}
}
#[cfg(feature = "derive")]
fn system_endian() -> Endian {
if cfg!(target_endian = "big") {
Endian::Big
@ -233,11 +246,49 @@ fn system_endian() -> Endian {
}
}
/// Description of the memory layout of a type with named fields.
#[derive(Clone, Debug)]
pub struct LayoutDescription(Vec<LayoutField>);
impl LayoutDescription {
pub fn new(fields: &[LayoutField]) -> Self {
Self(fields.into())
}
}
/// Enum to describe the field type and size in a padded or unpadded layout.
#[derive(Clone, Debug)]
pub enum LayoutField {
Field {
name: alloc::borrow::Cow<'static, str>,
ty: alloc::borrow::Cow<'static, str>,
size: usize,
},
Padding {
size: usize,
},
}
impl LayoutField {
pub fn new(name: &'static str, ty: &'static str, size: usize) -> Self {
LayoutField::Field {
name: name.into(),
ty: ty.into(),
size,
}
}
pub fn padding(size: usize) -> Self {
LayoutField::Padding { size }
}
}
/// The intermediate point cloud type for ROS integrations.
///
/// 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,
@ -251,6 +302,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]
@ -259,13 +311,13 @@ 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,
Sparse,
}
#[cfg(feature = "derive")]
enum ByteSimilarity {
Equal,
Overlapping,
@ -415,41 +467,67 @@ 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,
}
fn ordered_field_names<const N: usize, C: PointConvertible<N>>() -> Vec<String> {
C::layout()
.0
.iter()
.filter(|field| {
matches!(
field,
LayoutField::Field {
name: _,
ty: _,
size: _,
}
)
})
.map(|field| match field {
LayoutField::Field {
name,
ty: _,
size: _,
} => name.as_ref().into(),
_ => unreachable!("Fields must be filtered before."),
})
.collect()
}
impl PointCloud2Msg {
#[cfg(feature = "derive")]
#[inline]
fn byte_similarity<const N: usize, C>(&self) -> Result<ByteSimilarity, MsgConversionError>
where
C: PointConvertible<N>,
{
let point: RPCL2Point<N> = C::default().into();
debug_assert!(point.fields.len() == N);
let field_names = ordered_field_names::<N, C>();
let target_layout = KnownLayoutInfo::try_from(C::layout())?;
let field_names = C::field_names_ordered();
debug_assert!(field_names.len() == N);
let layout = TypeLayoutInfo::try_from(C::type_layout())?;
debug_assert!(field_names.len() == layout.fields.len());
debug_assert!(field_names.len() <= target_layout.fields.len());
debug_assert!(self.fields.len() >= target_layout.fields.len());
let mut offset: u32 = 0;
let mut field_counter = 0;
for (f, msg_f) in layout.fields.iter().zip(self.fields.iter()) {
for f in target_layout.fields.iter() {
match f {
PointField::Field {
datatype,
size,
count,
} => {
let f_translated = String::from_str(field_names[field_counter])
.expect("Field name is not a valid string.");
if field_counter >= self.fields.len() || field_counter >= field_names.len() {
return Err(MsgConversionError::ExhaustedSource);
}
let msg_f = unsafe { self.fields.get_unchecked(field_counter) };
let f_translated = unsafe { field_names.get_unchecked(field_counter) };
field_counter += 1;
if msg_f.name != f_translated
if msg_f.name != *f_translated
|| msg_f.offset != offset
|| msg_f.datatype != *datatype
|| msg_f.count != 1
@ -472,7 +550,7 @@ impl PointCloud2Msg {
})
}
/// Create a [`PointCloud2Msg`] from any iterable type.
/// Create a [`PointCloud2Msg`] from any iterable type that implements [`PointConvertible`].
///
/// # Example
/// ```
@ -495,7 +573,7 @@ impl PointCloud2Msg {
let point: RPCL2Point<N> = C::default().into();
debug_assert!(point.fields.len() == N);
let field_names = C::field_names_ordered();
let field_names = crate::ordered_field_names::<N, C>();
debug_assert!(field_names.len() == N);
let mut pdata_offsets_acc: u32 = 0;
@ -511,7 +589,7 @@ impl PointCloud2Msg {
let _ = FieldDatatype::try_from(datatype_code)?;
*field_val = PointFieldMsg {
name: field_name.into(),
name: field_name,
offset: pdata_offsets_acc,
datatype: datatype_code,
count: 1,
@ -549,8 +627,8 @@ impl PointCloud2Msg {
}
/// Create a PointCloud2Msg from a parallel iterator. Requires the `rayon` and `derive` feature to be enabled.
#[cfg(all(feature = "rayon", feature = "derive"))]
#[cfg_attr(docsrs, doc(cfg(all(feature = "rayon", feature = "derive"))))]
#[cfg(feature = "rayon")]
#[cfg_attr(docsrs, doc(cfg(feature = "rayon")))]
pub fn try_from_par_iter<const N: usize, C>(
iterable: impl rayon::iter::ParallelIterator<Item = C>,
) -> Result<Self, MsgConversionError>
@ -577,8 +655,6 @@ impl PointCloud2Msg {
///
/// # Errors
/// Returns an error if the byte buffer does not match the expected layout or the message contains other discrepancies.
#[cfg(feature = "derive")]
#[cfg_attr(docsrs, doc(cfg(feature = "derive")))]
pub fn try_from_vec<const N: usize, C>(vec: Vec<C>) -> Result<Self, MsgConversionError>
where
C: PointConvertible<N>,
@ -589,17 +665,15 @@ impl PointCloud2Msg {
let point: RPCL2Point<N> = C::default().into();
debug_assert!(point.fields.len() == N);
let field_names = C::field_names_ordered();
let field_names = crate::ordered_field_names::<N, C>();
debug_assert!(field_names.len() == N);
let layout = TypeLayoutInfo::try_from(C::type_layout())?;
debug_assert!(field_names.len() == layout.fields.len());
let layout = KnownLayoutInfo::try_from(C::layout())?;
debug_assert!(field_names.len() <= layout.fields.len());
let mut offset = 0;
let mut fields: Vec<PointFieldMsg> = Vec::with_capacity(layout.fields.len());
let mut fields: Vec<PointFieldMsg> = Vec::with_capacity(field_names.len());
for f in layout.fields.into_iter() {
let f_translated = String::from_str(field_names[fields.len()])
.expect("Field name is not a valid string.");
match f {
PointField::Field {
datatype,
@ -607,7 +681,7 @@ impl PointCloud2Msg {
count,
} => {
fields.push(PointFieldMsg {
name: f_translated,
name: field_names[fields.len()].clone(),
offset,
datatype,
..Default::default()
@ -630,7 +704,7 @@ impl PointCloud2Msg {
let bytes_total = vec.len() * point_step as usize;
cloud.data.resize(bytes_total, u8::default());
let raw_data: *mut C = cloud.data.as_ptr() as *mut C;
let raw_data: *mut C = cloud.data.as_mut_ptr() as *mut C;
unsafe {
core::ptr::copy_nonoverlapping(
vec.as_ptr().cast::<u8>(),
@ -666,8 +740,6 @@ impl PointCloud2Msg {
///
/// # Errors
/// Returns an error if the byte buffer does not match the expected layout or the message contains other discrepancies.
#[cfg(feature = "derive")]
#[cfg_attr(docsrs, doc(cfg(feature = "derive")))]
pub fn try_into_vec<const N: usize, C>(self) -> Result<Vec<C>, MsgConversionError>
where
C: PointConvertible<N>,
@ -770,14 +842,6 @@ pub struct RPCL2Point<const N: usize> {
fields: [PointData; N],
}
impl<const N: usize> Default for RPCL2Point<N> {
fn default() -> Self {
Self {
fields: [PointData::default(); N],
}
}
}
impl<const N: usize> core::ops::Index<usize> for RPCL2Point<N> {
type Output = PointData;
@ -794,157 +858,100 @@ impl<const N: usize> From<[PointData; N]> for RPCL2Point<N> {
/// Trait to enable point conversions on the fly.
///
/// # Example
/// Implement this trait for your custom point you want to read or write in the message.
/// It is strongly recommended to enable the `derive` feature and use the `#[derive(PointConvertible)]` macro.
/// This prevents common errors when implementing this trait by hand.
///
/// Be aware that Rust does not guarantee the memory layout of structs. Learn more [here](https://doc.rust-lang.org/reference/type-layout.html).
/// To make layouting more predictable and thus faster for C++ node interactions, use the `#[repr(C)]` attribute on your struct.
/// An example for diverging point layouts with padding can be seen in the source code of [this](points::PointXYZRGBA::layout) implementation.
///
/// The generic parameter `N` is the number of fields in the point type. There can be more (hidden) fields that pad the layout but they do not count for the N.
/// For
///
/// # Derive
/// ```ignore
/// use ros_pointcloud2::prelude::*;
///
/// #[derive(Clone, Debug, PartialEq, Copy, Default, PointConvertible)]
/// #[repr(C, align(4))]
/// pub struct MyPointXYZL {
/// pub x: f32,
/// pub y: f32,
/// pub z: f32,
/// #[rpcl2(rename("l"))]
/// pub label: u8,
/// }
/// ```
///
/// # Manual
/// ```
/// use ros_pointcloud2::prelude::*;
///
/// #[derive(Clone, Debug, PartialEq, Copy, Default)]
/// pub struct MyPointXYZI {
/// #[repr(C, align(4))]
/// pub struct MyPointXYZL {
/// pub x: f32,
/// pub y: f32,
/// pub z: f32,
/// pub intensity: f32,
/// pub label: u8,
/// }
///
/// impl From<MyPointXYZI> for RPCL2Point<4> {
/// fn from(point: MyPointXYZI) -> Self {
/// [point.x.into(), point.y.into(), point.z.into(), point.intensity.into()].into()
/// impl From<MyPointXYZL> for RPCL2Point<4> {
/// fn from(point: MyPointXYZL) -> Self {
/// [point.x.into(), point.y.into(), point.z.into(), point.label.into()].into()
/// }
/// }
///
/// impl From<RPCL2Point<4>> for MyPointXYZI {
/// impl From<RPCL2Point<4>> for MyPointXYZL {
/// fn from(point: RPCL2Point<4>) -> Self {
/// Self {
/// x: point[0].get(),
/// y: point[1].get(),
/// z: point[2].get(),
/// intensity: point[3].get(),
/// label: point[3].get(),
/// }
/// }
/// }
///
/// impl Fields<4> for MyPointXYZI {
/// fn field_names_ordered() -> [&'static str; 4] {
/// ["x", "y", "z", "intensity"]
/// }
/// }
///
/// impl PointConvertible<4> for MyPointXYZI {}
/// ```
#[cfg_attr(docsrs, doc(cfg(not(feature = "derive"))))]
#[cfg(not(feature = "derive"))]
pub trait PointConvertible<const N: usize>:
From<RPCL2Point<N>> + Into<RPCL2Point<N>> + Fields<N> + Clone + Default
{
}
/// Trait to enable point conversions on the fly.
///
/// Implement this trait for your custom point you want to read or write in the message.
/// For a more convenient way to implement this trait, enable the `derive` feature and use the `#[derive(PointConvertible, TypeLayout)]` macro.
///
/// # Derive Example
/// ```
/// use ros_pointcloud2::prelude::*;
///
/// #[derive(Clone, Debug, PartialEq, Copy, Default, PointConvertible, TypeLayout)]
/// pub struct MyPointXYZI {
/// pub x: f32,
/// pub y: f32,
/// pub z: f32,
/// pub intensity: f32,
/// }
/// ```
///
/// # Manual Example
/// ```
/// use ros_pointcloud2::prelude::*;
///
/// #[derive(Clone, Debug, PartialEq, Copy, Default, TypeLayout)]
/// pub struct MyPointXYZI {
/// pub x: f32,
/// pub y: f32,
/// pub z: f32,
/// pub intensity: f32,
/// }
///
/// impl From<MyPointXYZI> for RPCL2Point<4> {
/// fn from(point: MyPointXYZI) -> Self {
/// [point.x.into(), point.y.into(), point.z.into(), point.intensity.into()].into()
/// unsafe impl PointConvertible<4> for MyPointXYZL {
/// fn layout() -> LayoutDescription {
/// LayoutDescription::new(&[
/// LayoutField::new("x", "f32", 4),
/// LayoutField::new("y", "f32", 4),
/// LayoutField::new("z", "f32", 4),
/// LayoutField::new("l", "u8", 1),
/// LayoutField::padding(3),
/// ])
/// }
/// }
///
/// impl From<RPCL2Point<4>> for MyPointXYZI {
/// fn from(point: RPCL2Point<4>) -> Self {
/// Self {
/// x: point[0].get(),
/// y: point[1].get(),
/// z: point[2].get(),
/// intensity: point[3].get(),
/// }
/// }
/// }
///
/// impl Fields<4> for MyPointXYZI {
/// fn field_names_ordered() -> [&'static str; 4] {
/// ["x", "y", "z", "intensity"]
/// }
/// }
///
/// impl PointConvertible<4> for MyPointXYZI {}
/// ```
#[cfg_attr(docsrs, doc(cfg(feature = "derive")))]
#[cfg(feature = "derive")]
pub trait PointConvertible<const N: usize>:
type_layout::TypeLayout + From<RPCL2Point<N>> + Into<RPCL2Point<N>> + Fields<N> + Default
/// # Safety
/// The layout is used for raw memory interpretation, where safety can not be guaranteed by the compiler.
/// Take care when implementing the layout, especially in combination with `#[repr]` or use the `derive` feature when possible to prevent common errors.
pub unsafe trait PointConvertible<const N: usize>:
From<RPCL2Point<N>> + Into<RPCL2Point<N>> + Default + Sized
{
fn layout() -> LayoutDescription;
}
/// Matching field names from each data point.
/// Always make sure to use the same order as in your conversion implementation to have a correct mapping.
///
/// This trait is needed to implement the `PointConvertible` trait.
///
/// # Example
/// ```
/// use ros_pointcloud2::prelude::*;
///
/// #[derive(Clone, Debug, PartialEq, Copy)]
/// pub struct MyPointXYZI {
/// pub x: f32,
/// pub y: f32,
/// pub z: f32,
/// pub intensity: f32,
/// }
///
/// impl Fields<4> for MyPointXYZI {
/// fn field_names_ordered() -> [&'static str; 4] {
/// ["x", "y", "z", "intensity"]
/// }
/// }
/// ```
pub trait Fields<const N: usize> {
fn field_names_ordered() -> [&'static str; N];
}
#[cfg(feature = "derive")]
#[derive(Debug, Clone)]
enum PointField {
Padding(u32),
Field { size: u32, datatype: u8, count: u32 },
}
#[cfg(feature = "derive")]
struct TypeLayoutInfo {
#[derive(Debug, Clone)]
struct KnownLayoutInfo {
fields: Vec<PointField>,
}
#[cfg(feature = "derive")]
impl TryFrom<type_layout::Field> for PointField {
impl TryFrom<LayoutField> for PointField {
type Error = MsgConversionError;
fn try_from(f: type_layout::Field) -> Result<Self, Self::Error> {
fn try_from(f: LayoutField) -> Result<Self, Self::Error> {
match f {
type_layout::Field::Field { name: _, ty, size } => {
LayoutField::Field { name: _, ty, size } => {
let typename: String = ty.into_owned().to_lowercase();
let datatype = FieldDatatype::from_str(typename.as_str())?;
Ok(Self::Field {
@ -953,21 +960,19 @@ impl TryFrom<type_layout::Field> for PointField {
count: 1,
})
}
type_layout::Field::Padding { size } => Ok(Self::Padding(size.try_into()?)),
LayoutField::Padding { size } => Ok(Self::Padding(size.try_into()?)),
}
}
}
#[cfg(feature = "derive")]
impl TryFrom<type_layout::TypeLayoutInfo> for TypeLayoutInfo {
impl TryFrom<LayoutDescription> for KnownLayoutInfo {
type Error = MsgConversionError;
fn try_from(t: type_layout::TypeLayoutInfo) -> Result<Self, Self::Error> {
let fields: Vec<PointField> = t
.fields
.into_iter()
.map(PointField::try_from)
.collect::<Result<Vec<_>, _>>()?;
fn try_from(t: LayoutDescription) -> Result<Self, Self::Error> {
let fields: Vec<PointField> =
t.0.into_iter()
.map(PointField::try_from)
.collect::<Result<Vec<_>, _>>()?;
Ok(Self { fields })
}
}
@ -1021,11 +1026,10 @@ impl PointData {
#[inline]
fn from_buffer(data: &[u8], offset: usize, datatype: FieldDatatype, endian: Endian) -> Self {
debug_assert!(data.len() >= offset + datatype.size());
let bytes = [u8::default(); core::mem::size_of::<f64>()];
let mut bytes = [u8::default(); core::mem::size_of::<f64>()];
unsafe {
let data_ptr = data.as_ptr().add(offset);
let bytes_ptr = bytes.as_ptr() as *mut u8;
core::ptr::copy_nonoverlapping(data_ptr, bytes_ptr, datatype.size());
core::ptr::copy_nonoverlapping(data_ptr, bytes.as_mut_ptr(), datatype.size());
}
Self {
@ -1464,27 +1468,196 @@ impl FromBytes for u8 {
}
}
#[cfg(test)]
#[cfg(feature = "derive")]
mod tests {
use super::Fields;
use rpcl2_derive::Fields;
use alloc::string::String;
#[allow(dead_code)]
#[derive(Fields)]
struct TestStruct {
field1: String,
#[rpcl2(rename("renamed_field"))]
field2: i32,
field3: f64,
field4: bool,
mod test {
#![allow(clippy::unwrap_used)]
use crate::prelude::*;
#[derive(Debug, Default, Clone, PartialEq)]
#[repr(C)]
struct PointA {
x: f32,
y: f32,
z: f32,
intensity: f32,
t: u32,
reflectivity: u16,
ring: u16,
ambient: u16,
range: u32,
}
impl From<RPCL2Point<9>> for PointA {
fn from(point: RPCL2Point<9>) -> Self {
Self::new(point[0].get(), point[1].get(), point[2].get())
}
}
impl From<PointA> for RPCL2Point<9> {
fn from(point: PointA) -> Self {
[
point.x.into(),
point.y.into(),
point.z.into(),
point.intensity.into(),
point.t.into(),
point.reflectivity.into(),
point.ring.into(),
point.ambient.into(),
point.range.into(),
]
.into()
}
}
unsafe impl PointConvertible<9> for PointA {
fn layout() -> LayoutDescription {
LayoutDescription::new(&[
LayoutField::new("x", "f32", 4),
LayoutField::new("y", "f32", 4),
LayoutField::new("z", "f32", 4),
LayoutField::new("intensity", "f32", 4),
LayoutField::new("t", "u32", 4),
LayoutField::new("reflectivity", "u16", 2),
LayoutField::padding(2),
LayoutField::new("ring", "u16", 2),
LayoutField::padding(2),
LayoutField::new("ambient", "u16", 2),
LayoutField::padding(2),
LayoutField::new("range", "u32", 4),
])
}
}
impl PointA {
fn new(x: f32, y: f32, z: f32) -> Self {
Self {
x,
y,
z,
intensity: 0.0,
t: 0,
reflectivity: 0,
ring: 0,
ambient: 0,
range: 0,
}
}
}
#[derive(Debug, Clone, Default, PartialEq)]
#[repr(C)]
struct PointB {
pub x: f32,
pub y: f32,
pub z: f32,
pub t: u32,
}
impl PointB {
fn new(x: f32, y: f32, z: f32) -> Self {
Self { x, y, z, t: 0 }
}
}
impl From<RPCL2Point<4>> for PointB {
fn from(point: RPCL2Point<4>) -> Self {
Self::new(point[0].get(), point[1].get(), point[2].get())
}
}
impl From<PointB> for RPCL2Point<4> {
fn from(point: PointB) -> Self {
[
point.x.into(),
point.y.into(),
point.z.into(),
point.t.into(),
]
.into()
}
}
unsafe impl PointConvertible<4> for PointB {
fn layout() -> LayoutDescription {
LayoutDescription::new(&[
LayoutField::new("x", "f32", 4),
LayoutField::new("y", "f32", 4),
LayoutField::new("z", "f32", 4),
LayoutField::new("t", "u32", 4),
])
}
}
#[derive(Debug, Clone, Default, PartialEq)]
#[repr(C)]
struct PointD {
x: f32,
y: f32,
z: f32,
t: u32,
ring: u16,
range: u32,
signal: u16,
reflectivity: u16,
near_ir: u16,
}
impl From<RPCL2Point<9>> for PointD {
fn from(point: RPCL2Point<9>) -> Self {
Self::new(point[0].get(), point[1].get(), point[2].get())
}
}
impl From<PointD> for RPCL2Point<9> {
fn from(point: PointD) -> Self {
[
point.x.into(),
point.y.into(),
point.z.into(),
point.t.into(),
point.ring.into(),
point.range.into(),
point.signal.into(),
point.reflectivity.into(),
point.near_ir.into(),
]
.into()
}
}
unsafe impl PointConvertible<9> for PointD {
fn layout() -> LayoutDescription {
LayoutDescription::new(&[
LayoutField::new("x", "f32", 4),
LayoutField::new("y", "f32", 4),
LayoutField::new("z", "f32", 4),
LayoutField::new("t", "u32", 4),
LayoutField::new("ring", "u16", 2),
LayoutField::padding(2),
LayoutField::new("range", "u32", 4),
LayoutField::new("signal", "u16", 2),
LayoutField::padding(2),
LayoutField::new("reflectivity", "u16", 2),
LayoutField::padding(2),
LayoutField::new("near_ir", "u16", 2),
LayoutField::padding(2),
])
}
}
impl PointD {
fn new(x: f32, y: f32, z: f32) -> Self {
Self {
x,
y,
z,
t: 0,
ring: 0,
range: 0,
signal: 0,
reflectivity: 0,
near_ir: 0,
}
}
}
#[test]
fn test_struct_names() {
let names = TestStruct::field_names_ordered();
assert_eq!(names, ["field1", "renamed_field", "field3", "field4"]);
fn subtype_iterator_fallback() {
let cloud_a = PointCloud2Msg::try_from_iter(vec![
PointA::new(1.0, 2.0, 3.0),
PointA::new(4.0, 5.0, 6.0),
PointA::new(7.0, 8.0, 9.0),
])
.unwrap();
let cloud_c: PointB = cloud_a.clone().try_into_iter().unwrap().next().unwrap();
assert_eq!(cloud_c, PointB::new(1.0, 2.0, 3.0));
let cloud_b: Vec<PointB> = cloud_a.try_into_vec().unwrap();
assert_eq!(cloud_b[0], PointB::new(1.0, 2.0, 3.0));
assert_eq!(cloud_b[1], PointB::new(4.0, 5.0, 6.0));
assert_eq!(cloud_b[2], PointB::new(7.0, 8.0, 9.0));
}
}

View File

@ -1,18 +1,15 @@
//! Predefined point types commonly used in ROS.
use crate::{Fields, PointConvertible, RPCL2Point};
use crate::{LayoutDescription, LayoutField, PointConvertible, RPCL2Point};
#[cfg(feature = "derive")]
use type_layout::TypeLayout;
#[cfg(feature = "derive")]
use alloc::vec::Vec;
#[cfg(feature = "serde")]
use serde::{Deserialize, Serialize};
/// A packed RGB color encoding as used in ROS tools.
#[derive(Clone, Copy)]
#[repr(C)]
#[repr(C, align(4))]
pub union RGB {
packed: f32,
unpacked: [u8; 4], // 1 byte padding
unpacked: [u8; 4], // Padding
}
unsafe impl Send for RGB {}
@ -46,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 {
#[must_use]
pub fn new(r: u8, g: u8, b: u8) -> Self {
@ -112,8 +132,8 @@ impl From<f32> for RGB {
/// Predefined point type commonly used in ROS with PCL.
/// This is a 3D point with x, y, z coordinates.
#[derive(Clone, Debug, PartialEq, Copy, Default)]
#[cfg_attr(feature = "derive", derive(TypeLayout))]
#[repr(C)]
#[repr(C, align(16))]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct PointXYZ {
pub x: f32,
pub y: f32,
@ -121,6 +141,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 {
@ -132,12 +153,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 {
@ -146,21 +228,28 @@ impl PointXYZ {
/// Get the coordinates as a nalgebra Point3.
#[cfg(feature = "nalgebra")]
#[deprecated(since = "0.5.2", note = "please use `xyz_f32` instead")]
#[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()
}
}
unsafe impl Send for PointXYZ {}
unsafe impl Sync for PointXYZ {}
impl Fields<3> for PointXYZ {
fn field_names_ordered() -> [&'static str; 3] {
["x", "y", "z"]
}
}
impl From<RPCL2Point<3>> for PointXYZ {
fn from(point: RPCL2Point<3>) -> Self {
Self::new(point[0].get(), point[1].get(), point[2].get())
@ -173,13 +262,22 @@ impl From<PointXYZ> for RPCL2Point<3> {
}
}
impl PointConvertible<3> for PointXYZ {}
unsafe impl PointConvertible<3> for PointXYZ {
fn layout() -> LayoutDescription {
LayoutDescription::new(&[
LayoutField::new("x", "f32", 4),
LayoutField::new("y", "f32", 4),
LayoutField::new("z", "f32", 4),
LayoutField::padding(4),
])
}
}
/// Predefined point type commonly used in ROS with PCL.
/// This is a 3D point with x, y, z coordinates and an intensity value.
#[derive(Clone, Debug, PartialEq, Copy, Default)]
#[cfg_attr(feature = "derive", derive(TypeLayout))]
#[repr(C)]
#[repr(C, align(16))]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct PointXYZI {
pub x: f32,
pub y: f32,
@ -195,20 +293,27 @@ impl PointXYZI {
/// Get the coordinates as a nalgebra Point3.
#[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> {
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 Sync for PointXYZI {}
impl Fields<4> for PointXYZI {
fn field_names_ordered() -> [&'static str; 4] {
["x", "y", "z", "intensity"]
}
}
impl From<RPCL2Point<4>> for PointXYZI {
fn from(point: RPCL2Point<4>) -> Self {
Self::new(
@ -232,13 +337,22 @@ impl From<PointXYZI> for RPCL2Point<4> {
}
}
impl PointConvertible<4> for PointXYZI {}
unsafe impl PointConvertible<4> for PointXYZI {
fn layout() -> LayoutDescription {
LayoutDescription::new(&[
LayoutField::new("x", "f32", 4),
LayoutField::new("y", "f32", 4),
LayoutField::new("z", "f32", 4),
LayoutField::new("intensity", "f32", 4),
])
}
}
/// Predefined point type commonly used in ROS with PCL.
/// This is a 3D point with x, y, z coordinates and a label.
#[derive(Clone, Debug, PartialEq, Copy, Default)]
#[cfg_attr(feature = "derive", derive(TypeLayout))]
#[repr(C)]
#[repr(C, align(16))]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct PointXYZL {
pub x: f32,
pub y: f32,
@ -254,20 +368,27 @@ impl PointXYZL {
/// Get the coordinates as a nalgebra Point3.
#[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> {
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 Sync for PointXYZL {}
impl Fields<4> for PointXYZL {
fn field_names_ordered() -> [&'static str; 4] {
["x", "y", "z", "label"]
}
}
impl From<RPCL2Point<4>> for PointXYZL {
fn from(point: RPCL2Point<4>) -> Self {
Self::new(
@ -291,13 +412,22 @@ impl From<PointXYZL> for RPCL2Point<4> {
}
}
impl PointConvertible<4> for PointXYZL {}
unsafe impl PointConvertible<4> for PointXYZL {
fn layout() -> LayoutDescription {
LayoutDescription::new(&[
LayoutField::new("x", "f32", 4),
LayoutField::new("y", "f32", 4),
LayoutField::new("z", "f32", 4),
LayoutField::new("label", "u32", 4),
])
}
}
/// Predefined point type commonly used in ROS with PCL.
/// This is a 3D point with x, y, z coordinates and an RGB color value.
#[derive(Clone, Debug, PartialEq, Copy, Default)]
#[cfg_attr(feature = "derive", derive(TypeLayout))]
#[repr(C)]
#[repr(C, align(16))]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct PointXYZRGB {
pub x: f32,
pub y: f32,
@ -330,20 +460,27 @@ impl PointXYZRGB {
/// Get the coordinates as a nalgebra Point3.
#[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> {
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 Sync for PointXYZRGB {}
impl Fields<4> for PointXYZRGB {
fn field_names_ordered() -> [&'static str; 4] {
["x", "y", "z", "rgb"]
}
}
impl From<RPCL2Point<4>> for PointXYZRGB {
fn from(point: RPCL2Point<4>) -> Self {
Self {
@ -367,14 +504,23 @@ impl From<PointXYZRGB> for RPCL2Point<4> {
}
}
impl PointConvertible<4> for PointXYZRGB {}
unsafe impl PointConvertible<4> for PointXYZRGB {
fn layout() -> LayoutDescription {
LayoutDescription::new(&[
LayoutField::new("x", "f32", 4),
LayoutField::new("y", "f32", 4),
LayoutField::new("z", "f32", 4),
LayoutField::new("rgb", "RGB", 4),
])
}
}
/// Predefined point type commonly used in ROS with PCL.
/// This is a 3D point with x, y, z coordinates and an RGBA color value.
/// The alpha channel is commonly used as padding but this crate uses every channel and no padding.
#[derive(Clone, Debug, PartialEq, Copy, Default)]
#[cfg_attr(feature = "derive", derive(TypeLayout))]
#[repr(C)]
#[repr(C, align(16))]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct PointXYZRGBA {
pub x: f32,
pub y: f32,
@ -408,20 +554,27 @@ impl PointXYZRGBA {
/// Get the coordinates as a nalgebra Point3.
#[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> {
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 Sync for PointXYZRGBA {}
impl Fields<5> for PointXYZRGBA {
fn field_names_ordered() -> [&'static str; 5] {
["x", "y", "z", "rgb", "a"]
}
}
impl From<RPCL2Point<5>> for PointXYZRGBA {
fn from(point: RPCL2Point<5>) -> Self {
Self {
@ -447,13 +600,24 @@ impl From<PointXYZRGBA> for RPCL2Point<5> {
}
}
impl PointConvertible<5> for PointXYZRGBA {}
unsafe impl PointConvertible<5> for PointXYZRGBA {
fn layout() -> LayoutDescription {
LayoutDescription::new(&[
LayoutField::new("x", "f32", 4),
LayoutField::new("y", "f32", 4),
LayoutField::new("z", "f32", 4),
LayoutField::new("rgb", "RGB", 4),
LayoutField::new("a", "u8", 1),
LayoutField::padding(15),
])
}
}
/// Predefined point type commonly used in ROS with PCL.
/// This is a 3D point with x, y, z coordinates, an RGB color value and a normal vector.
#[derive(Clone, Debug, PartialEq, Copy, Default)]
#[cfg_attr(feature = "derive", derive(TypeLayout))]
#[repr(C)]
#[repr(C, align(16))]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct PointXYZRGBNormal {
pub x: f32,
pub y: f32,
@ -504,20 +668,27 @@ impl PointXYZRGBNormal {
/// Get the coordinates as a nalgebra Point3.
#[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> {
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 Sync for PointXYZRGBNormal {}
impl Fields<7> for PointXYZRGBNormal {
fn field_names_ordered() -> [&'static str; 7] {
["x", "y", "z", "rgb", "normal_x", "normal_y", "normal_z"]
}
}
impl From<RPCL2Point<7>> for PointXYZRGBNormal {
fn from(point: RPCL2Point<7>) -> Self {
Self {
@ -547,13 +718,26 @@ impl From<PointXYZRGBNormal> for RPCL2Point<7> {
}
}
impl PointConvertible<7> for PointXYZRGBNormal {}
unsafe impl PointConvertible<7> for PointXYZRGBNormal {
fn layout() -> LayoutDescription {
LayoutDescription::new(&[
LayoutField::new("x", "f32", 4),
LayoutField::new("y", "f32", 4),
LayoutField::new("z", "f32", 4),
LayoutField::new("rgb", "RGB", 4),
LayoutField::new("normal_x", "f32", 4),
LayoutField::new("normal_y", "f32", 4),
LayoutField::new("normal_z", "f32", 4),
LayoutField::padding(4),
])
}
}
/// Predefined point type commonly used in ROS with PCL.
/// This is a 3D point with x, y, z coordinates, an intensity value and a normal vector.
#[derive(Clone, Debug, PartialEq, Copy, Default)]
#[cfg_attr(feature = "derive", derive(TypeLayout))]
#[repr(C)]
#[repr(C, align(16))]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct PointXYZINormal {
pub x: f32,
pub y: f32,
@ -589,20 +773,26 @@ impl PointXYZINormal {
/// Get the coordinates as a nalgebra Point3.
#[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> {
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 Sync for PointXYZINormal {}
impl Fields<7> for PointXYZINormal {
fn field_names_ordered() -> [&'static str; 7] {
["x", "y", "z", "i", "normal_x", "normal_y", "normal_z"]
}
}
impl From<RPCL2Point<7>> for PointXYZINormal {
fn from(point: RPCL2Point<7>) -> Self {
Self::new(
@ -632,13 +822,26 @@ impl From<PointXYZINormal> for RPCL2Point<7> {
}
}
impl PointConvertible<7> for PointXYZINormal {}
unsafe impl PointConvertible<7> for PointXYZINormal {
fn layout() -> LayoutDescription {
LayoutDescription::new(&[
LayoutField::new("x", "f32", 4),
LayoutField::new("y", "f32", 4),
LayoutField::new("z", "f32", 4),
LayoutField::new("intensity", "f32", 4),
LayoutField::new("normal_x", "f32", 4),
LayoutField::new("normal_y", "f32", 4),
LayoutField::new("normal_z", "f32", 4),
LayoutField::padding(4),
])
}
}
/// Predefined point type commonly used in ROS with PCL.
/// This is a 3D point with x, y, z coordinates and a label.
#[derive(Clone, Debug, PartialEq, Copy, Default)]
#[cfg_attr(feature = "derive", derive(TypeLayout))]
#[repr(C)]
#[repr(C, align(16))]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct PointXYZRGBL {
pub x: f32,
pub y: f32,
@ -681,14 +884,21 @@ impl PointXYZRGBL {
/// Get the coordinates as a nalgebra Point3.
#[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> {
nalgebra::Point3::new(self.x, self.y, self.z)
}
}
impl Fields<5> for PointXYZRGBL {
fn field_names_ordered() -> [&'static str; 5] {
["x", "y", "z", "rgb", "label"]
#[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)
}
}
@ -717,13 +927,24 @@ impl From<PointXYZRGBL> for RPCL2Point<5> {
}
}
impl PointConvertible<5> for PointXYZRGBL {}
unsafe impl PointConvertible<5> for PointXYZRGBL {
fn layout() -> LayoutDescription {
LayoutDescription::new(&[
LayoutField::new("x", "f32", 4),
LayoutField::new("y", "f32", 4),
LayoutField::new("z", "f32", 4),
LayoutField::new("rgb", "RGB", 4),
LayoutField::new("label", "u32", 4),
LayoutField::padding(12),
])
}
}
/// Predefined point type commonly used in ROS with PCL.
/// This is a 3D point with x, y, z coordinates and a normal vector.
#[derive(Clone, Debug, PartialEq, Copy, Default)]
#[cfg_attr(feature = "derive", derive(TypeLayout))]
#[repr(C)]
#[repr(C, align(16))]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct PointXYZNormal {
pub x: f32,
pub y: f32,
@ -749,20 +970,27 @@ impl PointXYZNormal {
/// Get the coordinates as a nalgebra Point3.
#[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> {
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 Sync for PointXYZNormal {}
impl Fields<6> for PointXYZNormal {
fn field_names_ordered() -> [&'static str; 6] {
["x", "y", "z", "normal_x", "normal_y", "normal_z"]
}
}
impl From<RPCL2Point<6>> for PointXYZNormal {
fn from(point: RPCL2Point<6>) -> Self {
Self::new(
@ -790,4 +1018,16 @@ impl From<PointXYZNormal> for RPCL2Point<6> {
}
}
impl PointConvertible<6> for PointXYZNormal {}
unsafe impl PointConvertible<6> for PointXYZNormal {
fn layout() -> LayoutDescription {
LayoutDescription::new(&[
LayoutField::new("x", "f32", 4),
LayoutField::new("y", "f32", 4),
LayoutField::new("z", "f32", 4),
LayoutField::new("normal_x", "f32", 4),
LayoutField::new("normal_y", "f32", 4),
LayoutField::new("normal_z", "f32", 4),
LayoutField::padding(8),
])
}
}

View File

@ -1,7 +1,7 @@
//! Commonly used types and traits for predefined and custom point conversions.
pub use crate::{
FieldDatatype, Fields, FromBytes, GetFieldDatatype, MsgConversionError, PointCloud2Msg,
PointConvertible, PointDataBuffer, RPCL2Point,
FieldDatatype, FromBytes, GetFieldDatatype, LayoutDescription, LayoutField, MsgConversionError,
PointCloud2Msg, PointConvertible, PointDataBuffer, RPCL2Point,
};
pub use crate::points::*;
@ -10,8 +10,5 @@ pub use crate::ros::*;
#[cfg(feature = "rayon")]
pub use rayon::prelude::*;
#[cfg(feature = "derive")]
pub use type_layout::TypeLayout;
#[cfg(feature = "derive")]
pub use rpcl2_derive::*;

View File

@ -25,13 +25,21 @@
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)]
#[cfg(not(any(feature = "rclrs_msg")))]
#[derive(Clone, Debug, Default, Copy)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct TimeMsg {
pub sec: i32,
pub nanosec: u32,
}
#[cfg(feature = "rclrs_msg")]
pub use builtin_interfaces::msg::Time as TimeMsg;
#[cfg(feature = "rosrust_msg")]
impl From<rosrust::Time> for TimeMsg {
fn from(time: rosrust::Time) -> Self {
@ -44,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).
#[derive(Clone, Debug, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct HeaderMsg {
pub seq: u32,
pub stamp: TimeMsg,
@ -52,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.
#[derive(Clone, Debug)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct PointFieldMsg {
pub name: String,
pub offset: u32,
@ -70,6 +80,81 @@ impl Default for PointFieldMsg {
}
}
#[cfg(feature = "rclrs_msg")]
impl From<sensor_msgs::msg::PointCloud2> for crate::PointCloud2Msg {
fn from(msg: sensor_msgs::msg::PointCloud2) -> Self {
Self {
header: HeaderMsg {
seq: 0,
stamp: msg.header.stamp,
frame_id: msg.header.frame_id,
},
dimensions: crate::CloudDimensions {
width: msg.width,
height: msg.height,
},
fields: msg
.fields
.into_iter()
.map(|field| PointFieldMsg {
name: field.name,
offset: field.offset,
datatype: field.datatype,
count: field.count,
})
.collect(),
endian: if msg.is_bigendian {
crate::Endian::Big
} else {
crate::Endian::Little
},
point_step: msg.point_step,
row_step: msg.row_step,
data: msg.data,
dense: if msg.is_dense {
crate::Denseness::Dense
} else {
crate::Denseness::Sparse
},
}
}
}
#[cfg(feature = "rclrs_msg")]
impl From<crate::PointCloud2Msg> for sensor_msgs::msg::PointCloud2 {
fn from(msg: crate::PointCloud2Msg) -> Self {
sensor_msgs::msg::PointCloud2 {
header: std_msgs::msg::Header {
stamp: msg.header.stamp,
frame_id: msg.header.frame_id,
},
height: msg.dimensions.height,
width: msg.dimensions.width,
fields: msg
.fields
.into_iter()
.map(|field| sensor_msgs::msg::PointField {
name: field.name,
offset: field.offset,
datatype: field.datatype,
count: field.count,
})
.collect(),
is_bigendian: match msg.endian {
crate::Endian::Big => true,
crate::Endian::Little => false,
},
point_step: msg.point_step,
row_step: msg.row_step,
data: msg.data,
is_dense: match msg.dense {
crate::Denseness::Dense => true,
crate::Denseness::Sparse => false,
},
}
}
}
#[cfg(feature = "r2r_msg")]
impl From<r2r::sensor_msgs::msg::PointCloud2> for crate::PointCloud2Msg {
fn from(msg: r2r::sensor_msgs::msg::PointCloud2) -> Self {

View File

@ -0,0 +1,35 @@
# syntax=docker/dockerfile:1
FROM ros:jazzy
# Update default packages
RUN apt-get update
# Get Ubuntu packages
RUN apt-get install -y \
build-essential \
curl \
libclang-dev \
git \
python3 \
python3-pip \
python3-vcstool
# Get Rust
RUN curl --proto '=https' --tlsv1.2 https://sh.rustup.rs -sSf | bash -s -- -y
RUN echo 'source $HOME/.cargo/env' >> $HOME/.bashrc
RUN . $HOME/.cargo/env && cargo install --debug cargo-ament-build
RUN pip install --break-system-packages git+https://github.com/colcon/colcon-cargo.git
RUN pip install --break-system-packages git+https://github.com/colcon/colcon-ros-cargo.git
WORKDIR /ros2_rust_build
RUN git clone https://github.com/ros2-rust/ros2_rust.git src/ros2_rust
RUN vcs import src < src/ros2_rust/ros2_rust_jazzy.repos
WORKDIR /ros2_rust_build/src/ros_pointcloud2_tests
COPY . .
WORKDIR /ros2_rust_build
RUN . $HOME/.cargo/env && . /opt/ros/jazzy/setup.sh && colcon build
RUN chmod +x /ros2_rust_build/src/ros_pointcloud2_tests/rpcl2/tests/rclrs_test.bash
ENTRYPOINT [ "/ros2_rust_build/src/ros_pointcloud2_tests/rpcl2/tests/rclrs_test.bash" ]

View File

@ -1,3 +1,4 @@
use pretty_assertions::assert_eq;
use ros_pointcloud2::prelude::*;
#[cfg(feature = "derive")]
@ -9,7 +10,6 @@ macro_rules! convert_from_into {
};
}
#[cfg(feature = "derive")]
macro_rules! convert_from_into_vec {
($point:ty, $cloud:expr) => {
convert_from_into_in_out_cloud_vec!($cloud, $point, $cloud, $point);
@ -30,7 +30,6 @@ macro_rules! convert_from_into_in_out_cloud {
};
}
#[cfg(feature = "derive")]
macro_rules! convert_from_into_in_out_cloud_vec {
($in_cloud:expr, $in_point:ty, $out_cloud:expr, $out_point:ty) => {
let msg = PointCloud2Msg::try_from_vec($in_cloud.clone());
@ -57,9 +56,21 @@ fn write_cloud() {
let msg = PointCloud2Msg::try_from_iter(cloud);
assert!(msg.is_ok());
}
/*
#[test]
fn collect_vec() {
let cloud = vec![
PointXYZ::new(0.0, 1.0, 5.0),
PointXYZ::new(1.0, 1.5, 5.0),
PointXYZ::new(1.3, 1.6, 5.7),
PointXYZ::new(f32::MAX, f32::MIN, f32::MAX),
]
.into_iter();
let msg: Result<PointCloud2Msg, MsgConversionError> = cloud.collect();
}*/
#[test]
#[cfg(feature = "derive")]
fn write_cloud_from_vec() {
let cloud = vec![
PointXYZ::new(0.0, 1.0, 5.0),
@ -73,7 +84,6 @@ fn write_cloud_from_vec() {
}
#[test]
#[cfg(feature = "derive")]
fn write_empty_cloud_vec() {
let cloud: Vec<PointXYZ> = vec![];
let msg = PointCloud2Msg::try_from_vec(cloud);
@ -90,7 +100,7 @@ fn write_empty_cloud_iter() {
}
#[test]
#[cfg(all(feature = "derive", feature = "rayon"))]
#[cfg(feature = "rayon")]
fn conv_cloud_par_iter() {
let cloud = vec![
PointXYZ::new(0.0, 1.0, 5.0),
@ -110,7 +120,7 @@ fn conv_cloud_par_iter() {
}
#[test]
#[cfg(all(feature = "derive", feature = "rayon"))]
#[cfg(feature = "rayon")]
fn conv_cloud_par_par_iter() {
let cloud = vec![
PointXYZ::new(0.0, 1.0, 5.0),
@ -133,14 +143,40 @@ fn conv_cloud_par_par_iter() {
#[test]
#[cfg(feature = "derive")]
fn custom_xyz_f32() {
#[derive(Debug, PartialEq, Clone, Default, PointConvertible, TypeLayout)]
#[repr(C)]
#[derive(Debug, PartialEq, Clone, Default)]
#[repr(C, align(4))]
struct CustomPoint {
x: f32,
y: f32,
z: f32,
}
impl From<RPCL2Point<3>> for CustomPoint {
fn from(point: RPCL2Point<3>) -> Self {
Self {
x: point[0].get(),
y: point[1].get(),
z: point[2].get(),
}
}
}
impl From<CustomPoint> for RPCL2Point<3> {
fn from(point: CustomPoint) -> Self {
[point.x.into(), point.y.into(), point.z.into()].into()
}
}
unsafe impl PointConvertible<3> for CustomPoint {
fn layout() -> LayoutDescription {
LayoutDescription::new(&[
LayoutField::new("x", "f32", 4),
LayoutField::new("y", "f32", 4),
LayoutField::new("z", "f32", 4),
])
}
}
convert_from_into!(
CustomPoint,
vec![
@ -164,7 +200,6 @@ fn custom_xyz_f32() {
}
#[test]
#[cfg(feature = "derive")]
fn custom_xyzi_f32() {
let cloud: Vec<CustomPointXYZI> = vec![
CustomPointXYZI {
@ -193,8 +228,8 @@ fn custom_xyzi_f32() {
},
];
#[derive(Debug, PartialEq, Clone, Default, PointConvertible, TypeLayout)]
#[repr(C)]
#[derive(Debug, PartialEq, Clone, Default)]
#[repr(C, align(4))]
struct CustomPointXYZI {
x: f32,
y: f32,
@ -202,14 +237,49 @@ fn custom_xyzi_f32() {
i: u8,
}
impl From<RPCL2Point<4>> for CustomPointXYZI {
fn from(point: RPCL2Point<4>) -> Self {
Self {
x: point[0].get(),
y: point[1].get(),
z: point[2].get(),
i: point[3].get(),
}
}
}
impl From<CustomPointXYZI> for RPCL2Point<4> {
fn from(point: CustomPointXYZI) -> Self {
[
point.x.into(),
point.y.into(),
point.z.into(),
point.i.into(),
]
.into()
}
}
unsafe impl PointConvertible<4> for CustomPointXYZI {
fn layout() -> LayoutDescription {
LayoutDescription::new(&[
LayoutField::new("x", "f32", 4),
LayoutField::new("y", "f32", 4),
LayoutField::new("z", "f32", 4),
LayoutField::new("i", "u8", 1),
LayoutField::padding(3),
])
}
}
convert_from_into!(CustomPointXYZI, cloud);
}
#[test]
#[cfg(feature = "derive")]
fn custom_rgba_f32() {
#[derive(Debug, PartialEq, Clone, Default, PointConvertible, TypeLayout)]
#[repr(C)]
#[derive(Debug, PartialEq, Clone, Default)]
#[repr(C, align(4))]
struct CustomPoint {
x: f32,
y: f32,
@ -220,6 +290,53 @@ fn custom_rgba_f32() {
a: u8,
}
impl From<RPCL2Point<7>> for CustomPoint {
fn from(point: RPCL2Point<7>) -> Self {
Self {
x: point[0].get(),
y: point[1].get(),
z: point[2].get(),
r: point[3].get(),
g: point[4].get(),
b: point[5].get(),
a: point[6].get(),
}
}
}
impl From<CustomPoint> for RPCL2Point<7> {
fn from(point: CustomPoint) -> Self {
[
point.x.into(),
point.y.into(),
point.z.into(),
point.r.into(),
point.g.into(),
point.b.into(),
point.a.into(),
]
.into()
}
}
unsafe impl PointConvertible<7> for CustomPoint {
fn layout() -> LayoutDescription {
LayoutDescription::new(&[
LayoutField::new("x", "f32", 4),
LayoutField::new("y", "f32", 4),
LayoutField::new("z", "f32", 4),
LayoutField::new("r", "u8", 1),
LayoutField::padding(3),
LayoutField::new("g", "u8", 1),
LayoutField::padding(3),
LayoutField::new("b", "u8", 1),
LayoutField::padding(3),
LayoutField::new("a", "u8", 1),
LayoutField::padding(3),
])
}
}
let cloud = vec![
CustomPoint {
x: 0.0,
@ -375,7 +492,6 @@ fn converterxyzrgb() {
}
#[test]
#[cfg(feature = "derive")]
fn converterxyzrgb_from_vec() {
convert_from_into_vec!(
PointXYZRGB,
@ -433,7 +549,6 @@ fn write_xyzi_read_xyz() {
}
#[test]
#[cfg(feature = "derive")]
fn write_xyzi_read_xyz_vec() {
let write_cloud = vec![
PointXYZI::new(0.0, 1.0, 5.0, 0.0),
@ -453,10 +568,9 @@ fn write_xyzi_read_xyz_vec() {
}
#[test]
#[cfg(feature = "derive")]
fn write_less_than_available() {
#[derive(Debug, PartialEq, Clone, Default, TypeLayout)]
#[repr(C)]
#[derive(Debug, PartialEq, Clone, Default)]
#[repr(C, align(4))]
struct CustomPoint {
x: f32,
y: f32,
@ -481,14 +595,16 @@ fn write_less_than_available() {
}
}
impl Fields<3> for CustomPoint {
fn field_names_ordered() -> [&'static str; 3] {
["x", "y", "z"]
unsafe impl PointConvertible<3> for CustomPoint {
fn layout() -> LayoutDescription {
LayoutDescription::new(&[
LayoutField::new("x", "f32", 4),
LayoutField::new("y", "f32", 4),
LayoutField::new("z", "f32", 4),
])
}
}
impl PointConvertible<3> for CustomPoint {}
let write_cloud = vec![
CustomPoint {
x: 1.0,
@ -532,37 +648,4 @@ fn write_less_than_available() {
];
convert_from_into_in_out_cloud!(write_cloud, CustomPoint, read_cloud, CustomPoint);
}
#[test]
#[cfg(feature = "derive")]
#[allow(unused_variables)]
fn readme() {
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<_>>();
}
}

32
tests/rclrs_msg_test.rs Normal file
View File

@ -0,0 +1,32 @@
#[cfg(feature = "rclrs_msg")]
#[test]
fn convertxyz_rclrs_msg() {
use ros_pointcloud2::{points::PointXYZ, PointCloud2Msg};
use sensor_msgs::msg::PointCloud2;
let cloud = vec![
PointXYZ {
x: 1.0,
y: 2.0,
z: 3.0,
},
PointXYZ {
x: 4.0,
y: 5.0,
z: 6.0,
},
PointXYZ {
x: 7.0,
y: 8.0,
z: 9.0,
},
];
let copy = cloud.clone();
let internal_cloud = PointCloud2Msg::try_from_iter(cloud).unwrap();
let rclrs_msg_cloud: PointCloud2 = internal_cloud.into();
let convert_back_internal: PointCloud2Msg = rclrs_msg_cloud.into();
let to_convert = convert_back_internal.try_into_iter().unwrap();
let back_to_type = to_convert.collect::<Vec<PointXYZ>>();
assert_eq!(copy, back_to_type);
}

View File

@ -15,6 +15,11 @@ if [ -e "/opt/ros/humble/setup.bash" ]; then
. "/ros2_rust_build/install/local_setup.bash"
fi
if [ -e "/opt/ros/galactic/setup.bash" ]; then
. "/opt/ros/galactic/setup.bash"
. "/ros2_rust_build/install/local_setup.bash"
fi
cd /ros2_rust_build/src/ros_pointcloud2_tests/ || exit
"$@"

View File

@ -1,27 +0,0 @@
[package]
name = "type-layout"
description = "Derivable trait to view the layout of a struct, useful for debugging."
version = "0.2.0"
edition = "2018"
authors = ["Lucien Greathouse <me@lpghatguy.com>"]
documentation = "https://docs.rs/type-layout"
homepage = "https://github.com/LPGhatguy/type-layout"
repository = "https://github.com/LPGhatguy/type-layout"
readme = "README.md"
keywords = ["layout", "struct", "type"]
license = "MIT OR Apache-2.0"
rust-version = "1.60.0"
# See more keys and their definitions at https://doc.rust-lang.org/cargo/reference/manifest.html
[features]
serde1 = ["serde"]
[workspace]
members = ["type-layout-derive", "try-crate"]
[dependencies]
type-layout-derive = { version = "0.2.0", path = "type-layout-derive" }
memoffset = "0.5"
serde = { version = "1.0.116", features = ["derive"], optional = true }

View File

@ -1,201 +0,0 @@
i Apache License
Version 2.0, January 2004
http://www.apache.org/licenses/
TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION
1. Definitions.
"License" shall mean the terms and conditions for use, reproduction,
and distribution as defined by Sections 1 through 9 of this document.
"Licensor" shall mean the copyright owner or entity authorized by
the copyright owner that is granting the License.
"Legal Entity" shall mean the union of the acting entity and all
other entities that control, are controlled by, or are under common
control with that entity. For the purposes of this definition,
"control" means (i) the power, direct or indirect, to cause the
direction or management of such entity, whether by contract or
otherwise, or (ii) ownership of fifty percent (50%) or more of the
outstanding shares, or (iii) beneficial ownership of such entity.
"You" (or "Your") shall mean an individual or Legal Entity
exercising permissions granted by this License.
"Source" form shall mean the preferred form for making modifications,
including but not limited to software source code, documentation
source, and configuration files.
"Object" form shall mean any form resulting from mechanical
transformation or translation of a Source form, including but
not limited to compiled object code, generated documentation,
and conversions to other media types.
"Work" shall mean the work of authorship, whether in Source or
Object form, made available under the License, as indicated by a
copyright notice that is included in or attached to the work
(an example is provided in the Appendix below).
"Derivative Works" shall mean any work, whether in Source or Object
form, that is based on (or derived from) the Work and for which the
editorial revisions, annotations, elaborations, or other modifications
represent, as a whole, an original work of authorship. For the purposes
of this License, Derivative Works shall not include works that remain
separable from, or merely link (or bind by name) to the interfaces of,
the Work and Derivative Works thereof.
"Contribution" shall mean any work of authorship, including
the original version of the Work and any modifications or additions
to that Work or Derivative Works thereof, that is intentionally
submitted to Licensor for inclusion in the Work by the copyright owner
or by an individual or Legal Entity authorized to submit on behalf of
the copyright owner. For the purposes of this definition, "submitted"
means any form of electronic, verbal, or written communication sent
to the Licensor or its representatives, including but not limited to
communication on electronic mailing lists, source code control systems,
and issue tracking systems that are managed by, or on behalf of, the
Licensor for the purpose of discussing and improving the Work, but
excluding communication that is conspicuously marked or otherwise
designated in writing by the copyright owner as "Not a Contribution."
"Contributor" shall mean Licensor and any individual or Legal Entity
on behalf of whom a Contribution has been received by Licensor and
subsequently incorporated within the Work.
2. Grant of Copyright License. Subject to the terms and conditions of
this License, each Contributor hereby grants to You a perpetual,
worldwide, non-exclusive, no-charge, royalty-free, irrevocable
copyright license to reproduce, prepare Derivative Works of,
publicly display, publicly perform, sublicense, and distribute the
Work and such Derivative Works in Source or Object form.
3. Grant of Patent License. Subject to the terms and conditions of
this License, each Contributor hereby grants to You a perpetual,
worldwide, non-exclusive, no-charge, royalty-free, irrevocable
(except as stated in this section) patent license to make, have made,
use, offer to sell, sell, import, and otherwise transfer the Work,
where such license applies only to those patent claims licensable
by such Contributor that are necessarily infringed by their
Contribution(s) alone or by combination of their Contribution(s)
with the Work to which such Contribution(s) was submitted. If You
institute patent litigation against any entity (including a
cross-claim or counterclaim in a lawsuit) alleging that the Work
or a Contribution incorporated within the Work constitutes direct
or contributory patent infringement, then any patent licenses
granted to You under this License for that Work shall terminate
as of the date such litigation is filed.
4. Redistribution. You may reproduce and distribute copies of the
Work or Derivative Works thereof in any medium, with or without
modifications, and in Source or Object form, provided that You
meet the following conditions:
(a) You must give any other recipients of the Work or
Derivative Works a copy of this License; and
(b) You must cause any modified files to carry prominent notices
stating that You changed the files; and
(c) You must retain, in the Source form of any Derivative Works
that You distribute, all copyright, patent, trademark, and
attribution notices from the Source form of the Work,
excluding those notices that do not pertain to any part of
the Derivative Works; and
(d) If the Work includes a "NOTICE" text file as part of its
distribution, then any Derivative Works that You distribute must
include a readable copy of the attribution notices contained
within such NOTICE file, excluding those notices that do not
pertain to any part of the Derivative Works, in at least one
of the following places: within a NOTICE text file distributed
as part of the Derivative Works; within the Source form or
documentation, if provided along with the Derivative Works; or,
within a display generated by the Derivative Works, if and
wherever such third-party notices normally appear. The contents
of the NOTICE file are for informational purposes only and
do not modify the License. You may add Your own attribution
notices within Derivative Works that You distribute, alongside
or as an addendum to the NOTICE text from the Work, provided
that such additional attribution notices cannot be construed
as modifying the License.
You may add Your own copyright statement to Your modifications and
may provide additional or different license terms and conditions
for use, reproduction, or distribution of Your modifications, or
for any such Derivative Works as a whole, provided Your use,
reproduction, and distribution of the Work otherwise complies with
the conditions stated in this License.
5. Submission of Contributions. Unless You explicitly state otherwise,
any Contribution intentionally submitted for inclusion in the Work
by You to the Licensor shall be under the terms and conditions of
this License, without any additional terms or conditions.
Notwithstanding the above, nothing herein shall supersede or modify
the terms of any separate license agreement you may have executed
with Licensor regarding such Contributions.
6. Trademarks. This License does not grant permission to use the trade
names, trademarks, service marks, or product names of the Licensor,
except as required for reasonable and customary use in describing the
origin of the Work and reproducing the content of the NOTICE file.
7. Disclaimer of Warranty. Unless required by applicable law or
agreed to in writing, Licensor provides the Work (and each
Contributor provides its Contributions) on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or
implied, including, without limitation, any warranties or conditions
of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A
PARTICULAR PURPOSE. You are solely responsible for determining the
appropriateness of using or redistributing the Work and assume any
risks associated with Your exercise of permissions under this License.
8. Limitation of Liability. In no event and under no legal theory,
whether in tort (including negligence), contract, or otherwise,
unless required by applicable law (such as deliberate and grossly
negligent acts) or agreed to in writing, shall any Contributor be
liable to You for damages, including any direct, indirect, special,
incidental, or consequential damages of any character arising as a
result of this License or out of the use or inability to use the
Work (including but not limited to damages for loss of goodwill,
work stoppage, computer failure or malfunction, or any and all
other commercial damages or losses), even if such Contributor
has been advised of the possibility of such damages.
9. Accepting Warranty or Additional Liability. While redistributing
the Work or Derivative Works thereof, You may choose to offer,
and charge a fee for, acceptance of support, warranty, indemnity,
or other liability obligations and/or rights consistent with this
License. However, in accepting such obligations, You may act only
on Your own behalf and on Your sole responsibility, not on behalf
of any other Contributor, and only if You agree to indemnify,
defend, and hold each Contributor harmless for any liability
incurred by, or claims asserted against, such Contributor by reason
of your accepting any such warranty or additional liability.
END OF TERMS AND CONDITIONS
APPENDIX: How to apply the Apache License to your work.
To apply the Apache License to your work, attach the following
boilerplate notice, with the fields enclosed by brackets "{}"
replaced with your own identifying information. (Don't include
the brackets!) The text should be enclosed in the appropriate
comment syntax for the file format. We also recommend that a
file or class name and description of purpose be included on the
same "printed page" as the copyright notice for easier
identification within third-party archives.
Copyright {yyyy} {name of copyright owner}
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.

View File

@ -1,19 +0,0 @@
Copyright (c) 2020 Lucien Greathouse
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in all
copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
SOFTWARE.

View File

@ -1,204 +0,0 @@
/*!
[![GitHub CI Status](https://github.com/LPGhatguy/type-layout/workflows/CI/badge.svg)](https://github.com/LPGhatguy/type-layout/actions)
[![type-layout on crates.io](https://img.shields.io/crates/v/type-layout.svg)](https://crates.io/crates/type-layout)
[![type-layout docs](https://img.shields.io/badge/docs-docs.rs-orange.svg)](https://docs.rs/type-layout)
type-layout is a type layout debugging aid, providing a `#[derive]`able trait
that reports:
- The type's name, size, and minimum alignment
- Each field's name, type, offset, and size
- Padding due to alignment requirements
**type-layout currently only functions on structs with named fields.** This is a
temporary limitation.
## Examples
The layout of types is only defined if they're `#[repr(C)]`. This crate works on
non-`#[repr(C)]` types, but their layout is unpredictable.
```rust
use type_layout::TypeLayout;
#[derive(TypeLayout)]
#[repr(C)]
struct Foo {
a: u8,
b: u32,
}
println!("{}", Foo::type_layout());
// prints:
// Foo (size 8, alignment 4)
// | Offset | Name | Size |
// | ------ | --------- | ---- |
// | 0 | a | 1 |
// | 1 | [padding] | 3 |
// | 4 | b | 4 |
```
Over-aligned types have trailing padding, which can be a source of bugs in some
FFI scenarios:
```rust
use type_layout::TypeLayout;
#[derive(TypeLayout)]
#[repr(C, align(128))]
struct OverAligned {
value: u8,
}
println!("{}", OverAligned::type_layout());
// prints:
// OverAligned (size 128, alignment 128)
// | Offset | Name | Size |
// | ------ | --------- | ---- |
// | 0 | value | 1 |
// | 1 | [padding] | 127 |
```
## Minimum Supported Rust Version (MSRV)
type-layout supports Rust 1.34.1 and newer. Until type-layout reaches 1.0,
changes to the MSRV will require major version bumps. After 1.0, MSRV changes
will only require minor version bumps, but will need significant justification.
*/
use std::borrow::Cow;
use std::fmt::{self, Display};
use std::str;
pub use type_layout_derive::TypeLayout;
#[doc(hidden)]
pub use memoffset;
pub trait TypeLayout {
fn type_layout() -> TypeLayoutInfo;
}
#[derive(Debug)]
#[cfg_attr(feature = "serde1", derive(serde::Serialize, serde::Deserialize))]
pub struct TypeLayoutInfo {
pub name: Cow<'static, str>,
pub size: usize,
pub alignment: usize,
pub fields: Vec<Field>,
}
#[derive(Debug)]
#[cfg_attr(feature = "serde1", derive(serde::Serialize, serde::Deserialize))]
pub enum Field {
Field {
name: Cow<'static, str>,
ty: Cow<'static, str>,
size: usize,
},
Padding {
size: usize,
},
}
impl fmt::Display for TypeLayoutInfo {
fn fmt(&self, formatter: &mut fmt::Formatter) -> fmt::Result {
writeln!(
formatter,
"{} (size {}, alignment {})",
self.name, self.size, self.alignment
)?;
let longest_name = self
.fields
.iter()
.map(|field| match field {
Field::Field { name, .. } => name.len(),
Field::Padding { .. } => "[padding]".len(),
})
.max()
.unwrap_or(1);
let widths = RowWidths {
offset: "Offset".len(),
name: longest_name,
size: "Size".len(),
};
write_row(
formatter,
widths,
Row {
offset: "Offset",
name: "Name",
size: "Size",
},
)?;
write_row(
formatter,
widths,
Row {
offset: "------",
name: str::repeat("-", longest_name),
size: "----",
},
)?;
let mut offset = 0;
for field in &self.fields {
match field {
Field::Field { name, size, .. } => {
write_row(formatter, widths, Row { offset, name, size })?;
offset += size;
}
Field::Padding { size } => {
write_row(
formatter,
widths,
Row {
offset,
name: "[padding]",
size,
},
)?;
offset += size;
}
}
}
Ok(())
}
}
#[derive(Clone, Copy)]
struct RowWidths {
offset: usize,
name: usize,
size: usize,
}
struct Row<O, N, S> {
offset: O,
name: N,
size: S,
}
fn write_row<O: Display, N: Display, S: Display>(
formatter: &mut fmt::Formatter,
widths: RowWidths,
row: Row<O, N, S>,
) -> fmt::Result {
writeln!(
formatter,
"| {:<offset_width$} | {:<name_width$} | {:<size_width$} |",
row.offset,
row.name,
row.size,
offset_width = widths.offset,
name_width = widths.name,
size_width = widths.size
)
}

View File

@ -1,18 +0,0 @@
[package]
name = "type-layout-derive"
description = "Derive macro implementation for type-layout crate"
version = "0.2.0"
edition = "2018"
authors = ["Lucien Greathouse <me@lpghatguy.com>"]
homepage = "https://github.com/LPGhatguy/type-layout"
license = "MIT OR Apache-2.0"
[lib]
proc-macro = true
# See more keys and their definitions at https://doc.rust-lang.org/cargo/reference/manifest.html
[dependencies]
syn = "2"
quote = "1.0.7"
proc-macro2 = "1.0.21"

View File

@ -1,93 +0,0 @@
extern crate proc_macro;
use proc_macro::TokenStream;
use proc_macro2::{Ident, Literal};
use quote::{quote, quote_spanned, ToTokens};
use syn::{parse_macro_input, spanned::Spanned, Data, DeriveInput, Fields};
#[proc_macro_derive(TypeLayout)]
pub fn derive_type_layout(input: TokenStream) -> TokenStream {
// Parse the input tokens into a syntax tree
let input = parse_macro_input!(input as DeriveInput);
// Used in the quasi-quotation below as `#name`.
let name = input.ident;
let name_str = Literal::string(&name.to_string());
let (impl_generics, ty_generics, where_clause) = input.generics.split_for_impl();
let layout = layout_of_type(&name, &input.data);
// Build the output, possibly using quasi-quotation
let expanded = quote! {
impl #impl_generics ::type_layout::TypeLayout for #name #ty_generics #where_clause {
fn type_layout() -> ::type_layout::TypeLayoutInfo {
let mut last_field_end = 0;
let mut fields = Vec::new();
#layout
::type_layout::TypeLayoutInfo {
name: ::std::borrow::Cow::Borrowed(#name_str),
size: std::mem::size_of::<#name>(),
alignment: ::std::mem::align_of::<#name>(),
fields,
}
}
}
};
// Hand the output tokens back to the compiler
TokenStream::from(expanded)
}
fn layout_of_type(struct_name: &Ident, data: &Data) -> proc_macro2::TokenStream {
match data {
Data::Struct(data) => match &data.fields {
Fields::Named(fields) => {
let values = fields.named.iter().map(|field| {
let field_name = field.ident.as_ref().unwrap();
let field_name_str = Literal::string(&field_name.to_string());
let field_ty = &field.ty;
let field_ty_str = Literal::string(&field_ty.to_token_stream().to_string());
quote_spanned! { field.span() =>
#[allow(unused_assignments)]
{
let size = ::std::mem::size_of::<#field_ty>();
let offset = ::type_layout::memoffset::offset_of!(#struct_name, #field_name);
if offset > last_field_end {
fields.push(::type_layout::Field::Padding {
size: offset - last_field_end
});
}
fields.push(::type_layout::Field::Field {
name: ::std::borrow::Cow::Borrowed(#field_name_str),
ty: ::std::borrow::Cow::Borrowed(#field_ty_str),
size,
});
last_field_end = offset + size;
}
}
});
quote! {
#(#values)*
let struct_size = ::std::mem::size_of::<#struct_name>();
if struct_size > last_field_end {
fields.push(::type_layout::Field::Padding {
size: struct_size - last_field_end,
});
}
}
}
Fields::Unnamed(_) => unimplemented!(),
Fields::Unit => unimplemented!(),
},
Data::Enum(_) | Data::Union(_) => unimplemented!("type-layout only supports structs"),
}
}