Compare commits

...

4 Commits

Author SHA1 Message Date
stelzo c16334736e
bump version 2025-02-04 11:50:17 +01:00
stelzo 17e5bec524 fix time 2025-02-04 11:37:40 +01:00
stelzo c7134732d2 remove hint 2025-02-04 10:53:23 +01:00
stelzo 42dad82157 rosrust fix 2025-02-04 10:44:24 +01:00
6 changed files with 32 additions and 47 deletions

View File

@ -5,18 +5,9 @@
</p>
</p>
> [!IMPORTANT]
> The optional rosrust dependency currently breaks the build of this crate because of a yanked transitive dependency on crates.io.
> Use [this workaround](https://github.com/adnanademovic/rosrust/issues/210#issuecomment-2609494830) in your project when rosrust is needed.
> If you are not using rosrust at all, you can also use the main branch of this repository, where the integration is removed at the moment.
> ```toml
> [dependencies]
> ros_pointcloud2 = { version = "0.5.2", git = "https://github.com/stelzo/ros_pointcloud2.git" }
> ```
ros_pointcloud2 uses its own type for the message `PointCloud2Msg` to keep the library framework agnostic. ROS1 and ROS2 are supported with feature flags.
Get started with the example below, check out the other use cases in the `examples` folder or see the [Documentation](https://docs.rs/ros_pointcloud2/0.5.1/) for a complete guide.
Get started with the example below, check out the other use cases in the `examples` folder or see the [Documentation](https://docs.rs/ros_pointcloud2/0.5.2/) for a complete guide.
## Quickstart
@ -79,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.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.

View File

@ -8,16 +8,12 @@ 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]
ros_pointcloud2 = { path = "../rpcl2", features = ["std", "derive"] }
rpcl2-derive = { path = "../rpcl2-derive" }
[patch.crates-io]
# Fixes https://github.com/adnanademovic/rosrust/issues/210
xml-rpc = { git = "https://github.com/locusrobotics/xml-rpc-rs", branch = "minimum-update" }

View File

@ -8,31 +8,31 @@ 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.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.33", optional = true, default-features = false }
@ -40,7 +40,7 @@ rpcl2-derive = { version = "0.4", optional = true, path = "../rpcl2-derive" }
serde = { version = "1.0", features = ["derive"], optional = true }
[dev-dependencies]
rand = "0.8"
rand = "0.9"
criterion = { version = "0.5", features = ["html_reports"] }
pretty_assertions = "1.0"
@ -51,7 +51,7 @@ path = "benches/roundtrip.rs"
[features]
serde = ["dep:serde", "nalgebra/serde-serialize-no-std"]
#rosrust_msg = ["dep:rosrust_msg"]
rosrust_msg = ["dep:rosrust_msg", "dep:rosrust"]
r2r_msg = ["dep:r2r"]
rayon = ["dep:rayon"]
derive = ["dep:rpcl2-derive"]

View File

@ -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);

View File

@ -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);
}

View File

@ -1,5 +1,3 @@
#![allow(unexpected_cfgs)] // TODO remove when rosrust is fixed
#[cfg(feature = "rosrust_msg")]
#[test]
fn convertxyz_rosrust_msg() {