Compare commits
8 Commits
95459b605c
...
e412096be0
| Author | SHA1 | Date |
|---|---|---|
|
|
e412096be0 | |
|
|
83e9d1019e | |
|
|
46771bfdd0 | |
|
|
15a1db79d6 | |
|
|
4c1e60210e | |
|
|
47b09c60af | |
|
|
c65f204d28 | |
|
|
ff055f93af |
|
|
@ -0,0 +1,108 @@
|
|||
name: roslibrust_noetic
|
||||
|
||||
on:
|
||||
push:
|
||||
branches-ignore:
|
||||
- rclrs
|
||||
pull_request:
|
||||
branches-ignore:
|
||||
- rclrs
|
||||
workflow_dispatch:
|
||||
|
||||
jobs:
|
||||
build:
|
||||
runs-on: ubuntu-20.04
|
||||
env:
|
||||
ROS_CI_DESKTOP: "`lsb_release -cs`" # e.g. [trusty|xenial|...]
|
||||
# CI_SOURCE_PATH: $(pwd)
|
||||
ROSINSTALL_FILE: $CI_SOURCE_PATH/dependencies.rosinstall
|
||||
CATKIN_OPTIONS: $CI_SOURCE_PATH/catkin.options
|
||||
ROS_PARALLEL_JOBS: "-j8 -l6"
|
||||
# Set the python path manually to include /usr/-/python2.7/dist-packages
|
||||
# as this is where apt-get installs python packages.
|
||||
PYTHONPATH: $PYTHONPATH:/usr/lib/python2.7/dist-packages:/usr/local/lib/python2.7/dist-packages
|
||||
ROS_DISTRO: noetic
|
||||
steps:
|
||||
- name: roslibrust
|
||||
uses: actions/checkout@v1
|
||||
- name: Install latest rust
|
||||
run: |
|
||||
curl --proto '=https' --tlsv1.2 https://sh.rustup.rs -sSf | sh -s -- -y
|
||||
rustc --version
|
||||
cargo --version
|
||||
- name: Configure ROS for install
|
||||
run: |
|
||||
sudo sh -c "echo \"deb http://packages.ros.org/ros/ubuntu $ROS_CI_DESKTOP main\" > /etc/apt/sources.list.d/ros-latest.list"
|
||||
sudo apt-key adv --keyserver 'hkp://keyserver.ubuntu.com:80' --recv-key C1CF6E31E6BADE8868B172B4F42ED6FBAB17C654
|
||||
sudo apt-get update -qq
|
||||
sudo apt-get install dpkg
|
||||
sudo apt-get install -y libyaml-cpp-dev
|
||||
- name: Install ROS basic packages
|
||||
run: |
|
||||
sudo apt-get install -y python3-catkin-pkg
|
||||
sudo apt-get install -y python3-catkin-tools
|
||||
sudo apt-get install -y python3-rosdep
|
||||
sudo apt-get install -y python3-wstool
|
||||
sudo apt-get install -y python3-osrf-pycommon
|
||||
sudo apt-get install -y ros-cmake-modules
|
||||
sudo apt-get install -y ros-$ROS_DISTRO-ros-base
|
||||
source /opt/ros/$ROS_DISTRO/setup.bash
|
||||
sudo rosdep init
|
||||
rosdep update # --include-eol-distros # Support EOL distros.
|
||||
- name: Install ROS additional packages
|
||||
# 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
|
||||
sudo apt-get install -y ros-$ROS_DISTRO-actionlib-msgs
|
||||
sudo apt-get install -y ros-$ROS_DISTRO-camera-info-manager
|
||||
sudo apt-get install -y ros-$ROS_DISTRO-compressed-image-transport
|
||||
sudo apt-get install -y ros-$ROS_DISTRO-catkin
|
||||
sudo apt-get install -y ros-$ROS_DISTRO-class-loader
|
||||
sudo apt-get install -y ros-$ROS_DISTRO-cmake-modules
|
||||
sudo apt-get install -y ros-$ROS_DISTRO-cv-bridge
|
||||
sudo apt-get install -y ros-$ROS_DISTRO-dynamic-reconfigure
|
||||
sudo apt-get install -y ros-$ROS_DISTRO-ddynamic-reconfigure
|
||||
# Not in noetic yet
|
||||
# sudo apt-get install -y ros-$ROS_DISTRO-ddynamic-reconfigure-python
|
||||
sudo apt-get install -y ros-$ROS_DISTRO-eigen-conversions
|
||||
sudo apt-get install -y ros-$ROS_DISTRO-geometry-msgs
|
||||
sudo apt-get install -y ros-$ROS_DISTRO-genmsg
|
||||
sudo apt-get install -y ros-$ROS_DISTRO-image-geometry
|
||||
sudo apt-get install -y ros-$ROS_DISTRO-image-proc
|
||||
sudo apt-get install -y ros-$ROS_DISTRO-image-transport
|
||||
sudo apt-get install -y ros-$ROS_DISTRO-message-generation
|
||||
sudo apt-get install -y ros-$ROS_DISTRO-message-runtime
|
||||
# sudo apt-get install -y ros-$ROS_DISTRO-nodelet-core
|
||||
# sudo apt-get install -y ros-$ROS_DISTRO-nodelet-topic-tools
|
||||
# sudo apt-get install -y ros-$ROS_DISTRO-pcl-conversions
|
||||
# sudo apt-get install -y ros-$ROS_DISTRO-pcl-ros
|
||||
sudo apt-get install -y ros-$ROS_DISTRO-pluginlib
|
||||
sudo apt-get install -y ros-$ROS_DISTRO-roscpp
|
||||
sudo apt-get install -y ros-$ROS_DISTRO-roslib
|
||||
sudo apt-get install -y ros-$ROS_DISTRO-roslint
|
||||
sudo apt-get install -y ros-$ROS_DISTRO-rospy
|
||||
sudo apt-get install -y ros-$ROS_DISTRO-rospy-message-converter
|
||||
sudo apt-get install -y ros-$ROS_DISTRO-rostest
|
||||
sudo apt-get install -y ros-$ROS_DISTRO-sensor-msgs
|
||||
sudo apt-get install -y ros-$ROS_DISTRO-std-msgs
|
||||
sudo apt-get install -y ros-$ROS_DISTRO-tf
|
||||
sudo apt-get install -y ros-$ROS_DISTRO-tf-conversions
|
||||
sudo apt-get install -y ros-$ROS_DISTRO-tf2-geometry-msgs
|
||||
sudo apt-get install -y ros-$ROS_DISTRO-tf2-msgs
|
||||
sudo apt-get install -y ros-$ROS_DISTRO-tf2-py
|
||||
sudo apt-get install -y ros-$ROS_DISTRO-tf2-ros
|
||||
sudo apt-get install -y ros-$ROS_DISTRO-tf2-sensor-msgs
|
||||
- name: build
|
||||
run: |
|
||||
source /opt/ros/$ROS_DISTRO/setup.bash
|
||||
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
|
||||
sudo apt-get install -y ros-$ROS_DISTRO-roscpp-tutorials
|
||||
sudo apt-get install -y ros-$ROS_DISTRO-rospy-tutorials
|
||||
- name: test
|
||||
run: |
|
||||
source /opt/ros/$ROS_DISTRO/setup.bash
|
||||
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
|
||||
|
|
@ -1,7 +1,7 @@
|
|||
[package]
|
||||
name = "rpcl2-derive"
|
||||
description = "Derive macros for ros_pointcloud2 crate."
|
||||
version = "0.3.0"
|
||||
version = "0.4.0"
|
||||
edition = "2021"
|
||||
authors = ["Christopher Sieh <stelzo@steado.de>"]
|
||||
homepage = "https://github.com/stelzo/ros_pointcloud2"
|
||||
|
|
|
|||
|
|
@ -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.1"
|
||||
version = "0.5.2"
|
||||
edition = "2021"
|
||||
authors = ["Christopher Sieh <stelzo@steado.de>"]
|
||||
description = "Customizable conversions for working with sensor_msgs/PointCloud2."
|
||||
|
|
@ -28,7 +28,7 @@ exclude = [
|
|||
"**/doc/**",
|
||||
"**/ensure_no_std/**",
|
||||
]
|
||||
rust-version = "1.63"
|
||||
rust-version = "1.77"
|
||||
|
||||
[dependencies]
|
||||
rosrust_msg = { version = "0.1", optional = true }
|
||||
|
|
@ -36,8 +36,20 @@ 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 }
|
||||
rpcl2-derive = { version = "0.4", optional = true, path = "../rpcl2-derive" }
|
||||
|
||||
[dependencies.roslibrust]
|
||||
version = "0.10.2"
|
||||
optional = true
|
||||
features = ["ros1"]
|
||||
|
||||
[dependencies.roslibrust_codegen]
|
||||
version = "0.10"
|
||||
optional = true
|
||||
|
||||
[dependencies.roslibrust_codegen_macro]
|
||||
version = "0.10"
|
||||
optional = true
|
||||
|
||||
[dev-dependencies]
|
||||
rand = "0.8"
|
||||
|
|
@ -50,10 +62,11 @@ harness = false
|
|||
path = "benches/roundtrip.rs"
|
||||
|
||||
[features]
|
||||
roslibrust_msg = ["dep:roslibrust", "dep:roslibrust_codegen", "dep:roslibrust_codegen_macro"]
|
||||
rosrust_msg = ["dep:rosrust_msg", "dep:rosrust"]
|
||||
r2r_msg = ["dep:r2r"]
|
||||
rayon = ["dep:rayon"]
|
||||
derive = ["dep:rpcl2-derive", "dep:memoffset"]
|
||||
derive = ["dep:rpcl2-derive"]
|
||||
nalgebra = ["dep:nalgebra"]
|
||||
std = ["nalgebra/std"]
|
||||
|
||||
|
|
|
|||
|
|
@ -148,10 +148,6 @@ pub mod iterator;
|
|||
|
||||
use crate::ros::{HeaderMsg, PointFieldMsg};
|
||||
|
||||
#[cfg(feature = "derive")]
|
||||
#[doc(hidden)]
|
||||
pub use memoffset;
|
||||
|
||||
use core::str::FromStr;
|
||||
|
||||
#[macro_use]
|
||||
|
|
|
|||
|
|
@ -113,6 +113,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 {
|
||||
|
|
@ -124,12 +125,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 {
|
||||
|
|
@ -138,9 +200,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()
|
||||
}
|
||||
}
|
||||
|
||||
|
|
@ -187,10 +262,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 {}
|
||||
|
|
@ -247,10 +335,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 {}
|
||||
|
|
@ -324,10 +425,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 {}
|
||||
|
|
@ -403,10 +517,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 {}
|
||||
|
|
@ -502,10 +629,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 {}
|
||||
|
|
@ -592,10 +732,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 {}
|
||||
|
|
@ -689,10 +842,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 {
|
||||
|
|
@ -760,10 +926,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 {}
|
||||
|
|
|
|||
|
|
@ -25,6 +25,9 @@
|
|||
|
||||
use alloc::string::String;
|
||||
|
||||
#[cfg(feature = "roslibrust_msg")]
|
||||
roslibrust_codegen_macro::find_and_generate_ros_messages!();
|
||||
|
||||
/// [Time](https://docs.ros2.org/latest/api/builtin_interfaces/msg/Time.html) representation for ROS messages.
|
||||
#[derive(Clone, Debug, Default)]
|
||||
pub struct TimeMsg {
|
||||
|
|
@ -32,6 +35,16 @@ pub struct TimeMsg {
|
|||
pub nanosec: u32,
|
||||
}
|
||||
|
||||
#[cfg(feature = "roslibrust_msg")]
|
||||
impl From<roslibrust_codegen::Time> for TimeMsg {
|
||||
fn from(time: roslibrust_codegen::Time) -> Self {
|
||||
Self {
|
||||
sec: time.secs as i32,
|
||||
nanosec: time.nsecs,
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#[cfg(feature = "rosrust_msg")]
|
||||
impl From<rosrust::Time> for TimeMsg {
|
||||
fn from(time: rosrust::Time) -> Self {
|
||||
|
|
@ -151,6 +164,90 @@ impl From<crate::PointCloud2Msg> for r2r::sensor_msgs::msg::PointCloud2 {
|
|||
}
|
||||
}
|
||||
|
||||
#[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.secs as i32,
|
||||
nanosec: msg.header.stamp.nsecs,
|
||||
},
|
||||
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 = "roslibrust_msg")]
|
||||
impl From<crate::PointCloud2Msg> for sensor_msgs::PointCloud2 {
|
||||
fn from(msg: crate::PointCloud2Msg) -> Self {
|
||||
sensor_msgs::PointCloud2 {
|
||||
header: std_msgs::Header {
|
||||
seq: msg.header.seq,
|
||||
stamp: roslibrust_codegen::Time {
|
||||
secs: msg.header.stamp.sec as u32,
|
||||
nsecs: 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| sensor_msgs::PointField {
|
||||
name: field.name,
|
||||
offset: field.offset,
|
||||
datatype: field.datatype,
|
||||
count: field.count,
|
||||
})
|
||||
.collect(),
|
||||
is_bigendian: if msg.endian == crate::Endian::Big {
|
||||
true
|
||||
} else {
|
||||
false
|
||||
},
|
||||
point_step: msg.point_step,
|
||||
row_step: msg.row_step,
|
||||
data: msg.data,
|
||||
is_dense: if msg.dense == crate::Denseness::Dense {
|
||||
true
|
||||
} else {
|
||||
false
|
||||
},
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#[cfg(feature = "rosrust_msg")]
|
||||
impl From<rosrust_msg::sensor_msgs::PointCloud2> for crate::PointCloud2Msg {
|
||||
fn from(msg: rosrust_msg::sensor_msgs::PointCloud2) -> Self {
|
||||
|
|
|
|||
|
|
@ -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
|
||||
|
||||
"$@"
|
||||
|
|
|
|||
Loading…
Reference in New Issue