Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

add roslibrust ros1 message support #24

Draft
wants to merge 6 commits into
base: main
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
21 changes: 0 additions & 21 deletions .github/workflows/r2r_galactic.yml

This file was deleted.

21 changes: 0 additions & 21 deletions .github/workflows/r2r_humble.yml

This file was deleted.

21 changes: 0 additions & 21 deletions .github/workflows/r2r_iron.yml

This file was deleted.

21 changes: 0 additions & 21 deletions .github/workflows/rclrs_humble.yml

This file was deleted.

21 changes: 0 additions & 21 deletions .github/workflows/rclrs_iron.yml

This file was deleted.

Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
name: rosrust_noetic
name: roslibrust_noetic

on:
push:
Expand All @@ -23,7 +23,7 @@ jobs:
PYTHONPATH: $PYTHONPATH:/usr/lib/python2.7/dist-packages:/usr/local/lib/python2.7/dist-packages
ROS_DISTRO: noetic
steps:
- name: rosrust
- name: roslibrust
uses: actions/checkout@v1
- name: Install latest rust
run: |
Expand All @@ -50,7 +50,7 @@ jobs:
sudo rosdep init
rosdep update # --include-eol-distros # Support EOL distros.
- name: Install ROS additional packages
# Does installing these mean rosrust_msg builds more messages, which is a better
# Does installing these mean roslibrust_msg builds more messages, which is a better
# check? Or does it just slow down the action?
run: |
sudo apt-get install -y ros-$ROS_DISTRO-actionlib
Expand Down Expand Up @@ -96,7 +96,7 @@ jobs:
- name: build
run: |
source /opt/ros/$ROS_DISTRO/setup.bash
cargo build # --verbose
ROS_PACKAGE_PATH=`rospack find geometry_msgs`:`rospack find tf2_msgs`:`rospack find sensor_msgs`:`rospack find std_msgs`:`rospack find actionlib_msgs` cargo build # --verbose
- name: Install ROS packages for tests
run: |
sudo apt-get install -y ros-$ROS_DISTRO-actionlib-tutorials
Expand All @@ -105,4 +105,4 @@ jobs:
- name: test
run: |
source /opt/ros/$ROS_DISTRO/setup.bash
cargo test --features rosrust_msg,derive,nalgebra,rayon
ROS_PACKAGE_PATH=`rospack find geometry_msgs`:`rospack find tf2_msgs`:`rospack find sensor_msgs`:`rospack find std_msgs`:`rospack find actionlib_msgs` cargo test --features roslibrust_msg,derive,nalgebra,rayon
2 changes: 1 addition & 1 deletion Cargo.toml
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
[workspace]

members = [ "derive-test","rpcl2", "rpcl2-derive"]
members = ["derive-test", "ros_pointcloud2", "rpcl2-derive"]

resolver = "2"
9 changes: 5 additions & 4 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -43,8 +43,8 @@ let processed_cloud = in_msg.try_into_iter().unwrap()

There are currently 3 integrations for common ROS crates.

- [rosrust_msg](https://github.com/adnanademovic/rosrust)
- [![Tests](https://github.com/stelzo/ros_pointcloud2/actions/workflows/rosrust_noetic.yml/badge.svg)](https://github.com/stelzo/ros_pointcloud2/actions/workflows/rosrust_noetic.yml)
- [roslibrust_msg](https://github.com/roslibrust/roslibrust)
- TBD roslibrust test to replace old rosrust one
- [r2r_msg](https://github.com/sequenceplanner/r2r)
- [![Tests](https://github.com/stelzo/ros_pointcloud2/actions/workflows/r2r_galactic.yml/badge.svg)](https://github.com/stelzo/ros_pointcloud2/actions/workflows/r2r_galactic.yml)
- [![Tests](https://github.com/stelzo/ros_pointcloud2/actions/workflows/r2r_humble.yml/badge.svg)](https://github.com/stelzo/ros_pointcloud2/actions/workflows/r2r_humble.yml)
Expand All @@ -55,13 +55,14 @@ There are currently 3 integrations for common ROS crates.
- [![Tests](https://github.com/stelzo/ros_pointcloud2/actions/workflows/rclrs_iron.yml/badge.svg)](https://github.com/stelzo/ros_pointcloud2/actions/workflows/rclrs_iron.yml)
- [![Tests](https://github.com/stelzo/ros_pointcloud2/actions/workflows/rclrs_jazzy.yml/badge.svg)](https://github.com/stelzo/ros_pointcloud2/actions/workflows/rclrs_jazzy.yml)

You can use `rosrust` and `r2r` by enabling the respective feature:
You can use `roslibrust` and `r2r` by enabling the respective feature:

```toml
[dependencies]
ros_pointcloud2 = { version = "*", features = ["r2r_msg"]}
# or
ros_pointcloud2 = { version = "*", features = ["rosrust_msg"]}
# ros_pointcloud2 = { version = "*", features = ["roslibrust_msg"]}
ros_pointcloud2 = { version = "*", features = ["roslibrust_msg"]}
```

### rclrs (ros2_rust)
Expand Down
2 changes: 1 addition & 1 deletion derive-test/Cargo.toml
Original file line number Diff line number Diff line change
Expand Up @@ -15,5 +15,5 @@ categories = [
]

[dependencies]
ros_pointcloud2 = { path = "../rpcl2", features = ["std", "derive"] }
ros_pointcloud2 = { path = "../ros_pointcloud2", features = ["std", "derive"] }
rpcl2-derive = { path = "../rpcl2-derive" }
17 changes: 13 additions & 4 deletions rpcl2/Cargo.toml → ros_pointcloud2/Cargo.toml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
[package]
name = "ros_pointcloud2"
version = "0.5.0"
version = "0.6.0"
edition = "2021"
authors = ["Christopher Sieh <[email protected]>"]
description = "Customizable conversions for working with sensor_msgs/PointCloud2."
Expand Down Expand Up @@ -31,14 +31,23 @@ exclude = [
rust-version = "1.63"

[dependencies]
rosrust_msg = { version = "0.1", optional = true }
rosrust = { version = "0.9.11", optional = true }
r2r = { version = "0.9", optional = true }
rayon = { version = "1", optional = true }
nalgebra = { version = "0.33", optional = true, default-features = false }
rpcl2-derive = { version = "0.3", optional = true, path = "../rpcl2-derive" }
memoffset = { version = "0.9", optional = true }

[dependencies.roslibrust]
git = "https://github.com/lucasw/roslibrust"
branch = "get_rx_msg_def_v0_12"
features = ["ros1"]
optional = true

[dependencies.roslibrust_util]
git = "https://github.com/lucasw/tf_roslibrust"
version = "0.2.0"
optional = true

[dev-dependencies]
rand = "0.8"
criterion = { version = "0.5", features = ["html_reports"] }
Expand All @@ -50,7 +59,7 @@ harness = false
path = "benches/roundtrip.rs"

[features]
rosrust_msg = ["dep:rosrust_msg", "dep:rosrust"]
roslibrust_msg = ["dep:roslibrust", "dep:roslibrust_util"]
r2r_msg = ["dep:r2r"]
rayon = ["dep:rayon"]
derive = ["dep:rpcl2-derive", "dep:memoffset"]
Expand Down
File renamed without changes.
File renamed without changes.
6 changes: 3 additions & 3 deletions rpcl2/src/iterator.rs → ros_pointcloud2/src/iterator.rs
Original file line number Diff line number Diff line change
Expand Up @@ -15,15 +15,15 @@ use alloc::vec::Vec;
/// When using within a ROS node, the PointCloud2 (created by the ROS crate) must be converted first.
/// The cost of this operation is low, as it mostly moves ownership without iterating over the point data.
///
/// ROS1 with rosrust:
/// let msg: rosrust_msg::sensor_msgs::PointCloud2; // inside the callback
/// ROS1 with roslibrust:
/// let msg: roslibrust_msg::sensor_msgs::PointCloud2; // inside the callback
/// let converted: ros_pointcloud2::PointCloud2Msg = msg.into();
///
/// ROS2 with r2r:
/// let msg: r2r::sensor_msgs::msg::PointCloud2 = internal_msg.into();
/// let converted: ros_pointcloud2::PointCloud2Msg = msg.into();
///
/// `ros_pointcloud2` supports r2r, rclrs and rosrust as conversion targets out of the box via feature flags.
/// `ros_pointcloud2` supports r2r, rclrs and roslibrust as conversion targets out of the box via feature flags.
///
pub struct PointCloudIterator<const N: usize, C>
where
Expand Down
2 changes: 1 addition & 1 deletion rpcl2/src/lib.rs → ros_pointcloud2/src/lib.rs
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@
//!
//! # Features
//! - 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.
//! - roslibrust_msg — Integration with the [roslibrust](https://github.com/roslibrust/roslibrust) 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 — Offers implementations for the [`PointConvertible`] trait needed for custom points.
//! - rayon — Parallel iterator support for `_par_iter` functions.
Expand Down
File renamed without changes.
File renamed without changes.
45 changes: 27 additions & 18 deletions rpcl2/src/ros.rs → ros_pointcloud2/src/ros.rs
Original file line number Diff line number Diff line change
Expand Up @@ -25,19 +25,28 @@

use alloc::string::String;

#[cfg(feature = "roslibrust_msg")]
use roslibrust::codegen::integral_types::Time as RosTime;

#[cfg(feature = "roslibrust_msg")]
use roslibrust_util::sensor_msgs;

#[cfg(feature = "roslibrust_msg")]
use roslibrust_util::std_msgs;

/// [Time](https://docs.ros2.org/latest/api/builtin_interfaces/msg/Time.html) representation for ROS messages.
#[derive(Clone, Debug, Default)]
pub struct TimeMsg {
pub sec: i32,
pub nanosec: u32,
}

#[cfg(feature = "rosrust_msg")]
impl From<rosrust::Time> for TimeMsg {
fn from(time: rosrust::Time) -> Self {
#[cfg(feature = "roslibrust_msg")]
impl From<RosTime> for TimeMsg {
fn from(time: RosTime) -> Self {
Self {
sec: time.sec as i32,
nanosec: time.nsec,
sec: time.secs as i32,
nanosec: time.nsecs as u32,
}
}
}
Expand Down Expand Up @@ -151,15 +160,15 @@ impl From<crate::PointCloud2Msg> for r2r::sensor_msgs::msg::PointCloud2 {
}
}

#[cfg(feature = "rosrust_msg")]
impl From<rosrust_msg::sensor_msgs::PointCloud2> for crate::PointCloud2Msg {
fn from(msg: rosrust_msg::sensor_msgs::PointCloud2) -> Self {
#[cfg(feature = "roslibrust_msg")]
impl From<sensor_msgs::PointCloud2> for crate::PointCloud2Msg {
fn from(msg: sensor_msgs::PointCloud2) -> Self {
Self {
header: HeaderMsg {
seq: msg.header.seq,
stamp: TimeMsg {
sec: msg.header.stamp.sec as i32,
nanosec: msg.header.stamp.nsec,
sec: msg.header.stamp.secs as i32,
nanosec: msg.header.stamp.nsecs as u32,
},
frame_id: msg.header.frame_id,
},
Expand Down Expand Up @@ -194,15 +203,15 @@ impl From<rosrust_msg::sensor_msgs::PointCloud2> for crate::PointCloud2Msg {
}
}

#[cfg(feature = "rosrust_msg")]
impl From<crate::PointCloud2Msg> for rosrust_msg::sensor_msgs::PointCloud2 {
#[cfg(feature = "roslibrust_msg")]
impl From<crate::PointCloud2Msg> for sensor_msgs::PointCloud2 {
fn from(msg: crate::PointCloud2Msg) -> Self {
rosrust_msg::sensor_msgs::PointCloud2 {
header: rosrust_msg::std_msgs::Header {
sensor_msgs::PointCloud2 {
header: std_msgs::Header {
seq: msg.header.seq,
stamp: rosrust::Time {
sec: msg.header.stamp.sec as u32,
nsec: msg.header.stamp.nanosec,
stamp: RosTime {
secs: msg.header.stamp.sec,
nsecs: msg.header.stamp.nanosec as i32,
},
frame_id: msg.header.frame_id,
},
Expand All @@ -211,7 +220,7 @@ impl From<crate::PointCloud2Msg> for rosrust_msg::sensor_msgs::PointCloud2 {
fields: msg
.fields
.into_iter()
.map(|field| rosrust_msg::sensor_msgs::PointField {
.map(|field| sensor_msgs::PointField {
name: field.name,
offset: field.offset,
datatype: field.datatype,
Expand Down
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#[cfg(feature = "rosrust_msg")]
#[cfg(feature = "roslibrust_msg")]
#[test]
fn convertxyz_rosrust_msg() {
fn convertxyz_roslibrust_msg() {
use ros_pointcloud2::{points::PointXYZ, PointCloud2Msg};

let cloud = vec![
Expand All @@ -22,8 +22,8 @@ fn convertxyz_rosrust_msg() {
];
let copy = cloud.clone();
let internal_cloud = PointCloud2Msg::try_from_iter(cloud).unwrap();
let rosrust_msg_cloud: rosrust_msg::sensor_msgs::PointCloud2 = internal_cloud.into();
let convert_back_internal: PointCloud2Msg = rosrust_msg_cloud.into();
let roslibrust_msg_cloud: roslibrust_util::sensor_msgs::PointCloud2 = internal_cloud.into();
let convert_back_internal: PointCloud2Msg = roslibrust_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);
Expand Down