prepare version
This commit is contained in:
parent
d67518abff
commit
acab42d203
|
|
@ -23,6 +23,6 @@ jobs:
|
||||||
rustc --version
|
rustc --version
|
||||||
cargo --version
|
cargo --version
|
||||||
- name: Linting
|
- name: Linting
|
||||||
run: cargo clippy --all-targets -- -D warnings
|
run: cargo clippy --all-targets --features derive,nalgebra,rayon -- -D warnings
|
||||||
- name: Tests
|
- name: Tests
|
||||||
run: cargo test --features derive,nalgebra,rayon
|
run: cargo test --features derive,nalgebra,rayon
|
||||||
|
|
|
||||||
|
|
@ -1,6 +1,6 @@
|
||||||
[package]
|
[package]
|
||||||
name = "ros_pointcloud2"
|
name = "ros_pointcloud2"
|
||||||
version = "1.0.0-rc.1"
|
version = "0.5.0-rc.1"
|
||||||
edition = "2021"
|
edition = "2021"
|
||||||
authors = ["Christopher Sieh <stelzo@steado.de>"]
|
authors = ["Christopher Sieh <stelzo@steado.de>"]
|
||||||
description = "Customizable conversions for working with sensor_msgs/PointCloud2."
|
description = "Customizable conversions for working with sensor_msgs/PointCloud2."
|
||||||
|
|
@ -53,7 +53,7 @@ derive = ["dep:rpcl2_derive", "dep:type-layout"]
|
||||||
nalgebra = ["dep:nalgebra"]
|
nalgebra = ["dep:nalgebra"]
|
||||||
std = []
|
std = []
|
||||||
|
|
||||||
default = ["derive", "std"]
|
default = ["std", "derive"]
|
||||||
|
|
||||||
[package.metadata.docs.rs]
|
[package.metadata.docs.rs]
|
||||||
features = ["derive", "nalgebra", "rayon"]
|
features = ["derive", "nalgebra", "rayon"]
|
||||||
|
|
|
||||||
|
|
@ -1,5 +1,5 @@
|
||||||
> [!NOTE]
|
> [!NOTE]
|
||||||
> This library is currently in preparation for v1. For the documentation of the current crates.io v0.4, visit the [docs](https://docs.rs/ros_pointcloud2/0.4.0/ros_pointcloud2/).
|
> 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">
|
<p align="center">
|
||||||
<h3 align="center">ROS PointCloud2</h3>
|
<h3 align="center">ROS PointCloud2</h3>
|
||||||
|
|
@ -10,7 +10,7 @@
|
||||||
|
|
||||||
ros_pointcloud2 uses its own type for the message `PointCloud2Msg` to keep the library framework agnostic. ROS1 and ROS2 are supported with feature flags.
|
ros_pointcloud2 uses its own type for the message `PointCloud2Msg` to keep the library framework agnostic. ROS1 and ROS2 are supported with feature flags.
|
||||||
|
|
||||||
Get started with the example below, check out the other use cases in the `examples` folder or see the [Documentation](https://docs.rs/ros_pointcloud2/1.0.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.0-rc.1/) for a complete guide.
|
||||||
|
|
||||||
## Quickstart
|
## Quickstart
|
||||||
|
|
||||||
|
|
@ -71,7 +71,7 @@ Features do not work properly with `rcrls` because the messages are linked exter
|
||||||
|
|
||||||
```toml
|
```toml
|
||||||
[dependencies]
|
[dependencies]
|
||||||
ros_pointcloud2 = { git = "https://github.com/stelzo/ros_pointcloud2", tag = "v0.4.0_rclrs" }
|
ros_pointcloud2 = { git = "https://github.com/stelzo/ros_pointcloud2", tag = "v0.5.0-rc.1_rclrs" }
|
||||||
```
|
```
|
||||||
|
|
||||||
Also, indicate the following dependencies to your linker inside the `package.xml` of your package.
|
Also, indicate the following dependencies to your linker inside the `package.xml` of your package.
|
||||||
|
|
@ -96,7 +96,7 @@ For minimizing the conversion overhead in general, always use the functions that
|
||||||
|
|
||||||
## `no_std` Environments
|
## `no_std` Environments
|
||||||
|
|
||||||
The `_iter` conversions are compatible with `#[no_std]` environments when 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.
|
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.
|
||||||
|
|
||||||
## License
|
## License
|
||||||
|
|
||||||
|
|
|
||||||
|
|
@ -4,14 +4,9 @@ use crate::{
|
||||||
RPCL2Point,
|
RPCL2Point,
|
||||||
};
|
};
|
||||||
|
|
||||||
#[cfg(not(feature = "std"))]
|
|
||||||
use alloc::string::String;
|
|
||||||
|
|
||||||
#[cfg(not(feature = "std"))]
|
|
||||||
use alloc::vec::Vec;
|
|
||||||
|
|
||||||
#[cfg(not(feature = "std"))]
|
|
||||||
use alloc::borrow::ToOwned;
|
use alloc::borrow::ToOwned;
|
||||||
|
use alloc::string::String;
|
||||||
|
use alloc::vec::Vec;
|
||||||
|
|
||||||
/// The PointCloudIterator provides a an iterator abstraction of the [`PointCloud2Msg`].
|
/// The PointCloudIterator provides a an iterator abstraction of the [`PointCloud2Msg`].
|
||||||
///
|
///
|
||||||
|
|
@ -166,7 +161,7 @@ where
|
||||||
|
|
||||||
struct ByteBufferView<const N: usize> {
|
struct ByteBufferView<const N: usize> {
|
||||||
#[cfg(feature = "rayon")]
|
#[cfg(feature = "rayon")]
|
||||||
data: std::sync::Arc<[u8]>,
|
data: alloc::sync::Arc<[u8]>,
|
||||||
#[cfg(not(feature = "rayon"))]
|
#[cfg(not(feature = "rayon"))]
|
||||||
data: Vec<u8>,
|
data: Vec<u8>,
|
||||||
start_point_idx: usize,
|
start_point_idx: usize,
|
||||||
|
|
@ -189,7 +184,7 @@ impl<const N: usize> ByteBufferView<N> {
|
||||||
) -> Self {
|
) -> Self {
|
||||||
Self {
|
Self {
|
||||||
#[cfg(feature = "rayon")]
|
#[cfg(feature = "rayon")]
|
||||||
data: std::sync::Arc::<[u8]>::from(data),
|
data: alloc::sync::Arc::<[u8]>::from(data),
|
||||||
#[cfg(not(feature = "rayon"))]
|
#[cfg(not(feature = "rayon"))]
|
||||||
data,
|
data,
|
||||||
start_point_idx,
|
start_point_idx,
|
||||||
|
|
@ -380,6 +375,7 @@ where
|
||||||
|
|
||||||
#[cfg(feature = "rayon")]
|
#[cfg(feature = "rayon")]
|
||||||
mod test {
|
mod test {
|
||||||
|
#![allow(clippy::unwrap_used)]
|
||||||
|
|
||||||
#[test]
|
#[test]
|
||||||
fn test_double_ended_iter() {
|
fn test_double_ended_iter() {
|
||||||
|
|
|
||||||
|
|
@ -128,7 +128,7 @@
|
||||||
//! ```
|
//! ```
|
||||||
#![crate_type = "lib"]
|
#![crate_type = "lib"]
|
||||||
#![cfg_attr(docsrs, feature(doc_cfg))]
|
#![cfg_attr(docsrs, feature(doc_cfg))]
|
||||||
#![doc(html_root_url = "https://docs.rs/ros_pointcloud2/1.0.0-rc.1")]
|
#![doc(html_root_url = "https://docs.rs/ros_pointcloud2/0.5.0-rc.1")]
|
||||||
#![warn(clippy::print_stderr)]
|
#![warn(clippy::print_stderr)]
|
||||||
#![warn(clippy::print_stdout)]
|
#![warn(clippy::print_stdout)]
|
||||||
#![warn(clippy::unwrap_used)]
|
#![warn(clippy::unwrap_used)]
|
||||||
|
|
@ -148,16 +148,12 @@ pub mod iterator;
|
||||||
|
|
||||||
use crate::ros::{HeaderMsg, PointFieldMsg};
|
use crate::ros::{HeaderMsg, PointFieldMsg};
|
||||||
|
|
||||||
|
#[cfg(feature = "derive")]
|
||||||
use core::str::FromStr;
|
use core::str::FromStr;
|
||||||
|
|
||||||
#[cfg(not(feature = "std"))]
|
|
||||||
#[macro_use]
|
#[macro_use]
|
||||||
extern crate alloc;
|
extern crate alloc;
|
||||||
|
|
||||||
#[cfg(not(feature = "std"))]
|
|
||||||
use alloc::string::String;
|
use alloc::string::String;
|
||||||
|
|
||||||
#[cfg(not(feature = "std"))]
|
|
||||||
use alloc::vec::Vec;
|
use alloc::vec::Vec;
|
||||||
|
|
||||||
/// All errors that can occur while converting to or from the message type.
|
/// All errors that can occur while converting to or from the message type.
|
||||||
|
|
@ -1474,7 +1470,6 @@ mod tests {
|
||||||
use super::Fields;
|
use super::Fields;
|
||||||
use rpcl2_derive::Fields;
|
use rpcl2_derive::Fields;
|
||||||
|
|
||||||
#[cfg(not(feature = "std"))]
|
|
||||||
use alloc::string::String;
|
use alloc::string::String;
|
||||||
|
|
||||||
#[allow(dead_code)]
|
#[allow(dead_code)]
|
||||||
|
|
|
||||||
|
|
@ -4,7 +4,7 @@ use crate::{Fields, PointConvertible, RPCL2Point};
|
||||||
#[cfg(feature = "derive")]
|
#[cfg(feature = "derive")]
|
||||||
use type_layout::TypeLayout;
|
use type_layout::TypeLayout;
|
||||||
|
|
||||||
#[cfg(all(not(feature = "std"), feature = "derive"))]
|
#[cfg(feature = "derive")]
|
||||||
use alloc::vec::Vec;
|
use alloc::vec::Vec;
|
||||||
|
|
||||||
/// A packed RGB color encoding as used in ROS tools.
|
/// A packed RGB color encoding as used in ROS tools.
|
||||||
|
|
|
||||||
|
|
@ -23,7 +23,6 @@
|
||||||
//! }
|
//! }
|
||||||
//! ```
|
//! ```
|
||||||
|
|
||||||
#[cfg(not(feature = "std"))]
|
|
||||||
use alloc::string::String;
|
use alloc::string::String;
|
||||||
|
|
||||||
/// [Time](https://docs.ros2.org/latest/api/builtin_interfaces/msg/Time.html) representation for ROS messages.
|
/// [Time](https://docs.ros2.org/latest/api/builtin_interfaces/msg/Time.html) representation for ROS messages.
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue