Compare commits
28 Commits
v0.5.0-rc.
...
main
| Author | SHA1 | Date |
|---|---|---|
|
|
9d46ff4373 | |
|
|
88ed94b282 | |
|
|
0e3b34b668 | |
|
|
922d3e226d | |
|
|
c16334736e | |
|
|
17e5bec524 | |
|
|
c7134732d2 | |
|
|
42dad82157 | |
|
|
506ff826a3 | |
|
|
54c5e8f6bb | |
|
|
83e9d1019e | |
|
|
46771bfdd0 | |
|
|
15a1db79d6 | |
|
|
4c1e60210e | |
|
|
dbe88e97d0 | |
|
|
458b602a6d | |
|
|
3258198cec | |
|
|
52005e6278 | |
|
|
cecc6702f3 | |
|
|
773b2e77e0 | |
|
|
00acc2a183 | |
|
|
063fb48c75 | |
|
|
31052834af | |
|
|
60b901d636 | |
|
|
a295a36060 | |
|
|
94991c720b | |
|
|
925522ea82 | |
|
|
09d3bef0a8 |
|
|
@ -0,0 +1 @@
|
|||
rpcl2/tests/*.bash linguist-vendored
|
||||
|
|
@ -18,17 +18,17 @@ jobs:
|
|||
with:
|
||||
components: clippy
|
||||
- name: Linting
|
||||
run: cargo clippy --all-targets --features derive,nalgebra,rayon -- -D warnings
|
||||
run: cargo clippy --all-targets --features derive,nalgebra,rayon,serde,ros2-interfaces-jazzy -- -D warnings
|
||||
- name: Tests
|
||||
run: cargo test --features derive,nalgebra,rayon
|
||||
run: cargo test --features derive,nalgebra,rayon,serde,ros2-interfaces-jazzy
|
||||
|
||||
outdated:
|
||||
name: Outdated
|
||||
runs-on: ubuntu-latest
|
||||
if: github.event_name != 'pull_request'
|
||||
timeout-minutes: 45
|
||||
steps:
|
||||
- uses: actions/checkout@v4
|
||||
- uses: dtolnay/rust-toolchain@stable
|
||||
- uses: dtolnay/install@cargo-outdated
|
||||
- run: cargo outdated --exit-code 1
|
||||
# outdated:
|
||||
# name: Outdated
|
||||
# runs-on: ubuntu-latest
|
||||
# if: github.event_name != 'pull_request'
|
||||
# timeout-minutes: 45
|
||||
# steps:
|
||||
# - uses: actions/checkout@v4
|
||||
# - uses: dtolnay/rust-toolchain@stable
|
||||
# - uses: dtolnay/install@cargo-outdated
|
||||
# - run: cargo outdated --exit-code 1
|
||||
|
|
|
|||
|
|
@ -18,4 +18,4 @@ jobs:
|
|||
steps:
|
||||
- uses: actions/checkout@v2
|
||||
- run: docker build . --file ./rpcl2/tests/Dockerfile_r2r_galactic --tag r2r_galactic
|
||||
- run: docker run r2r_galactic cargo test --features r2r_msg,derive,nalgebra,rayon
|
||||
- run: docker run r2r_galactic cargo test --features r2r_msg,derive,nalgebra,rayon,serde
|
||||
|
|
|
|||
|
|
@ -18,4 +18,4 @@ jobs:
|
|||
steps:
|
||||
- uses: actions/checkout@v2
|
||||
- run: docker build . --file ./rpcl2/tests/Dockerfile_r2r_humble --tag r2r_humble
|
||||
- run: docker run r2r_humble cargo test --features r2r_msg,derive,nalgebra,rayon
|
||||
- run: docker run r2r_humble cargo test --features r2r_msg,derive,nalgebra,rayon,serde
|
||||
|
|
|
|||
|
|
@ -18,4 +18,4 @@ jobs:
|
|||
steps:
|
||||
- uses: actions/checkout@v2
|
||||
- run: docker build . --file ./rpcl2/tests/Dockerfile_r2r_iron --tag r2r_iron
|
||||
- run: docker run r2r_iron cargo test --features r2r_msg,derive,nalgebra,rayon
|
||||
- run: docker run r2r_iron cargo test --features r2r_msg,derive,nalgebra,rayon,serde
|
||||
|
|
|
|||
|
|
@ -0,0 +1,21 @@
|
|||
name: r2r_jazzy
|
||||
|
||||
on:
|
||||
push:
|
||||
branches-ignore:
|
||||
- rclrs
|
||||
pull_request:
|
||||
branches-ignore:
|
||||
- rclrs
|
||||
workflow_dispatch:
|
||||
|
||||
env:
|
||||
CARGO_TERM_COLOR: always
|
||||
|
||||
jobs:
|
||||
tests_jazzy:
|
||||
runs-on: ubuntu-latest
|
||||
steps:
|
||||
- uses: actions/checkout@v2
|
||||
- run: docker build . --file ./rpcl2/tests/Dockerfile_r2r_jazzy --tag r2r_jazzy
|
||||
- run: docker run r2r_jazzy cargo test --features r2r_msg,derive,nalgebra,rayon,serde
|
||||
|
|
@ -18,4 +18,4 @@ jobs:
|
|||
steps:
|
||||
- uses: actions/checkout@v2
|
||||
- run: docker build . --file ./rpcl2/tests/Dockerfile_rclrs_humble --tag rclrs_humble
|
||||
- run: docker run rclrs_humble cargo test --features derive,nalgebra,rayon
|
||||
- run: docker run rclrs_humble cargo test --features derive,nalgebra,rayon,serde
|
||||
|
|
|
|||
|
|
@ -18,4 +18,4 @@ jobs:
|
|||
steps:
|
||||
- uses: actions/checkout@v2
|
||||
- run: docker build . --file ./rpcl2/tests/Dockerfile_rclrs_iron --tag rclrs_iron
|
||||
- run: docker run rclrs_iron cargo test --features derive,nalgebra,rayon
|
||||
- run: docker run rclrs_iron cargo test --features derive,nalgebra,rayon,serde
|
||||
|
|
|
|||
|
|
@ -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 ./rpcl2/tests/Dockerfile_rclrs_jazzy --tag rclrs_jazzy
|
||||
- run: docker run rclrs_jazzy cargo test --features derive,nalgebra,rayon,serde
|
||||
|
|
@ -105,4 +105,4 @@ jobs:
|
|||
- name: test
|
||||
run: |
|
||||
source /opt/ros/$ROS_DISTRO/setup.bash
|
||||
cargo test --features rosrust_msg,derive,nalgebra,rayon
|
||||
cargo test --features rosrust_msg,derive,nalgebra,rayon,serde
|
||||
|
|
|
|||
|
|
@ -21,6 +21,8 @@ jobs:
|
|||
with:
|
||||
components: clippy
|
||||
- name: Linting
|
||||
run: cargo clippy --all-targets --features derive,nalgebra,rayon -- -D warnings
|
||||
- name: Tests
|
||||
run: cargo test --features derive,nalgebra,rayon
|
||||
run: cargo clippy --all-targets --features derive,nalgebra,rayon,serde -- -D warnings
|
||||
- name: Build examples with features
|
||||
run: cargo build --examples --features derive,nalgebra,rayon,serde,ros2-interfaces-jazzy
|
||||
- name: Test library
|
||||
run: cargo test --features derive,nalgebra,rayon,serde
|
||||
|
|
|
|||
|
|
@ -1,3 +1,3 @@
|
|||
Cargo.lock
|
||||
Cargo.lock*
|
||||
.idea/
|
||||
target/
|
||||
|
|
|
|||
11
CHANGELOG.md
11
CHANGELOG.md
|
|
@ -1,5 +1,16 @@
|
|||
# Changelog
|
||||
|
||||
## v0.5.0 -> v0.5.1
|
||||
|
||||
- Fixes a bug, where the conversion of larger to smaller types results in a false buffer interpretation.
|
||||
|
||||
## v0.5.0-rc.3 -> v0.5.0
|
||||
|
||||
- `PointConvertible` trait is now `unsafe` since the offset is used for raw memory access, where safety can not be guaranteed by the compiler.
|
||||
- Fixes clippy on nightly.
|
||||
- Fixes a bug when attempting to write larger types than available in the message. This now results in a `ExhaustedSource` error.
|
||||
- Adds `repr(C)` to docs where custom conversions are explained to encourage best practices for raw type descriptions.
|
||||
|
||||
## v0.5.0-rc.2 -> v0.5.0-rc.3
|
||||
|
||||
- Bump r2r to 0.9.
|
||||
|
|
|
|||
|
|
@ -7,7 +7,7 @@
|
|||
|
||||
ros_pointcloud2 uses its own type for the message `PointCloud2Msg` to keep the library framework agnostic. ROS1 and ROS2 are supported with feature flags.
|
||||
|
||||
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.3/) 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
|
||||
|
||||
|
|
@ -49,9 +49,11 @@ There are currently 3 integrations for common ROS crates.
|
|||
- [](https://github.com/stelzo/ros_pointcloud2/actions/workflows/r2r_galactic.yml)
|
||||
- [](https://github.com/stelzo/ros_pointcloud2/actions/workflows/r2r_humble.yml)
|
||||
- [](https://github.com/stelzo/ros_pointcloud2/actions/workflows/r2r_iron.yml)
|
||||
- [](https://github.com/stelzo/ros_pointcloud2/actions/workflows/r2r_jazzy.yml)
|
||||
- [rclrs_msg](https://github.com/ros2-rust/ros2_rust)
|
||||
- [](https://github.com/stelzo/ros_pointcloud2/actions/workflows/rclrs_humble.yml)
|
||||
- [](https://github.com/stelzo/ros_pointcloud2/actions/workflows/rclrs_iron.yml)
|
||||
- [](https://github.com/stelzo/ros_pointcloud2/actions/workflows/rclrs_jazzy.yml)
|
||||
|
||||
You can use `rosrust` and `r2r` by enabling the respective feature:
|
||||
|
||||
|
|
@ -68,7 +70,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.3_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.
|
||||
|
|
|
|||
|
|
@ -8,10 +8,10 @@ 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",
|
||||
]
|
||||
|
||||
[dependencies]
|
||||
|
|
|
|||
|
|
@ -1,7 +1,7 @@
|
|||
[package]
|
||||
name = "rpcl2-derive"
|
||||
description = "Derive macros for ros_pointcloud2 crate."
|
||||
version = "0.2.0"
|
||||
version = "0.4.0"
|
||||
edition = "2021"
|
||||
authors = ["Christopher Sieh <stelzo@steado.de>"]
|
||||
homepage = "https://github.com/stelzo/ros_pointcloud2"
|
||||
|
|
|
|||
|
|
@ -48,8 +48,8 @@ fn struct_field_rename_array(input: &DeriveInput) -> Vec<String> {
|
|||
panic!("expected `name` attribute");
|
||||
}
|
||||
});
|
||||
if let Err(err) = res {
|
||||
panic!("Error parsing attribute: {}", err);
|
||||
if let Err(e) = res {
|
||||
panic!("Error parsing attribute: {e}");
|
||||
}
|
||||
}
|
||||
});
|
||||
|
|
@ -109,7 +109,7 @@ pub fn ros_point_derive(input: TokenStream) -> TokenStream {
|
|||
let layout = layout_of_type(&name, &input.data);
|
||||
|
||||
let expanded = quote! {
|
||||
impl #impl_generics ::ros_pointcloud2::PointConvertible<#field_len_token> for #name #ty_generics #where_clause {
|
||||
unsafe impl #impl_generics ::ros_pointcloud2::PointConvertible<#field_len_token> for #name #ty_generics #where_clause {
|
||||
fn layout() -> ::ros_pointcloud2::LayoutDescription {
|
||||
let mut last_field_end = 0;
|
||||
let mut fields = Vec::new();
|
||||
|
|
@ -188,7 +188,7 @@ fn layout_of_type(struct_name: &Ident, data: &Data) -> proc_macro2::TokenStream
|
|||
|
||||
quote! {
|
||||
let size = ::core::mem::size_of::<#field_ty>();
|
||||
let offset = ::ros_pointcloud2::memoffset::offset_of!(#struct_name, #field_name);
|
||||
let offset = ::core::mem::offset_of!(#struct_name, #field_name);
|
||||
if offset > last_field_end {
|
||||
fields.push((1, "", offset - last_field_end));
|
||||
}
|
||||
|
|
|
|||
|
|
@ -1,6 +1,6 @@
|
|||
[package]
|
||||
name = "ros_pointcloud2"
|
||||
version = "0.5.0-rc.3"
|
||||
version = "0.5.3"
|
||||
edition = "2021"
|
||||
authors = ["Christopher Sieh <stelzo@steado.de>"]
|
||||
description = "Customizable conversions for working with sensor_msgs/PointCloud2."
|
||||
|
|
@ -8,39 +8,42 @@ 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/**",
|
||||
"**/ensure_no_std/**",
|
||||
"**/.github/**",
|
||||
"**/tests/**",
|
||||
"**/examples/**",
|
||||
"**/benches/**",
|
||||
"**/target/**",
|
||||
"**/build/**",
|
||||
"**/dist/**",
|
||||
"**/docs/**",
|
||||
"**/doc/**",
|
||||
"**/ensure_no_std/**",
|
||||
]
|
||||
rust-version = "1.63"
|
||||
rust-version = "1.77"
|
||||
|
||||
[dependencies]
|
||||
rosrust_msg = { version = "0.1", optional = true }
|
||||
rosrust = { version = "0.9.11", 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", optional = true, default-features = false }
|
||||
rpcl2-derive = { version = "0.2", optional = true, path = "../rpcl2-derive" }
|
||||
memoffset = { version = "0.9", optional = true }
|
||||
nalgebra = { version = "0.33", optional = true, default-features = false }
|
||||
rpcl2-derive = { version = "0.4", optional = true, path = "../rpcl2-derive" }
|
||||
serde = { version = "1.0", features = ["derive"], optional = true }
|
||||
ros2-interfaces-jazzy = { version = "0.0.4", features = [
|
||||
"sensor_msgs",
|
||||
], optional = true }
|
||||
|
||||
[dev-dependencies]
|
||||
rand = "0.8"
|
||||
rand = "0.9"
|
||||
criterion = { version = "0.5", features = ["html_reports"] }
|
||||
pretty_assertions = "1.0"
|
||||
|
||||
|
|
@ -50,16 +53,18 @@ harness = false
|
|||
path = "benches/roundtrip.rs"
|
||||
|
||||
[features]
|
||||
serde = ["dep:serde", "nalgebra/serde-serialize-no-std"]
|
||||
rosrust_msg = ["dep:rosrust_msg", "dep:rosrust"]
|
||||
r2r_msg = ["dep:r2r"]
|
||||
ros2-interfaces-jazzy = ["dep:ros2-interfaces-jazzy"]
|
||||
rayon = ["dep:rayon"]
|
||||
derive = ["dep:rpcl2-derive", "dep:memoffset"]
|
||||
derive = ["dep:rpcl2-derive"]
|
||||
nalgebra = ["dep:nalgebra"]
|
||||
std = ["nalgebra/std"]
|
||||
|
||||
default = ["std"]
|
||||
|
||||
[package.metadata.docs.rs]
|
||||
features = ["derive", "nalgebra", "rayon"]
|
||||
features = ["derive", "nalgebra", "rayon", "serde"]
|
||||
default-target = "x86_64-unknown-linux-gnu"
|
||||
rustdoc-args = ["--cfg", "docsrs"]
|
||||
|
|
|
|||
|
|
@ -100,13 +100,13 @@ fn minus(point1: &PointXYZ, point2: &PointXYZ) -> PointXYZ {
|
|||
}
|
||||
|
||||
pub fn generate_random_pointcloud(num_points: usize, min: f32, max: f32) -> Vec<PointXYZB> {
|
||||
let mut rng = rand::thread_rng();
|
||||
let mut rng = rand::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),
|
||||
x: rng.random_range(min..max),
|
||||
y: rng.random_range(min..max),
|
||||
z: rng.random_range(min..max),
|
||||
..Default::default()
|
||||
};
|
||||
pointcloud.push(point);
|
||||
|
|
|
|||
|
|
@ -20,7 +20,7 @@ enum Label {
|
|||
// 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)]
|
||||
#[repr(C)]
|
||||
#[repr(C, align(4))]
|
||||
struct CustomPoint {
|
||||
x: f32,
|
||||
y: f32,
|
||||
|
|
@ -91,7 +91,7 @@ impl From<RPCL2Point<5>> for CustomPoint {
|
|||
}
|
||||
|
||||
// C representation of the struct hardcoded without using the derive feature.
|
||||
impl PointConvertible<5> for CustomPoint {
|
||||
unsafe impl PointConvertible<5> for CustomPoint {
|
||||
fn layout() -> LayoutDescription {
|
||||
LayoutDescription::new(&[
|
||||
LayoutField::new("x", "f32", 4),
|
||||
|
|
@ -134,30 +134,27 @@ impl From<Label> for PointDataBuffer {
|
|||
}
|
||||
|
||||
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),
|
||||
];
|
||||
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);
|
||||
println!("Original cloud: {cloud:?}");
|
||||
|
||||
let msg = PointCloud2Msg::try_from_iter(cloud).unwrap();
|
||||
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!("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);
|
||||
println!("Filtered cloud: {out:?}");
|
||||
|
||||
assert_eq!(
|
||||
vec![CustomPoint::new(1.0, 2.0, 3.0, 4.0, Label::Deer),],
|
||||
out
|
||||
);
|
||||
}
|
||||
assert_eq!(
|
||||
vec![CustomPoint::new(1.0, 2.0, 3.0, 4.0, Label::Deer),],
|
||||
out
|
||||
);
|
||||
}
|
||||
|
|
|
|||
|
|
@ -7,13 +7,13 @@ 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 rng = rand::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),
|
||||
x: rng.random_range(min..max),
|
||||
y: rng.random_range(min..max),
|
||||
z: rng.random_range(min..max),
|
||||
};
|
||||
pointcloud.push(point);
|
||||
}
|
||||
|
|
@ -105,31 +105,31 @@ fn main() {
|
|||
let how_often = 1_000;
|
||||
|
||||
let dur = measure_func_avg(how_often, how_many, roundtrip);
|
||||
println!("roundtrip: {:?}", dur);
|
||||
println!("roundtrip: {dur:?}");
|
||||
|
||||
#[cfg(feature = "rayon")]
|
||||
let dur = measure_func_avg(how_often, how_many, roundtrip_par);
|
||||
println!("roundtrip_par: {:?}", dur);
|
||||
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);
|
||||
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!("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);
|
||||
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!("roundtrip_filter_par: {dur:?}");
|
||||
}
|
||||
|
|
|
|||
|
|
@ -12,7 +12,7 @@ fn main() {
|
|||
PointXYZ::new(3.0, 3.0, 3.0),
|
||||
];
|
||||
|
||||
println!("Original cloud: {:?}", cloud);
|
||||
println!("Original cloud: {cloud:?}");
|
||||
|
||||
let msg = PointCloud2Msg::try_from_iter(cloud).unwrap();
|
||||
|
||||
|
|
@ -25,7 +25,7 @@ fn main() {
|
|||
})
|
||||
.collect::<Vec<_>>();
|
||||
|
||||
println!("Filtered cloud: {:?}", out);
|
||||
println!("Filtered cloud: {out:?}");
|
||||
|
||||
assert_eq!(vec![PointXYZ::new(1.0, 1.0, 1.0),], out);
|
||||
}
|
||||
|
|
|
|||
|
|
@ -260,8 +260,6 @@ 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 = fields_only
|
||||
|
|
@ -281,13 +279,14 @@ where
|
|||
return Err(MsgConversionError::FieldsNotFound(names_not_found));
|
||||
}
|
||||
|
||||
for (field, with_offset) in cloud.fields.iter().zip(pdata_with_offsets.iter_mut()) {
|
||||
let mut pdata_with_offsets = Vec::with_capacity(N);
|
||||
for field in cloud.fields.iter() {
|
||||
if fields_only.contains(&field.name) {
|
||||
*with_offset = (
|
||||
pdata_with_offsets.push((
|
||||
field.name.clone(),
|
||||
field.datatype.try_into()?,
|
||||
field.offset as usize,
|
||||
);
|
||||
));
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
|||
276
rpcl2/src/lib.rs
276
rpcl2/src/lib.rs
|
|
@ -17,11 +17,11 @@
|
|||
//! - [`try_into_par_iter`](PointCloud2Msg::try_into_par_iter) requires `rayon` 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.
|
||||
//! For ROS interoperability, there are integrations available 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.
|
||||
//!
|
||||
//! Common point types like [`PointXYZ`](points::PointXYZ) or [`PointXYZI`](points::PointXYZI) are provided. See the full list [`here`](points). You can easily add any additional custom type.
|
||||
//! See [custom_enum_field_filter.rs](https://github.com/stelzo/ros_pointcloud2/blob/main/examples/custom_enum_field_filter.rs) for an example.
|
||||
//! See [custom_enum_field_filter.rs](https://github.com/stelzo/ros_pointcloud2/blob/main/rpcl2/examples/custom_enum_field_filter.rs) for an example.
|
||||
//!
|
||||
//! # Minimal Example
|
||||
//! ```
|
||||
|
|
@ -67,6 +67,7 @@
|
|||
//! ## Derive (recommended)
|
||||
//! ```ignore
|
||||
//! #[derive(Clone, Debug, PartialEq, Copy, Default, PointConvertible)]
|
||||
//! #[repr(C, align(4))]
|
||||
//! pub struct MyPointXYZI {
|
||||
//! pub x: f32,
|
||||
//! pub y: f32,
|
||||
|
|
@ -81,6 +82,7 @@
|
|||
//! use ros_pointcloud2::prelude::*;
|
||||
//!
|
||||
//! #[derive(Clone, Debug, PartialEq, Copy, Default)]
|
||||
//! #[repr(C, align(4))]
|
||||
//! pub struct MyPointXYZI {
|
||||
//! pub x: f32,
|
||||
//! pub y: f32,
|
||||
|
|
@ -106,7 +108,7 @@
|
|||
//! }
|
||||
//! }
|
||||
//!
|
||||
//! impl PointConvertible<4> for MyPointXYZI {
|
||||
//! unsafe impl PointConvertible<4> for MyPointXYZI {
|
||||
//! fn layout() -> LayoutDescription {
|
||||
//! LayoutDescription::new(&[
|
||||
//! LayoutField::new("x", "f32", 4),
|
||||
|
|
@ -125,7 +127,7 @@
|
|||
//! ```
|
||||
#![crate_type = "lib"]
|
||||
#![cfg_attr(docsrs, feature(doc_cfg))]
|
||||
#![doc(html_root_url = "https://docs.rs/ros_pointcloud2/0.5.0-rc.3")]
|
||||
#![doc(html_root_url = "https://docs.rs/ros_pointcloud2/0.5.1")]
|
||||
#![warn(clippy::print_stderr)]
|
||||
#![warn(clippy::print_stdout)]
|
||||
#![warn(clippy::unwrap_used)]
|
||||
|
|
@ -137,6 +139,7 @@
|
|||
#![cfg_attr(not(feature = "std"), no_std)]
|
||||
// Setup an allocator with #[global_allocator]
|
||||
// see: https://doc.rust-lang.org/std/alloc/trait.GlobalAlloc.html
|
||||
#![allow(unexpected_cfgs)]
|
||||
|
||||
pub mod points;
|
||||
pub mod prelude;
|
||||
|
|
@ -146,12 +149,11 @@ pub mod iterator;
|
|||
|
||||
use crate::ros::{HeaderMsg, PointFieldMsg};
|
||||
|
||||
#[cfg(feature = "derive")]
|
||||
#[doc(hidden)]
|
||||
pub use memoffset;
|
||||
|
||||
use core::str::FromStr;
|
||||
|
||||
#[cfg(feature = "serde")]
|
||||
use serde::{Deserialize, Serialize};
|
||||
|
||||
#[macro_use]
|
||||
extern crate alloc;
|
||||
use alloc::string::String;
|
||||
|
|
@ -169,6 +171,7 @@ pub enum MsgConversionError {
|
|||
FieldsNotFound(Vec<String>),
|
||||
UnsupportedFieldCount,
|
||||
NumberConversion,
|
||||
ExhaustedSource,
|
||||
}
|
||||
|
||||
impl From<core::num::TryFromIntError> for MsgConversionError {
|
||||
|
|
@ -212,10 +215,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)> {
|
||||
|
|
@ -275,6 +285,7 @@ impl LayoutField {
|
|||
/// To assert consistency, the type should be build with the [`PointCloud2MsgBuilder`].
|
||||
/// See the offical [ROS message description](https://docs.ros2.org/latest/api/sensor_msgs/msg/PointCloud2.html) for more information on the fields.
|
||||
#[derive(Clone, Debug)]
|
||||
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
|
||||
pub struct PointCloud2Msg {
|
||||
pub header: HeaderMsg,
|
||||
pub dimensions: CloudDimensions,
|
||||
|
|
@ -288,6 +299,7 @@ pub struct PointCloud2Msg {
|
|||
|
||||
/// Endianess encoding hint for the message.
|
||||
#[derive(Default, Clone, Debug, PartialEq, Copy)]
|
||||
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
|
||||
pub enum Endian {
|
||||
Big,
|
||||
#[default]
|
||||
|
|
@ -296,12 +308,14 @@ 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,
|
||||
}
|
||||
|
||||
#[derive(Clone, Debug, PartialEq)]
|
||||
enum ByteSimilarity {
|
||||
Equal,
|
||||
Overlapping,
|
||||
|
|
@ -451,6 +465,7 @@ impl PointCloud2MsgBuilder {
|
|||
|
||||
/// Dimensions of the point cloud as width and height.
|
||||
#[derive(Clone, Debug, Default)]
|
||||
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
|
||||
pub struct CloudDimensions {
|
||||
pub width: u32,
|
||||
pub height: u32,
|
||||
|
|
@ -487,15 +502,11 @@ impl PointCloud2Msg {
|
|||
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>();
|
||||
debug_assert!(field_names.len() == N);
|
||||
|
||||
let target_layout = KnownLayoutInfo::try_from(C::layout())?;
|
||||
|
||||
debug_assert!(field_names.len() <= target_layout.fields.len());
|
||||
debug_assert!(self.fields.len() <= target_layout.fields.len());
|
||||
debug_assert!(self.fields.len() >= target_layout.fields.len());
|
||||
|
||||
let mut offset: u32 = 0;
|
||||
let mut field_counter = 0;
|
||||
|
|
@ -506,8 +517,12 @@ impl PointCloud2Msg {
|
|||
size,
|
||||
count,
|
||||
} => {
|
||||
let msg_f = &self.fields[field_counter];
|
||||
let f_translated = &field_names[field_counter];
|
||||
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
|
||||
|
|
@ -533,7 +548,7 @@ impl PointCloud2Msg {
|
|||
})
|
||||
}
|
||||
|
||||
/// Create a [`PointCloud2Msg`] from any iterable type.
|
||||
/// Create a [`PointCloud2Msg`] from any iterable type that implements [`PointConvertible`].
|
||||
///
|
||||
/// # Example
|
||||
/// ```
|
||||
|
|
@ -687,7 +702,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>(),
|
||||
|
|
@ -897,7 +912,7 @@ impl<const N: usize> From<[PointData; N]> for RPCL2Point<N> {
|
|||
/// }
|
||||
/// }
|
||||
///
|
||||
/// impl PointConvertible<4> for MyPointXYZL {
|
||||
/// unsafe impl PointConvertible<4> for MyPointXYZL {
|
||||
/// fn layout() -> LayoutDescription {
|
||||
/// LayoutDescription::new(&[
|
||||
/// LayoutField::new("x", "f32", 4),
|
||||
|
|
@ -909,7 +924,10 @@ impl<const N: usize> From<[PointData; N]> for RPCL2Point<N> {
|
|||
/// }
|
||||
/// }
|
||||
/// ```
|
||||
pub trait PointConvertible<const N: usize>:
|
||||
/// # 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;
|
||||
|
|
@ -1006,11 +1024,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 {
|
||||
|
|
@ -1448,3 +1465,216 @@ impl FromBytes for u8 {
|
|||
Self::from_le_bytes([bytes[0]])
|
||||
}
|
||||
}
|
||||
|
||||
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 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));
|
||||
}
|
||||
}
|
||||
|
|
|
|||
|
|
@ -1,7 +1,10 @@
|
|||
//! Predefined point types commonly used in ROS.
|
||||
use crate::{LayoutDescription, LayoutField, PointConvertible, RPCL2Point};
|
||||
|
||||
/// A packed RGB color encoding as used in ROS tools.
|
||||
#[cfg(feature = "serde")]
|
||||
use serde::{Deserialize, Serialize};
|
||||
|
||||
/// Packed RGB color encoding as used in ROS tools.
|
||||
#[derive(Clone, Copy)]
|
||||
#[repr(C, align(4))]
|
||||
pub union RGB {
|
||||
|
|
@ -9,6 +12,29 @@ pub union RGB {
|
|||
unpacked: [u8; 4], // Padding
|
||||
}
|
||||
|
||||
#[cfg(feature = "serde")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "serde")))]
|
||||
impl<'de> Deserialize<'de> for RGB {
|
||||
fn deserialize<D>(deserializer: D) -> Result<RGB, D::Error>
|
||||
where
|
||||
D: serde::Deserializer<'de>,
|
||||
{
|
||||
let packed = f32::deserialize(deserializer)?;
|
||||
Ok(RGB::new_from_packed_f32(packed))
|
||||
}
|
||||
}
|
||||
|
||||
#[cfg(feature = "serde")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "serde")))]
|
||||
impl Serialize for RGB {
|
||||
fn serialize<S>(&self, serializer: S) -> Result<S::Ok, S::Error>
|
||||
where
|
||||
S: serde::Serializer,
|
||||
{
|
||||
f32::from(*self).serialize(serializer)
|
||||
}
|
||||
}
|
||||
|
||||
unsafe impl Send for RGB {}
|
||||
unsafe impl Sync for RGB {}
|
||||
|
||||
|
|
@ -103,10 +129,10 @@ impl From<f32> for RGB {
|
|||
}
|
||||
}
|
||||
|
||||
/// Predefined point type commonly used in ROS with PCL.
|
||||
/// This is a 3D point with x, y, z coordinates.
|
||||
/// 3D point with x, y, z coordinates, commonly used in ROS with PCL.
|
||||
#[derive(Clone, Debug, PartialEq, Copy, Default)]
|
||||
#[repr(C, align(16))]
|
||||
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
|
||||
pub struct PointXYZ {
|
||||
pub x: f32,
|
||||
pub y: f32,
|
||||
|
|
@ -114,6 +140,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 {
|
||||
|
|
@ -125,12 +152,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 {
|
||||
|
|
@ -139,9 +227,22 @@ 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()
|
||||
}
|
||||
}
|
||||
|
||||
|
|
@ -160,7 +261,7 @@ 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),
|
||||
|
|
@ -171,10 +272,10 @@ impl PointConvertible<3> for PointXYZ {
|
|||
}
|
||||
}
|
||||
|
||||
/// Predefined point type commonly used in ROS with PCL.
|
||||
/// This is a 3D point with x, y, z coordinates and an intensity value.
|
||||
/// 3D point with x, y, z coordinates and an intensity value, commonly used in ROS with PCL.
|
||||
#[derive(Clone, Debug, PartialEq, Copy, Default)]
|
||||
#[repr(C, align(16))]
|
||||
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
|
||||
pub struct PointXYZI {
|
||||
pub x: f32,
|
||||
pub y: f32,
|
||||
|
|
@ -189,10 +290,23 @@ impl PointXYZI {
|
|||
|
||||
/// 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> {
|
||||
self.xyz_f32()
|
||||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz_f32(&self) -> nalgebra::Point3<f32> {
|
||||
nalgebra::Point3::new(self.x, self.y, self.z)
|
||||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz_f64(&self) -> nalgebra::Point3<f64> {
|
||||
nalgebra::Point3::new(self.x as f64, self.y as f64, self.z as f64)
|
||||
}
|
||||
}
|
||||
|
||||
unsafe impl Send for PointXYZI {}
|
||||
|
|
@ -221,7 +335,7 @@ 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),
|
||||
|
|
@ -232,10 +346,10 @@ impl PointConvertible<4> for PointXYZI {
|
|||
}
|
||||
}
|
||||
|
||||
/// Predefined point type commonly used in ROS with PCL.
|
||||
/// This is a 3D point with x, y, z coordinates and a label.
|
||||
/// 3D point with x, y, z coordinates and a label, commonly used in ROS with PCL.
|
||||
#[derive(Clone, Debug, PartialEq, Copy, Default)]
|
||||
#[repr(C, align(16))]
|
||||
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
|
||||
pub struct PointXYZL {
|
||||
pub x: f32,
|
||||
pub y: f32,
|
||||
|
|
@ -250,10 +364,23 @@ impl PointXYZL {
|
|||
|
||||
/// 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> {
|
||||
self.xyz_f32()
|
||||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz_f32(&self) -> nalgebra::Point3<f32> {
|
||||
nalgebra::Point3::new(self.x, self.y, self.z)
|
||||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz_f64(&self) -> nalgebra::Point3<f64> {
|
||||
nalgebra::Point3::new(self.x as f64, self.y as f64, self.z as f64)
|
||||
}
|
||||
}
|
||||
|
||||
unsafe impl Send for PointXYZL {}
|
||||
|
|
@ -282,7 +409,7 @@ 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),
|
||||
|
|
@ -293,10 +420,10 @@ impl PointConvertible<4> for PointXYZL {
|
|||
}
|
||||
}
|
||||
|
||||
/// Predefined point type commonly used in ROS with PCL.
|
||||
/// This is a 3D point with x, y, z coordinates and an RGB color value.
|
||||
/// 3D point with x, y, z coordinates and an RGB color value, commonly used in ROS with PCL.
|
||||
#[derive(Clone, Debug, PartialEq, Copy, Default)]
|
||||
#[repr(C, align(16))]
|
||||
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
|
||||
pub struct PointXYZRGB {
|
||||
pub x: f32,
|
||||
pub y: f32,
|
||||
|
|
@ -328,10 +455,23 @@ impl PointXYZRGB {
|
|||
|
||||
/// 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> {
|
||||
self.xyz_f32()
|
||||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz_f32(&self) -> nalgebra::Point3<f32> {
|
||||
nalgebra::Point3::new(self.x, self.y, self.z)
|
||||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz_f64(&self) -> nalgebra::Point3<f64> {
|
||||
nalgebra::Point3::new(self.x as f64, self.y as f64, self.z as f64)
|
||||
}
|
||||
}
|
||||
|
||||
unsafe impl Send for PointXYZRGB {}
|
||||
|
|
@ -360,7 +500,7 @@ 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),
|
||||
|
|
@ -371,11 +511,11 @@ impl PointConvertible<4> for PointXYZRGB {
|
|||
}
|
||||
}
|
||||
|
||||
/// Predefined point type commonly used in ROS with PCL.
|
||||
/// This is a 3D point with x, y, z coordinates and an RGBA color value.
|
||||
/// 3D point with x, y, z coordinates and an RGBA color value, commonly used in ROS with PCL.
|
||||
/// The alpha channel is commonly used as padding but this crate uses every channel and no padding.
|
||||
#[derive(Clone, Debug, PartialEq, Copy, Default)]
|
||||
#[repr(C, align(16))]
|
||||
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
|
||||
pub struct PointXYZRGBA {
|
||||
pub x: f32,
|
||||
pub y: f32,
|
||||
|
|
@ -408,10 +548,23 @@ impl PointXYZRGBA {
|
|||
|
||||
/// 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> {
|
||||
self.xyz_f32()
|
||||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz_f32(&self) -> nalgebra::Point3<f32> {
|
||||
nalgebra::Point3::new(self.x, self.y, self.z)
|
||||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz_f64(&self) -> nalgebra::Point3<f64> {
|
||||
nalgebra::Point3::new(self.x as f64, self.y as f64, self.z as f64)
|
||||
}
|
||||
}
|
||||
|
||||
unsafe impl Send for PointXYZRGBA {}
|
||||
|
|
@ -442,7 +595,7 @@ 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),
|
||||
|
|
@ -455,10 +608,10 @@ impl PointConvertible<5> for PointXYZRGBA {
|
|||
}
|
||||
}
|
||||
|
||||
/// 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.
|
||||
/// 3D point with x, y, z coordinates, an RGB color value and a normal vector, commonly used in ROS with PCL.
|
||||
#[derive(Clone, Debug, PartialEq, Copy, Default)]
|
||||
#[repr(C, align(16))]
|
||||
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
|
||||
pub struct PointXYZRGBNormal {
|
||||
pub x: f32,
|
||||
pub y: f32,
|
||||
|
|
@ -508,10 +661,23 @@ impl PointXYZRGBNormal {
|
|||
|
||||
/// 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> {
|
||||
self.xyz_f32()
|
||||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz_f32(&self) -> nalgebra::Point3<f32> {
|
||||
nalgebra::Point3::new(self.x, self.y, self.z)
|
||||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz_f64(&self) -> nalgebra::Point3<f64> {
|
||||
nalgebra::Point3::new(self.x as f64, self.y as f64, self.z as f64)
|
||||
}
|
||||
}
|
||||
|
||||
unsafe impl Send for PointXYZRGBNormal {}
|
||||
|
|
@ -546,7 +712,7 @@ 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),
|
||||
|
|
@ -561,10 +727,10 @@ impl PointConvertible<7> for PointXYZRGBNormal {
|
|||
}
|
||||
}
|
||||
|
||||
/// 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.
|
||||
/// 3D point with x, y, z coordinates, an intensity value and a normal vector, commonly used in ROS with PCL.
|
||||
#[derive(Clone, Debug, PartialEq, Copy, Default)]
|
||||
#[repr(C, align(16))]
|
||||
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
|
||||
pub struct PointXYZINormal {
|
||||
pub x: f32,
|
||||
pub y: f32,
|
||||
|
|
@ -599,10 +765,23 @@ impl PointXYZINormal {
|
|||
|
||||
/// 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> {
|
||||
self.xyz_f32()
|
||||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz_f32(&self) -> nalgebra::Point3<f32> {
|
||||
nalgebra::Point3::new(self.x, self.y, self.z)
|
||||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz_f64(&self) -> nalgebra::Point3<f64> {
|
||||
nalgebra::Point3::new(self.x as f64, self.y as f64, self.z as f64)
|
||||
}
|
||||
}
|
||||
|
||||
unsafe impl Send for PointXYZINormal {}
|
||||
|
|
@ -637,7 +816,7 @@ 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),
|
||||
|
|
@ -652,10 +831,10 @@ impl PointConvertible<7> for PointXYZINormal {
|
|||
}
|
||||
}
|
||||
|
||||
/// Predefined point type commonly used in ROS with PCL.
|
||||
/// This is a 3D point with x, y, z coordinates and a label.
|
||||
/// 3D point with x, y, z coordinates and a label, commonly used in ROS with PCL.
|
||||
#[derive(Clone, Debug, PartialEq, Copy, Default)]
|
||||
#[repr(C, align(16))]
|
||||
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
|
||||
pub struct PointXYZRGBL {
|
||||
pub x: f32,
|
||||
pub y: f32,
|
||||
|
|
@ -697,10 +876,23 @@ impl PointXYZRGBL {
|
|||
|
||||
/// 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> {
|
||||
self.xyz_f32()
|
||||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz_f32(&self) -> nalgebra::Point3<f32> {
|
||||
nalgebra::Point3::new(self.x, self.y, self.z)
|
||||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz_f64(&self) -> nalgebra::Point3<f64> {
|
||||
nalgebra::Point3::new(self.x as f64, self.y as f64, self.z as f64)
|
||||
}
|
||||
}
|
||||
|
||||
impl From<RPCL2Point<5>> for PointXYZRGBL {
|
||||
|
|
@ -728,7 +920,7 @@ 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),
|
||||
|
|
@ -741,10 +933,10 @@ impl PointConvertible<5> for PointXYZRGBL {
|
|||
}
|
||||
}
|
||||
|
||||
/// Predefined point type commonly used in ROS with PCL.
|
||||
/// This is a 3D point with x, y, z coordinates and a normal vector.
|
||||
/// 3D point with x, y, z coordinates and a normal vector, commonly used in ROS with PCL.
|
||||
#[derive(Clone, Debug, PartialEq, Copy, Default)]
|
||||
#[repr(C, align(16))]
|
||||
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
|
||||
pub struct PointXYZNormal {
|
||||
pub x: f32,
|
||||
pub y: f32,
|
||||
|
|
@ -769,10 +961,23 @@ impl PointXYZNormal {
|
|||
|
||||
/// 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> {
|
||||
self.xyz_f32()
|
||||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz_f32(&self) -> nalgebra::Point3<f32> {
|
||||
nalgebra::Point3::new(self.x, self.y, self.z)
|
||||
}
|
||||
|
||||
#[cfg(feature = "nalgebra")]
|
||||
#[cfg_attr(docsrs, doc(cfg(feature = "nalgebra")))]
|
||||
pub fn xyz_f64(&self) -> nalgebra::Point3<f64> {
|
||||
nalgebra::Point3::new(self.x as f64, self.y as f64, self.z as f64)
|
||||
}
|
||||
}
|
||||
|
||||
unsafe impl Send for PointXYZNormal {}
|
||||
|
|
@ -805,7 +1010,7 @@ 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),
|
||||
|
|
|
|||
112
rpcl2/src/ros.rs
112
rpcl2/src/ros.rs
|
|
@ -25,13 +25,27 @@
|
|||
|
||||
use alloc::string::String;
|
||||
|
||||
#[cfg(feature = "serde")]
|
||||
use serde::{Deserialize, Serialize};
|
||||
|
||||
/// [Time](https://docs.ros2.org/latest/api/builtin_interfaces/msg/Time.html) representation for ROS messages.
|
||||
#[derive(Clone, Debug, Default)]
|
||||
#[derive(Clone, Debug, Default, Copy)]
|
||||
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
|
||||
pub struct TimeMsg {
|
||||
pub sec: i32,
|
||||
pub nanosec: u32,
|
||||
}
|
||||
|
||||
#[cfg(feature = "ros2-interfaces-jazzy")]
|
||||
impl From<ros2_interfaces_jazzy::builtin_interfaces::msg::Time> for TimeMsg {
|
||||
fn from(time: ros2_interfaces_jazzy::builtin_interfaces::msg::Time) -> Self {
|
||||
Self {
|
||||
sec: time.sec,
|
||||
nanosec: time.nanosec,
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#[cfg(feature = "rosrust_msg")]
|
||||
impl From<rosrust::Time> for TimeMsg {
|
||||
fn from(time: rosrust::Time) -> Self {
|
||||
|
|
@ -44,14 +58,27 @@ 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,
|
||||
pub frame_id: String,
|
||||
}
|
||||
|
||||
#[cfg(feature = "ros2-interfaces-jazzy")]
|
||||
impl From<ros2_interfaces_jazzy::std_msgs::msg::Header> for HeaderMsg {
|
||||
fn from(header: ros2_interfaces_jazzy::std_msgs::msg::Header) -> Self {
|
||||
Self {
|
||||
seq: 0,
|
||||
stamp: header.stamp.into(),
|
||||
frame_id: header.frame_id,
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/// 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 +97,89 @@ impl Default for PointFieldMsg {
|
|||
}
|
||||
}
|
||||
|
||||
#[cfg(feature = "ros2-interfaces-jazzy")]
|
||||
impl From<ros2_interfaces_jazzy::sensor_msgs::msg::PointCloud2> for crate::PointCloud2Msg {
|
||||
fn from(msg: ros2_interfaces_jazzy::sensor_msgs::msg::PointCloud2) -> Self {
|
||||
Self {
|
||||
header: HeaderMsg {
|
||||
seq: 0,
|
||||
stamp: TimeMsg {
|
||||
sec: msg.header.stamp.sec,
|
||||
nanosec: msg.header.stamp.nanosec,
|
||||
},
|
||||
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 = "ros2-interfaces-jazzy")]
|
||||
impl From<crate::PointCloud2Msg> for ros2_interfaces_jazzy::sensor_msgs::msg::PointCloud2 {
|
||||
fn from(msg: crate::PointCloud2Msg) -> Self {
|
||||
ros2_interfaces_jazzy::sensor_msgs::msg::PointCloud2 {
|
||||
header: ros2_interfaces_jazzy::std_msgs::msg::Header {
|
||||
stamp: ros2_interfaces_jazzy::builtin_interfaces::msg::Time {
|
||||
sec: msg.header.stamp.sec,
|
||||
nanosec: msg.header.stamp.nanosec,
|
||||
},
|
||||
frame_id: msg.header.frame_id,
|
||||
},
|
||||
height: msg.dimensions.height,
|
||||
width: msg.dimensions.width,
|
||||
fields: msg
|
||||
.fields
|
||||
.into_iter()
|
||||
.map(
|
||||
|field| ros2_interfaces_jazzy::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 {
|
||||
|
|
|
|||
|
|
@ -0,0 +1,22 @@
|
|||
# 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
|
||||
|
||||
# Get ros test messages
|
||||
RUN apt-get install -y ros-jazzy-test-msgs ros-jazzy-example-interfaces
|
||||
|
||||
# Get Rust
|
||||
RUN curl --proto '=https' --tlsv1.2 https://sh.rustup.rs -sSf | bash -s -- -y
|
||||
RUN echo 'source $HOME/.cargo/env' >> $HOME/.bashrc
|
||||
|
||||
COPY . /r2r
|
||||
RUN chmod +x /r2r/rpcl2/tests/r2r_test.bash
|
||||
ENTRYPOINT [ "/r2r/rpcl2/tests/r2r_test.bash" ]
|
||||
|
|
@ -0,0 +1,34 @@
|
|||
# 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-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 git+https://github.com/colcon/colcon-cargo.git
|
||||
RUN pip install 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" ]
|
||||
|
|
@ -56,6 +56,19 @@ 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]
|
||||
fn write_cloud_from_vec() {
|
||||
|
|
@ -131,7 +144,7 @@ fn conv_cloud_par_par_iter() {
|
|||
#[cfg(feature = "derive")]
|
||||
fn custom_xyz_f32() {
|
||||
#[derive(Debug, PartialEq, Clone, Default)]
|
||||
#[repr(C)]
|
||||
#[repr(C, align(4))]
|
||||
struct CustomPoint {
|
||||
x: f32,
|
||||
y: f32,
|
||||
|
|
@ -154,7 +167,7 @@ fn custom_xyz_f32() {
|
|||
}
|
||||
}
|
||||
|
||||
impl PointConvertible<3> for CustomPoint {
|
||||
unsafe impl PointConvertible<3> for CustomPoint {
|
||||
fn layout() -> LayoutDescription {
|
||||
LayoutDescription::new(&[
|
||||
LayoutField::new("x", "f32", 4),
|
||||
|
|
@ -216,7 +229,7 @@ fn custom_xyzi_f32() {
|
|||
];
|
||||
|
||||
#[derive(Debug, PartialEq, Clone, Default)]
|
||||
#[repr(C)]
|
||||
#[repr(C, align(4))]
|
||||
struct CustomPointXYZI {
|
||||
x: f32,
|
||||
y: f32,
|
||||
|
|
@ -247,7 +260,7 @@ fn custom_xyzi_f32() {
|
|||
}
|
||||
}
|
||||
|
||||
impl PointConvertible<4> for CustomPointXYZI {
|
||||
unsafe impl PointConvertible<4> for CustomPointXYZI {
|
||||
fn layout() -> LayoutDescription {
|
||||
LayoutDescription::new(&[
|
||||
LayoutField::new("x", "f32", 4),
|
||||
|
|
@ -266,7 +279,7 @@ fn custom_xyzi_f32() {
|
|||
#[cfg(feature = "derive")]
|
||||
fn custom_rgba_f32() {
|
||||
#[derive(Debug, PartialEq, Clone, Default)]
|
||||
#[repr(C)]
|
||||
#[repr(C, align(4))]
|
||||
struct CustomPoint {
|
||||
x: f32,
|
||||
y: f32,
|
||||
|
|
@ -306,7 +319,7 @@ fn custom_rgba_f32() {
|
|||
}
|
||||
}
|
||||
|
||||
impl PointConvertible<7> for CustomPoint {
|
||||
unsafe impl PointConvertible<7> for CustomPoint {
|
||||
fn layout() -> LayoutDescription {
|
||||
LayoutDescription::new(&[
|
||||
LayoutField::new("x", "f32", 4),
|
||||
|
|
@ -557,7 +570,7 @@ fn write_xyzi_read_xyz_vec() {
|
|||
#[test]
|
||||
fn write_less_than_available() {
|
||||
#[derive(Debug, PartialEq, Clone, Default)]
|
||||
#[repr(C)]
|
||||
#[repr(C, align(4))]
|
||||
struct CustomPoint {
|
||||
x: f32,
|
||||
y: f32,
|
||||
|
|
@ -582,7 +595,7 @@ fn write_less_than_available() {
|
|||
}
|
||||
}
|
||||
|
||||
impl PointConvertible<3> for CustomPoint {
|
||||
unsafe impl PointConvertible<3> for CustomPoint {
|
||||
fn layout() -> LayoutDescription {
|
||||
LayoutDescription::new(&[
|
||||
LayoutField::new("x", "f32", 4),
|
||||
|
|
|
|||
|
|
@ -5,6 +5,10 @@
|
|||
# run rustup to test with latest rust version
|
||||
rustup update
|
||||
|
||||
if [ -e "/opt/ros/jazzy/setup.bash" ]; then
|
||||
source "/opt/ros/jazzy/setup.bash"
|
||||
fi
|
||||
|
||||
if [ -e "/opt/ros/iron/setup.bash" ]; then
|
||||
source "/opt/ros/iron/setup.bash"
|
||||
fi
|
||||
|
|
|
|||
|
|
@ -5,16 +5,19 @@
|
|||
# run rustup to test with latest rust version
|
||||
rustup update
|
||||
|
||||
if [ -e "/opt/ros/jazzy/setup.bash" ]; then
|
||||
. "/opt/ros/jazzy/setup.bash"
|
||||
fi
|
||||
|
||||
if [ -e "/opt/ros/iron/setup.bash" ]; then
|
||||
. "/opt/ros/iron/setup.bash"
|
||||
. "/ros2_rust_build/install/local_setup.bash"
|
||||
fi
|
||||
|
||||
if [ -e "/opt/ros/humble/setup.bash" ]; then
|
||||
. "/opt/ros/humble/setup.bash"
|
||||
. "/ros2_rust_build/install/local_setup.bash"
|
||||
fi
|
||||
|
||||
. "/ros2_rust_build/install/local_setup.bash"
|
||||
cd /ros2_rust_build/src/ros_pointcloud2_tests/ || exit
|
||||
|
||||
"$@"
|
||||
|
|
|
|||
|
|
@ -0,0 +1,32 @@
|
|||
#[cfg(feature = "ros2-interfaces-jazzy")]
|
||||
#[test]
|
||||
fn convertxyz_ros2_interfaces_jazzy_msg() {
|
||||
use ros_pointcloud2::{points::PointXYZ, PointCloud2Msg};
|
||||
|
||||
use ros2_interfaces_jazzy::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 ros2_msg_cloud: PointCloud2 = internal_cloud.into();
|
||||
let convert_back_internal: PointCloud2Msg = ros2_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);
|
||||
}
|
||||
Loading…
Reference in New Issue