Feature/support_r2r (#8)
* add r2r crate support and its test * add files for tests of feature r2r_msg * r2r prefixes
This commit is contained in:
parent
8e6f643b45
commit
8096edd6c7
|
|
@ -0,0 +1,17 @@
|
|||
name: galactic_r2r_test
|
||||
|
||||
on:
|
||||
push:
|
||||
pull_request:
|
||||
workflow_dispatch:
|
||||
|
||||
env:
|
||||
CARGO_TERM_COLOR: always
|
||||
|
||||
jobs:
|
||||
tests_galactic:
|
||||
runs-on: ubuntu-latest
|
||||
steps:
|
||||
- uses: actions/checkout@v2
|
||||
- run: docker build . --file ./tests/Dockerfile_r2r_galactic --tag r2r_galactic
|
||||
- run: docker run r2r_galactic cargo test --features r2r_msg
|
||||
|
|
@ -19,6 +19,8 @@ num-traits = "0.2.15"
|
|||
fallible-iterator = "0.3.0"
|
||||
rosrust_msg = { version = "0.1", optional = true }
|
||||
rosrust = { version = "0.9", optional = true }
|
||||
r2r = { version = "0.7.5", optional = true }
|
||||
|
||||
[features]
|
||||
rosrust_msg = ["dep:rosrust_msg", "dep:rosrust"]
|
||||
r2r_msg = ["dep:r2r"]
|
||||
|
|
@ -80,6 +80,71 @@ impl Default for PointCloud2Msg {
|
|||
}
|
||||
}
|
||||
|
||||
#[cfg(feature = "r2r_msg")]
|
||||
impl From<r2r::sensor_msgs::msg::PointCloud2> for PointCloud2Msg {
|
||||
fn from(msg: r2r::sensor_msgs::msg::PointCloud2) -> Self {
|
||||
Self {
|
||||
header: HeaderMsg {
|
||||
seq: 0,
|
||||
stamp: TimeMsg {
|
||||
sec: msg.header.stamp.sec as u32,
|
||||
nsec: msg.header.stamp.nanosec,
|
||||
},
|
||||
frame_id: msg.header.frame_id,
|
||||
},
|
||||
height: msg.height,
|
||||
width: msg.width,
|
||||
fields: msg
|
||||
.fields
|
||||
.into_iter()
|
||||
.map(|field| PointFieldMsg {
|
||||
name: field.name,
|
||||
offset: field.offset,
|
||||
datatype: field.datatype,
|
||||
count: field.count,
|
||||
})
|
||||
.collect(),
|
||||
is_bigendian: msg.is_bigendian,
|
||||
point_step: msg.point_step,
|
||||
row_step: msg.row_step,
|
||||
data: msg.data,
|
||||
is_dense: msg.is_dense,
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#[cfg(feature = "r2r_msg")]
|
||||
impl Into<r2r::sensor_msgs::msg::PointCloud2> for PointCloud2Msg {
|
||||
fn into(self) -> r2r::sensor_msgs::msg::PointCloud2 {
|
||||
r2r::sensor_msgs::msg::PointCloud2 {
|
||||
header: r2r::std_msgs::msg::Header {
|
||||
stamp: r2r::builtin_interfaces::msg::Time {
|
||||
sec: self.header.stamp.sec as i32,
|
||||
nanosec: self.header.stamp.nsec,
|
||||
},
|
||||
frame_id: self.header.frame_id,
|
||||
},
|
||||
height: self.height,
|
||||
width: self.width,
|
||||
fields: self
|
||||
.fields
|
||||
.into_iter()
|
||||
.map(|field| r2r::sensor_msgs::msg::PointField {
|
||||
name: field.name,
|
||||
offset: field.offset,
|
||||
datatype: field.datatype,
|
||||
count: field.count,
|
||||
})
|
||||
.collect(),
|
||||
is_bigendian: self.is_bigendian,
|
||||
point_step: self.point_step,
|
||||
row_step: self.row_step,
|
||||
data: self.data,
|
||||
is_dense: self.is_dense,
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#[cfg(feature = "rosrust_msg")]
|
||||
impl From<rosrust_msg::sensor_msgs::PointCloud2> for PointCloud2Msg {
|
||||
fn from(msg: rosrust_msg::sensor_msgs::PointCloud2) -> Self {
|
||||
|
|
|
|||
|
|
@ -0,0 +1,22 @@
|
|||
# syntax=docker/dockerfile:1
|
||||
FROM ros:galactic
|
||||
|
||||
# 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-galactic-test-msgs ros-galactic-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/tests/r2r_20.04_test.bash
|
||||
ENTRYPOINT [ "/r2r/tests/r2r_20.04_test.bash" ]
|
||||
|
|
@ -0,0 +1,20 @@
|
|||
#!/bin/bash
|
||||
|
||||
. "$HOME/.cargo/env"
|
||||
|
||||
# run rustup to test with latest rust version
|
||||
rustup update
|
||||
|
||||
if [ -e "/opt/ros/humble/setup.bash" ]; then
|
||||
source "/opt/ros/humble/setup.bash"
|
||||
fi
|
||||
if [ -e "/opt/ros/galactic/setup.bash" ]; then
|
||||
source "/opt/ros/galactic/setup.bash"
|
||||
fi
|
||||
if [ -e "/opt/ros/foxy/setup.bash" ]; then
|
||||
source "/opt/ros/foxy/setup.bash"
|
||||
fi
|
||||
|
||||
cd /r2r/ || exit
|
||||
|
||||
"$@"
|
||||
|
|
@ -0,0 +1,33 @@
|
|||
#[cfg(feature = "r2r_msg")]
|
||||
#[test]
|
||||
fn convertxyz_r2r_msg() {
|
||||
use ros_pointcloud2::fallible_iterator::FallibleIterator;
|
||||
use ros_pointcloud2::pcl_utils::PointXYZ;
|
||||
use ros_pointcloud2::ros_types::PointCloud2Msg;
|
||||
use ros_pointcloud2::ConvertXYZ;
|
||||
|
||||
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 = ConvertXYZ::try_from(cloud).unwrap().try_into().unwrap();
|
||||
let rosrust_msg_cloud: r2r::sensor_msgs::msg::PointCloud2 = internal_cloud.into();
|
||||
let convert_back_internal: PointCloud2Msg = rosrust_msg_cloud.into();
|
||||
let to_convert: ConvertXYZ = ConvertXYZ::try_from(convert_back_internal).unwrap();
|
||||
let back_to_type = to_convert.map(|point| Ok(point)).collect::<Vec<PointXYZ>>();
|
||||
assert_eq!(copy, back_to_type.unwrap());
|
||||
}
|
||||
Loading…
Reference in New Issue