pub mod pointcloud;
use crate::builtin_interfaces::Time;
use crate::cdr::*;
use crate::geometry_msgs::{Quaternion, Vector3};
use crate::std_msgs::Header;
#[derive(PartialEq, Clone, Copy, Debug)]
pub struct NavSatStatus {
pub status: i8,
pub service: u16,
}
impl CdrFixed for NavSatStatus {
const CDR_SIZE: usize = 4; fn read_cdr(cursor: &mut CdrCursor<'_>) -> Result<Self, CdrError> {
let status = cursor.read_i8()?;
let service = cursor.read_u16()?;
Ok(NavSatStatus { status, service })
}
fn write_cdr(&self, writer: &mut CdrWriter<'_>) {
writer.write_i8(self.status);
writer.write_u16(self.service);
}
fn size_cdr(sizer: &mut CdrSizer) {
sizer.size_i8();
sizer.size_u16();
}
}
#[derive(PartialEq, Clone, Copy, Debug)]
pub struct RegionOfInterest {
pub x_offset: u32,
pub y_offset: u32,
pub height: u32,
pub width: u32,
pub do_rectify: bool,
}
impl CdrFixed for RegionOfInterest {
const CDR_SIZE: usize = 17; fn read_cdr(cursor: &mut CdrCursor<'_>) -> Result<Self, CdrError> {
Ok(RegionOfInterest {
x_offset: cursor.read_u32()?,
y_offset: cursor.read_u32()?,
height: cursor.read_u32()?,
width: cursor.read_u32()?,
do_rectify: cursor.read_bool()?,
})
}
fn write_cdr(&self, writer: &mut CdrWriter<'_>) {
writer.write_u32(self.x_offset);
writer.write_u32(self.y_offset);
writer.write_u32(self.height);
writer.write_u32(self.width);
writer.write_bool(self.do_rectify);
}
fn size_cdr(sizer: &mut CdrSizer) {
sizer.size_u32();
sizer.size_u32();
sizer.size_u32();
sizer.size_u32();
sizer.size_bool();
}
}
fn read_f64_array9(c: &mut CdrCursor<'_>) -> Result<[f64; 9], CdrError> {
Ok([
c.read_f64()?,
c.read_f64()?,
c.read_f64()?,
c.read_f64()?,
c.read_f64()?,
c.read_f64()?,
c.read_f64()?,
c.read_f64()?,
c.read_f64()?,
])
}
fn write_f64_array9(w: &mut CdrWriter<'_>, a: &[f64; 9]) {
for v in a {
w.write_f64(*v);
}
}
fn size_f64_array9(s: &mut CdrSizer) {
for _ in 0..9 {
s.size_f64();
}
}
fn read_f64_array12(c: &mut CdrCursor<'_>) -> Result<[f64; 12], CdrError> {
Ok([
c.read_f64()?,
c.read_f64()?,
c.read_f64()?,
c.read_f64()?,
c.read_f64()?,
c.read_f64()?,
c.read_f64()?,
c.read_f64()?,
c.read_f64()?,
c.read_f64()?,
c.read_f64()?,
c.read_f64()?,
])
}
fn write_f64_array12(w: &mut CdrWriter<'_>, a: &[f64; 12]) {
for v in a {
w.write_f64(*v);
}
}
fn size_f64_array12(s: &mut CdrSizer) {
for _ in 0..12 {
s.size_f64();
}
}
pub struct PointFieldView<'a> {
pub name: &'a str,
pub offset: u32,
pub datatype: u8,
pub count: u32,
}
fn scan_point_field_element<'a>(c: &mut CdrCursor<'a>) -> Result<PointFieldView<'a>, CdrError> {
let name = c.read_string()?;
let offset = c.read_u32()?;
let datatype = c.read_u8()?;
let count = c.read_u32()?;
Ok(PointFieldView {
name,
offset,
datatype,
count,
})
}
fn write_point_field_element(w: &mut CdrWriter<'_>, f: &PointFieldView<'_>) {
w.write_string(f.name);
w.write_u32(f.offset);
w.write_u8(f.datatype);
w.write_u32(f.count);
}
fn size_point_field_element(s: &mut CdrSizer, name: &str) {
s.size_string(name);
s.size_u32();
s.size_u8();
s.size_u32();
}
pub struct PointFieldIter<'a> {
cursor: CdrCursor<'a>,
remaining: usize,
}
impl<'a> Iterator for PointFieldIter<'a> {
type Item = PointFieldView<'a>;
fn next(&mut self) -> Option<Self::Item> {
if self.remaining == 0 {
return None;
}
self.remaining -= 1;
Some(
scan_point_field_element(&mut self.cursor)
.expect("point field elements validated during from_cdr"),
)
}
fn size_hint(&self) -> (usize, Option<usize>) {
(self.remaining, Some(self.remaining))
}
}
impl ExactSizeIterator for PointFieldIter<'_> {}
pub struct CompressedImage<B> {
buf: B,
offsets: [usize; 3],
}
impl<B: AsRef<[u8]>> CompressedImage<B> {
pub fn from_cdr(buf: B) -> Result<Self, CdrError> {
let header = Header::<&[u8]>::from_cdr(buf.as_ref())?;
let o0 = header.end_offset();
let mut c = CdrCursor::resume(buf.as_ref(), o0);
let _ = c.read_string()?; let o1 = c.offset();
let _ = c.read_bytes()?; let o2 = c.offset();
Ok(CompressedImage {
offsets: [o0, o1, o2],
buf,
})
}
pub fn header(&self) -> Header<&[u8]> {
Header::from_cdr(self.buf.as_ref()).expect("header bytes validated during from_cdr")
}
pub fn stamp(&self) -> Time {
rd_time(self.buf.as_ref(), CDR_HEADER_SIZE)
}
pub fn frame_id(&self) -> &str {
rd_string(self.buf.as_ref(), CDR_HEADER_SIZE + 8).0
}
pub fn format(&self) -> &str {
rd_string(self.buf.as_ref(), self.offsets[0]).0
}
pub fn data(&self) -> &[u8] {
rd_bytes(self.buf.as_ref(), self.offsets[1]).0
}
pub fn as_cdr(&self) -> &[u8] {
self.buf.as_ref()
}
pub fn cdr_size(&self) -> usize {
self.buf.as_ref().len()
}
pub fn to_cdr(&self) -> Vec<u8> {
self.buf.as_ref().to_vec()
}
}
impl CompressedImage<Vec<u8>> {
#[deprecated(
since = "3.2.0",
note = "use CompressedImage::builder() for allocation-free buffer reuse; CompressedImage::new will be removed in 4.0"
)]
pub fn new(stamp: Time, frame_id: &str, format: &str, data: &[u8]) -> Result<Self, CdrError> {
let mut sizer = CdrSizer::new();
Time::size_cdr(&mut sizer);
sizer.size_string(frame_id);
let o0 = sizer.offset();
sizer.size_string(format);
let o1 = sizer.offset();
sizer.size_bytes(data.len());
let o2 = sizer.offset();
let mut buf = vec![0u8; sizer.size()];
let mut w = CdrWriter::new(&mut buf)?;
stamp.write_cdr(&mut w);
w.write_string(frame_id);
w.write_string(format);
w.write_bytes(data);
w.finish()?;
Ok(CompressedImage {
offsets: [o0, o1, o2],
buf,
})
}
pub fn into_cdr(self) -> Vec<u8> {
self.buf
}
pub fn builder<'a>() -> CompressedImageBuilder<'a> {
CompressedImageBuilder::new()
}
}
pub struct CompressedImageBuilder<'a> {
stamp: Time,
frame_id: std::borrow::Cow<'a, str>,
format: std::borrow::Cow<'a, str>,
data: &'a [u8],
}
impl<'a> Default for CompressedImageBuilder<'a> {
fn default() -> Self {
Self {
stamp: Time { sec: 0, nanosec: 0 },
frame_id: std::borrow::Cow::Borrowed(""),
format: std::borrow::Cow::Borrowed(""),
data: &[],
}
}
}
impl<'a> CompressedImageBuilder<'a> {
pub fn new() -> Self {
Self::default()
}
pub fn stamp(&mut self, t: Time) -> &mut Self {
self.stamp = t;
self
}
pub fn frame_id(&mut self, s: impl Into<std::borrow::Cow<'a, str>>) -> &mut Self {
self.frame_id = s.into();
self
}
pub fn format(&mut self, s: impl Into<std::borrow::Cow<'a, str>>) -> &mut Self {
self.format = s.into();
self
}
pub fn data(&mut self, d: &'a [u8]) -> &mut Self {
self.data = d;
self
}
fn size(&self) -> usize {
let mut s = CdrSizer::new();
Time::size_cdr(&mut s);
s.size_string(&self.frame_id);
s.size_string(&self.format);
s.size_bytes(self.data.len());
s.size()
}
fn write_into(&self, buf: &mut [u8]) -> Result<(), CdrError> {
let mut w = CdrWriter::new(buf)?;
self.stamp.write_cdr(&mut w);
w.write_string(&self.frame_id);
w.write_string(&self.format);
w.write_bytes(self.data);
w.finish()
}
pub fn build(&self) -> Result<CompressedImage<Vec<u8>>, CdrError> {
let mut buf = vec![0u8; self.size()];
self.write_into(&mut buf)?;
CompressedImage::from_cdr(buf)
}
pub fn encode_into_vec(&self, buf: &mut Vec<u8>) -> Result<(), CdrError> {
buf.resize(self.size(), 0);
self.write_into(buf)
}
pub fn encode_into_slice(&self, buf: &mut [u8]) -> Result<usize, CdrError> {
let need = self.size();
if buf.len() < need {
return Err(CdrError::BufferTooShort {
need,
have: buf.len(),
});
}
self.write_into(&mut buf[..need])?;
Ok(need)
}
}
impl<B: AsRef<[u8]> + AsMut<[u8]>> CompressedImage<B> {
pub fn set_stamp(&mut self, t: Time) -> Result<(), CdrError> {
let b = self.buf.as_mut();
wr_i32(b, CDR_HEADER_SIZE, t.sec)?;
wr_u32(b, CDR_HEADER_SIZE + 4, t.nanosec)
}
}
pub struct Image<B> {
buf: B,
offsets: [usize; 3],
}
impl<B: AsRef<[u8]>> Image<B> {
pub fn from_cdr(buf: B) -> Result<Self, CdrError> {
let header = Header::<&[u8]>::from_cdr(buf.as_ref())?;
let o0 = header.end_offset();
let mut c = CdrCursor::resume(buf.as_ref(), o0);
let _ = c.read_u32()?; let _ = c.read_u32()?; let _ = c.read_string()?; let o1 = c.offset();
let _ = c.read_u8()?; let _ = c.read_u32()?; let _ = c.read_bytes()?; let o2 = c.offset();
Ok(Image {
offsets: [o0, o1, o2],
buf,
})
}
pub fn header(&self) -> Header<&[u8]> {
Header::from_cdr(self.buf.as_ref()).expect("header bytes validated during from_cdr")
}
pub fn stamp(&self) -> Time {
rd_time(self.buf.as_ref(), CDR_HEADER_SIZE)
}
pub fn frame_id(&self) -> &str {
rd_string(self.buf.as_ref(), CDR_HEADER_SIZE + 8).0
}
pub fn height(&self) -> u32 {
let p = align(self.offsets[0], 4);
rd_u32(self.buf.as_ref(), p)
}
pub fn width(&self) -> u32 {
let p = align(self.offsets[0], 4) + 4;
rd_u32(self.buf.as_ref(), p)
}
pub fn encoding(&self) -> &str {
let p = align(self.offsets[0], 4) + 8;
rd_string(self.buf.as_ref(), p).0
}
pub fn is_bigendian(&self) -> u8 {
rd_u8(self.buf.as_ref(), self.offsets[1])
}
pub fn step(&self) -> u32 {
let p = align(self.offsets[1] + 1, 4);
rd_u32(self.buf.as_ref(), p)
}
pub fn data(&self) -> &[u8] {
let p = align(self.offsets[1] + 1, 4) + 4;
rd_bytes(self.buf.as_ref(), p).0
}
pub fn as_cdr(&self) -> &[u8] {
self.buf.as_ref()
}
pub fn cdr_size(&self) -> usize {
self.buf.as_ref().len()
}
pub fn to_cdr(&self) -> Vec<u8> {
self.buf.as_ref().to_vec()
}
}
impl Image<Vec<u8>> {
#[deprecated(
since = "3.2.0",
note = "use Image::builder() for allocation-free buffer reuse; Image::new will be removed in 4.0"
)]
pub fn new(
stamp: Time,
frame_id: &str,
height: u32,
width: u32,
encoding: &str,
is_bigendian: u8,
step: u32,
data: &[u8],
) -> Result<Self, CdrError> {
let mut sizer = CdrSizer::new();
Time::size_cdr(&mut sizer);
sizer.size_string(frame_id);
let o0 = sizer.offset();
sizer.size_u32(); sizer.size_u32(); sizer.size_string(encoding);
let o1 = sizer.offset();
sizer.size_u8(); sizer.size_u32(); sizer.size_bytes(data.len());
let o2 = sizer.offset();
let mut buf = vec![0u8; sizer.size()];
let mut w = CdrWriter::new(&mut buf)?;
stamp.write_cdr(&mut w);
w.write_string(frame_id);
w.write_u32(height);
w.write_u32(width);
w.write_string(encoding);
w.write_u8(is_bigendian);
w.write_u32(step);
w.write_bytes(data);
w.finish()?;
Ok(Image {
offsets: [o0, o1, o2],
buf,
})
}
pub fn into_cdr(self) -> Vec<u8> {
self.buf
}
pub fn builder<'a>() -> ImageBuilder<'a> {
ImageBuilder::new()
}
}
impl<B: AsRef<[u8]> + AsMut<[u8]>> Image<B> {
pub fn set_stamp(&mut self, t: Time) -> Result<(), CdrError> {
let b = self.buf.as_mut();
wr_i32(b, CDR_HEADER_SIZE, t.sec)?;
wr_u32(b, CDR_HEADER_SIZE + 4, t.nanosec)
}
pub fn set_height(&mut self, h: u32) -> Result<(), CdrError> {
let p = align(self.offsets[0], 4);
wr_u32(self.buf.as_mut(), p, h)
}
pub fn set_width(&mut self, w: u32) -> Result<(), CdrError> {
let p = align(self.offsets[0], 4) + 4;
wr_u32(self.buf.as_mut(), p, w)
}
pub fn set_is_bigendian(&mut self, v: u8) -> Result<(), CdrError> {
wr_u8(self.buf.as_mut(), self.offsets[1], v)
}
pub fn set_step(&mut self, v: u32) -> Result<(), CdrError> {
let p = align(self.offsets[1] + 1, 4);
wr_u32(self.buf.as_mut(), p, v)
}
}
pub struct ImageBuilder<'a> {
stamp: Time,
frame_id: std::borrow::Cow<'a, str>,
height: u32,
width: u32,
encoding: std::borrow::Cow<'a, str>,
is_bigendian: u8,
step: u32,
data: &'a [u8],
}
impl<'a> Default for ImageBuilder<'a> {
fn default() -> Self {
Self {
stamp: Time { sec: 0, nanosec: 0 },
frame_id: std::borrow::Cow::Borrowed(""),
height: 0,
width: 0,
encoding: std::borrow::Cow::Borrowed(""),
is_bigendian: 0,
step: 0,
data: &[],
}
}
}
impl<'a> ImageBuilder<'a> {
pub fn new() -> Self {
Self::default()
}
pub fn stamp(&mut self, t: Time) -> &mut Self {
self.stamp = t;
self
}
pub fn frame_id(&mut self, s: impl Into<std::borrow::Cow<'a, str>>) -> &mut Self {
self.frame_id = s.into();
self
}
pub fn height(&mut self, h: u32) -> &mut Self {
self.height = h;
self
}
pub fn width(&mut self, w: u32) -> &mut Self {
self.width = w;
self
}
pub fn encoding(&mut self, s: impl Into<std::borrow::Cow<'a, str>>) -> &mut Self {
self.encoding = s.into();
self
}
pub fn is_bigendian(&mut self, v: u8) -> &mut Self {
self.is_bigendian = v;
self
}
pub fn step(&mut self, v: u32) -> &mut Self {
self.step = v;
self
}
pub fn data(&mut self, d: &'a [u8]) -> &mut Self {
self.data = d;
self
}
fn size(&self) -> usize {
let mut s = CdrSizer::new();
Time::size_cdr(&mut s);
s.size_string(&self.frame_id);
s.size_u32(); s.size_u32(); s.size_string(&self.encoding);
s.size_u8(); s.size_u32(); s.size_bytes(self.data.len());
s.size()
}
fn write_into(&self, buf: &mut [u8]) -> Result<(), CdrError> {
let mut w = CdrWriter::new(buf)?;
self.stamp.write_cdr(&mut w);
w.write_string(&self.frame_id);
w.write_u32(self.height);
w.write_u32(self.width);
w.write_string(&self.encoding);
w.write_u8(self.is_bigendian);
w.write_u32(self.step);
w.write_bytes(self.data);
w.finish()
}
pub fn build(&self) -> Result<Image<Vec<u8>>, CdrError> {
let mut buf = vec![0u8; self.size()];
self.write_into(&mut buf)?;
Image::from_cdr(buf)
}
pub fn encode_into_vec(&self, buf: &mut Vec<u8>) -> Result<(), CdrError> {
buf.resize(self.size(), 0);
self.write_into(buf)
}
pub fn encode_into_slice(&self, buf: &mut [u8]) -> Result<usize, CdrError> {
let need = self.size();
if buf.len() < need {
return Err(CdrError::BufferTooShort {
need,
have: buf.len(),
});
}
self.write_into(&mut buf[..need])?;
Ok(need)
}
}
pub struct Imu<B> {
buf: B,
offsets: [usize; 1],
}
impl<B: AsRef<[u8]>> Imu<B> {
pub fn from_cdr(buf: B) -> Result<Self, CdrError> {
let header = Header::<&[u8]>::from_cdr(buf.as_ref())?;
let o0 = header.end_offset();
let mut c = CdrCursor::resume(buf.as_ref(), o0);
Quaternion::read_cdr(&mut c)?;
read_f64_array9(&mut c)?;
Vector3::read_cdr(&mut c)?;
read_f64_array9(&mut c)?;
Vector3::read_cdr(&mut c)?;
read_f64_array9(&mut c)?;
Ok(Imu { offsets: [o0], buf })
}
pub fn header(&self) -> Header<&[u8]> {
Header::from_cdr(self.buf.as_ref()).expect("header bytes validated during from_cdr")
}
pub fn stamp(&self) -> Time {
rd_time(self.buf.as_ref(), CDR_HEADER_SIZE)
}
pub fn frame_id(&self) -> &str {
rd_string(self.buf.as_ref(), CDR_HEADER_SIZE + 8).0
}
fn fixed_base(&self) -> usize {
cdr_align(self.offsets[0], 8)
}
pub fn orientation(&self) -> Quaternion {
let mut c = CdrCursor::resume(self.buf.as_ref(), self.offsets[0]);
Quaternion::read_cdr(&mut c).expect("orientation field validated during from_cdr")
}
pub fn orientation_covariance(&self) -> [f64; 9] {
let mut c = CdrCursor::resume(self.buf.as_ref(), self.fixed_base() + 32);
read_f64_array9(&mut c).expect("covariance field validated during from_cdr")
}
pub fn angular_velocity(&self) -> Vector3 {
let mut c = CdrCursor::resume(self.buf.as_ref(), self.fixed_base() + 104);
Vector3::read_cdr(&mut c).expect("vector3 field validated during from_cdr")
}
pub fn angular_velocity_covariance(&self) -> [f64; 9] {
let mut c = CdrCursor::resume(self.buf.as_ref(), self.fixed_base() + 128);
read_f64_array9(&mut c).expect("covariance field validated during from_cdr")
}
pub fn linear_acceleration(&self) -> Vector3 {
let mut c = CdrCursor::resume(self.buf.as_ref(), self.fixed_base() + 200);
Vector3::read_cdr(&mut c).expect("vector3 field validated during from_cdr")
}
pub fn linear_acceleration_covariance(&self) -> [f64; 9] {
let mut c = CdrCursor::resume(self.buf.as_ref(), self.fixed_base() + 224);
read_f64_array9(&mut c).expect("covariance field validated during from_cdr")
}
pub fn as_cdr(&self) -> &[u8] {
self.buf.as_ref()
}
pub fn to_cdr(&self) -> Vec<u8> {
self.buf.as_ref().to_vec()
}
}
impl Imu<Vec<u8>> {
#[deprecated(
since = "3.2.0",
note = "use Imu::builder() for allocation-free buffer reuse; Imu::new will be removed in 4.0"
)]
pub fn new(
stamp: Time,
frame_id: &str,
orientation: Quaternion,
orientation_covariance: [f64; 9],
angular_velocity: Vector3,
angular_velocity_covariance: [f64; 9],
linear_acceleration: Vector3,
linear_acceleration_covariance: [f64; 9],
) -> Result<Self, CdrError> {
let mut sizer = CdrSizer::new();
Time::size_cdr(&mut sizer);
sizer.size_string(frame_id);
let o0 = sizer.offset();
Quaternion::size_cdr(&mut sizer);
size_f64_array9(&mut sizer);
Vector3::size_cdr(&mut sizer);
size_f64_array9(&mut sizer);
Vector3::size_cdr(&mut sizer);
size_f64_array9(&mut sizer);
let mut buf = vec![0u8; sizer.size()];
let mut w = CdrWriter::new(&mut buf)?;
stamp.write_cdr(&mut w);
w.write_string(frame_id);
orientation.write_cdr(&mut w);
write_f64_array9(&mut w, &orientation_covariance);
angular_velocity.write_cdr(&mut w);
write_f64_array9(&mut w, &angular_velocity_covariance);
linear_acceleration.write_cdr(&mut w);
write_f64_array9(&mut w, &linear_acceleration_covariance);
w.finish()?;
Ok(Imu { offsets: [o0], buf })
}
pub fn into_cdr(self) -> Vec<u8> {
self.buf
}
pub fn builder<'a>() -> ImuBuilder<'a> {
ImuBuilder::new()
}
}
pub struct ImuBuilder<'a> {
stamp: Time,
frame_id: std::borrow::Cow<'a, str>,
orientation: Quaternion,
orientation_covariance: [f64; 9],
angular_velocity: Vector3,
angular_velocity_covariance: [f64; 9],
linear_acceleration: Vector3,
linear_acceleration_covariance: [f64; 9],
}
impl<'a> Default for ImuBuilder<'a> {
fn default() -> Self {
Self {
stamp: Time { sec: 0, nanosec: 0 },
frame_id: std::borrow::Cow::Borrowed(""),
orientation: Quaternion {
x: 0.0,
y: 0.0,
z: 0.0,
w: 0.0,
},
orientation_covariance: [0.0; 9],
angular_velocity: Vector3 {
x: 0.0,
y: 0.0,
z: 0.0,
},
angular_velocity_covariance: [0.0; 9],
linear_acceleration: Vector3 {
x: 0.0,
y: 0.0,
z: 0.0,
},
linear_acceleration_covariance: [0.0; 9],
}
}
}
impl<'a> ImuBuilder<'a> {
pub fn new() -> Self {
Self::default()
}
pub fn stamp(&mut self, t: Time) -> &mut Self {
self.stamp = t;
self
}
pub fn frame_id(&mut self, s: impl Into<std::borrow::Cow<'a, str>>) -> &mut Self {
self.frame_id = s.into();
self
}
pub fn orientation(&mut self, q: Quaternion) -> &mut Self {
self.orientation = q;
self
}
pub fn orientation_covariance(&mut self, c: [f64; 9]) -> &mut Self {
self.orientation_covariance = c;
self
}
pub fn angular_velocity(&mut self, v: Vector3) -> &mut Self {
self.angular_velocity = v;
self
}
pub fn angular_velocity_covariance(&mut self, c: [f64; 9]) -> &mut Self {
self.angular_velocity_covariance = c;
self
}
pub fn linear_acceleration(&mut self, v: Vector3) -> &mut Self {
self.linear_acceleration = v;
self
}
pub fn linear_acceleration_covariance(&mut self, c: [f64; 9]) -> &mut Self {
self.linear_acceleration_covariance = c;
self
}
fn size(&self) -> usize {
let mut s = CdrSizer::new();
Time::size_cdr(&mut s);
s.size_string(&self.frame_id);
Quaternion::size_cdr(&mut s);
size_f64_array9(&mut s);
Vector3::size_cdr(&mut s);
size_f64_array9(&mut s);
Vector3::size_cdr(&mut s);
size_f64_array9(&mut s);
s.size()
}
fn write_into(&self, buf: &mut [u8]) -> Result<(), CdrError> {
let mut w = CdrWriter::new(buf)?;
self.stamp.write_cdr(&mut w);
w.write_string(&self.frame_id);
self.orientation.write_cdr(&mut w);
write_f64_array9(&mut w, &self.orientation_covariance);
self.angular_velocity.write_cdr(&mut w);
write_f64_array9(&mut w, &self.angular_velocity_covariance);
self.linear_acceleration.write_cdr(&mut w);
write_f64_array9(&mut w, &self.linear_acceleration_covariance);
w.finish()
}
pub fn build(&self) -> Result<Imu<Vec<u8>>, CdrError> {
let mut buf = vec![0u8; self.size()];
self.write_into(&mut buf)?;
Imu::from_cdr(buf)
}
pub fn encode_into_vec(&self, buf: &mut Vec<u8>) -> Result<(), CdrError> {
buf.resize(self.size(), 0);
self.write_into(buf)
}
pub fn encode_into_slice(&self, buf: &mut [u8]) -> Result<usize, CdrError> {
let need = self.size();
if buf.len() < need {
return Err(CdrError::BufferTooShort {
need,
have: buf.len(),
});
}
self.write_into(&mut buf[..need])?;
Ok(need)
}
}
impl<B: AsRef<[u8]> + AsMut<[u8]>> Imu<B> {
pub fn set_stamp(&mut self, t: Time) -> Result<(), CdrError> {
let b = self.buf.as_mut();
wr_i32(b, CDR_HEADER_SIZE, t.sec)?;
wr_u32(b, CDR_HEADER_SIZE + 4, t.nanosec)
}
pub fn set_orientation(&mut self, q: Quaternion) -> Result<(), CdrError> {
let p = self.fixed_base();
let b = self.buf.as_mut();
wr_f64(b, p, q.x)?;
wr_f64(b, p + 8, q.y)?;
wr_f64(b, p + 16, q.z)?;
wr_f64(b, p + 24, q.w)
}
pub fn set_orientation_covariance(&mut self, c: [f64; 9]) -> Result<(), CdrError> {
let p = self.fixed_base() + 32;
let b = self.buf.as_mut();
for (i, v) in c.iter().enumerate() {
wr_f64(b, p + i * 8, *v)?;
}
Ok(())
}
pub fn set_angular_velocity(&mut self, v: Vector3) -> Result<(), CdrError> {
let p = self.fixed_base() + 104;
let b = self.buf.as_mut();
wr_f64(b, p, v.x)?;
wr_f64(b, p + 8, v.y)?;
wr_f64(b, p + 16, v.z)
}
pub fn set_angular_velocity_covariance(&mut self, c: [f64; 9]) -> Result<(), CdrError> {
let p = self.fixed_base() + 128;
let b = self.buf.as_mut();
for (i, v) in c.iter().enumerate() {
wr_f64(b, p + i * 8, *v)?;
}
Ok(())
}
pub fn set_linear_acceleration(&mut self, v: Vector3) -> Result<(), CdrError> {
let p = self.fixed_base() + 200;
let b = self.buf.as_mut();
wr_f64(b, p, v.x)?;
wr_f64(b, p + 8, v.y)?;
wr_f64(b, p + 16, v.z)
}
pub fn set_linear_acceleration_covariance(&mut self, c: [f64; 9]) -> Result<(), CdrError> {
let p = self.fixed_base() + 224;
let b = self.buf.as_mut();
for (i, v) in c.iter().enumerate() {
wr_f64(b, p + i * 8, *v)?;
}
Ok(())
}
}
pub struct NavSatFix<B> {
buf: B,
offsets: [usize; 2],
}
impl<B: AsRef<[u8]>> NavSatFix<B> {
pub fn from_cdr(buf: B) -> Result<Self, CdrError> {
let header = Header::<&[u8]>::from_cdr(buf.as_ref())?;
let o0 = header.end_offset();
let mut c = CdrCursor::resume(buf.as_ref(), o0);
NavSatStatus::read_cdr(&mut c)?;
c.align(8);
let o1 = c.offset();
c.read_f64()?; c.read_f64()?; c.read_f64()?; read_f64_array9(&mut c)?; c.read_u8()?; Ok(NavSatFix {
offsets: [o0, o1],
buf,
})
}
pub fn header(&self) -> Header<&[u8]> {
Header::from_cdr(self.buf.as_ref()).expect("header bytes validated during from_cdr")
}
pub fn stamp(&self) -> Time {
rd_time(self.buf.as_ref(), CDR_HEADER_SIZE)
}
pub fn frame_id(&self) -> &str {
rd_string(self.buf.as_ref(), CDR_HEADER_SIZE + 8).0
}
pub fn status(&self) -> NavSatStatus {
let mut c = CdrCursor::resume(self.buf.as_ref(), self.offsets[0]);
NavSatStatus::read_cdr(&mut c).expect("status field validated during from_cdr")
}
#[inline]
fn fixed_base(&self) -> usize {
self.offsets[1]
}
pub fn latitude(&self) -> f64 {
rd_f64(self.buf.as_ref(), self.fixed_base())
}
pub fn longitude(&self) -> f64 {
rd_f64(self.buf.as_ref(), self.fixed_base() + 8)
}
pub fn altitude(&self) -> f64 {
rd_f64(self.buf.as_ref(), self.fixed_base() + 16)
}
pub fn position_covariance(&self) -> [f64; 9] {
let mut c = CdrCursor::resume(self.buf.as_ref(), self.fixed_base() + 24);
read_f64_array9(&mut c).expect("covariance field validated during from_cdr")
}
pub fn position_covariance_type(&self) -> u8 {
rd_u8(self.buf.as_ref(), self.fixed_base() + 96)
}
pub fn as_cdr(&self) -> &[u8] {
self.buf.as_ref()
}
pub fn to_cdr(&self) -> Vec<u8> {
self.buf.as_ref().to_vec()
}
}
impl NavSatFix<Vec<u8>> {
#[deprecated(
since = "3.2.0",
note = "use NavSatFix::builder() for allocation-free buffer reuse; NavSatFix::new will be removed in 4.0"
)]
pub fn new(
stamp: Time,
frame_id: &str,
status: NavSatStatus,
latitude: f64,
longitude: f64,
altitude: f64,
position_covariance: [f64; 9],
position_covariance_type: u8,
) -> Result<Self, CdrError> {
let mut sizer = CdrSizer::new();
Time::size_cdr(&mut sizer);
sizer.size_string(frame_id);
let o0 = sizer.offset();
NavSatStatus::size_cdr(&mut sizer);
sizer.align(8);
let o1 = sizer.offset();
sizer.size_f64(); sizer.size_f64(); sizer.size_f64(); size_f64_array9(&mut sizer);
sizer.size_u8();
let mut buf = vec![0u8; sizer.size()];
let mut w = CdrWriter::new(&mut buf)?;
stamp.write_cdr(&mut w);
w.write_string(frame_id);
status.write_cdr(&mut w);
w.write_f64(latitude);
w.write_f64(longitude);
w.write_f64(altitude);
write_f64_array9(&mut w, &position_covariance);
w.write_u8(position_covariance_type);
w.finish()?;
Ok(NavSatFix {
offsets: [o0, o1],
buf,
})
}
pub fn into_cdr(self) -> Vec<u8> {
self.buf
}
pub fn builder<'a>() -> NavSatFixBuilder<'a> {
NavSatFixBuilder::new()
}
}
pub struct NavSatFixBuilder<'a> {
stamp: Time,
frame_id: std::borrow::Cow<'a, str>,
status: NavSatStatus,
latitude: f64,
longitude: f64,
altitude: f64,
position_covariance: [f64; 9],
position_covariance_type: u8,
}
impl<'a> Default for NavSatFixBuilder<'a> {
fn default() -> Self {
Self {
stamp: Time { sec: 0, nanosec: 0 },
frame_id: std::borrow::Cow::Borrowed(""),
status: NavSatStatus {
status: 0,
service: 0,
},
latitude: 0.0,
longitude: 0.0,
altitude: 0.0,
position_covariance: [0.0; 9],
position_covariance_type: 0,
}
}
}
impl<'a> NavSatFixBuilder<'a> {
pub fn new() -> Self {
Self::default()
}
pub fn stamp(&mut self, t: Time) -> &mut Self {
self.stamp = t;
self
}
pub fn frame_id(&mut self, s: impl Into<std::borrow::Cow<'a, str>>) -> &mut Self {
self.frame_id = s.into();
self
}
pub fn status(&mut self, s: NavSatStatus) -> &mut Self {
self.status = s;
self
}
pub fn latitude(&mut self, v: f64) -> &mut Self {
self.latitude = v;
self
}
pub fn longitude(&mut self, v: f64) -> &mut Self {
self.longitude = v;
self
}
pub fn altitude(&mut self, v: f64) -> &mut Self {
self.altitude = v;
self
}
pub fn position_covariance(&mut self, c: [f64; 9]) -> &mut Self {
self.position_covariance = c;
self
}
pub fn position_covariance_type(&mut self, v: u8) -> &mut Self {
self.position_covariance_type = v;
self
}
fn size(&self) -> usize {
let mut s = CdrSizer::new();
Time::size_cdr(&mut s);
s.size_string(&self.frame_id);
NavSatStatus::size_cdr(&mut s);
s.align(8);
s.size_f64(); s.size_f64(); s.size_f64(); size_f64_array9(&mut s);
s.size_u8(); s.size()
}
fn write_into(&self, buf: &mut [u8]) -> Result<(), CdrError> {
let mut w = CdrWriter::new(buf)?;
self.stamp.write_cdr(&mut w);
w.write_string(&self.frame_id);
self.status.write_cdr(&mut w);
w.write_f64(self.latitude);
w.write_f64(self.longitude);
w.write_f64(self.altitude);
write_f64_array9(&mut w, &self.position_covariance);
w.write_u8(self.position_covariance_type);
w.finish()
}
pub fn build(&self) -> Result<NavSatFix<Vec<u8>>, CdrError> {
let mut buf = vec![0u8; self.size()];
self.write_into(&mut buf)?;
NavSatFix::from_cdr(buf)
}
pub fn encode_into_vec(&self, buf: &mut Vec<u8>) -> Result<(), CdrError> {
buf.resize(self.size(), 0);
self.write_into(buf)
}
pub fn encode_into_slice(&self, buf: &mut [u8]) -> Result<usize, CdrError> {
let need = self.size();
if buf.len() < need {
return Err(CdrError::BufferTooShort {
need,
have: buf.len(),
});
}
self.write_into(&mut buf[..need])?;
Ok(need)
}
}
impl<B: AsRef<[u8]> + AsMut<[u8]>> NavSatFix<B> {
pub fn set_stamp(&mut self, t: Time) -> Result<(), CdrError> {
let b = self.buf.as_mut();
wr_i32(b, CDR_HEADER_SIZE, t.sec)?;
wr_u32(b, CDR_HEADER_SIZE + 4, t.nanosec)
}
pub fn set_status(&mut self, s: NavSatStatus) -> Result<(), CdrError> {
let status_pos = self.offsets[0];
let service_pos = cdr_align(status_pos + 1, 2);
let b = self.buf.as_mut();
wr_i8(b, status_pos, s.status)?;
wr_u16(b, service_pos, s.service)
}
pub fn set_latitude(&mut self, v: f64) -> Result<(), CdrError> {
let p = self.fixed_base();
wr_f64(self.buf.as_mut(), p, v)
}
pub fn set_longitude(&mut self, v: f64) -> Result<(), CdrError> {
let p = self.fixed_base() + 8;
wr_f64(self.buf.as_mut(), p, v)
}
pub fn set_altitude(&mut self, v: f64) -> Result<(), CdrError> {
let p = self.fixed_base() + 16;
wr_f64(self.buf.as_mut(), p, v)
}
pub fn set_position_covariance(&mut self, c: [f64; 9]) -> Result<(), CdrError> {
let p = self.fixed_base() + 24;
let b = self.buf.as_mut();
for (i, v) in c.iter().enumerate() {
wr_f64(b, p + i * 8, *v)?;
}
Ok(())
}
pub fn set_position_covariance_type(&mut self, v: u8) -> Result<(), CdrError> {
let p = self.fixed_base() + 96;
wr_u8(self.buf.as_mut(), p, v)
}
}
pub struct PointField<B> {
buf: B,
offsets: [usize; 1],
}
impl<B: AsRef<[u8]>> PointField<B> {
pub fn from_cdr(buf: B) -> Result<Self, CdrError> {
let mut c = CdrCursor::new(buf.as_ref())?;
let _ = c.read_string()?;
let o0 = c.offset();
c.read_u32()?;
c.read_u8()?;
c.read_u32()?;
Ok(PointField { offsets: [o0], buf })
}
#[inline]
pub fn name(&self) -> &str {
rd_string(self.buf.as_ref(), CDR_HEADER_SIZE).0
}
pub fn offset(&self) -> u32 {
let mut c = CdrCursor::resume(self.buf.as_ref(), self.offsets[0]);
c.read_u32()
.expect("point field element validated during from_cdr")
}
pub fn datatype(&self) -> u8 {
let mut c = CdrCursor::resume(self.buf.as_ref(), self.offsets[0]);
c.read_u32()
.expect("point field element validated during from_cdr"); c.read_u8()
.expect("point field element validated during from_cdr")
}
pub fn count(&self) -> u32 {
let mut c = CdrCursor::resume(self.buf.as_ref(), self.offsets[0]);
c.read_u32()
.expect("point field element validated during from_cdr"); c.read_u8()
.expect("point field element validated during from_cdr"); c.read_u32()
.expect("point field element validated during from_cdr")
}
#[inline]
pub fn as_cdr(&self) -> &[u8] {
self.buf.as_ref()
}
pub fn to_cdr(&self) -> Vec<u8> {
self.buf.as_ref().to_vec()
}
}
impl PointField<Vec<u8>> {
#[deprecated(
since = "3.2.0",
note = "use PointField::builder() for allocation-free buffer reuse; PointField::new will be removed in 4.0"
)]
pub fn new(name: &str, offset: u32, datatype: u8, count: u32) -> Result<Self, CdrError> {
let mut sizer = CdrSizer::new();
sizer.size_string(name);
let o0 = sizer.offset();
sizer.size_u32();
sizer.size_u8();
sizer.size_u32();
let mut buf = vec![0u8; sizer.size()];
let mut w = CdrWriter::new(&mut buf)?;
w.write_string(name);
w.write_u32(offset);
w.write_u8(datatype);
w.write_u32(count);
w.finish()?;
Ok(PointField { offsets: [o0], buf })
}
pub fn into_cdr(self) -> Vec<u8> {
self.buf
}
pub fn builder<'a>() -> PointFieldBuilder<'a> {
PointFieldBuilder::new()
}
}
pub struct PointFieldBuilder<'a> {
name: std::borrow::Cow<'a, str>,
offset: u32,
datatype: u8,
count: u32,
}
impl<'a> Default for PointFieldBuilder<'a> {
fn default() -> Self {
Self {
name: std::borrow::Cow::Borrowed(""),
offset: 0,
datatype: 0,
count: 0,
}
}
}
impl<'a> PointFieldBuilder<'a> {
pub fn new() -> Self {
Self::default()
}
pub fn name(&mut self, s: impl Into<std::borrow::Cow<'a, str>>) -> &mut Self {
self.name = s.into();
self
}
pub fn offset(&mut self, v: u32) -> &mut Self {
self.offset = v;
self
}
pub fn datatype(&mut self, v: u8) -> &mut Self {
self.datatype = v;
self
}
pub fn count(&mut self, v: u32) -> &mut Self {
self.count = v;
self
}
fn size(&self) -> usize {
let mut s = CdrSizer::new();
s.size_string(&self.name);
s.size_u32();
s.size_u8();
s.size_u32();
s.size()
}
fn write_into(&self, buf: &mut [u8]) -> Result<(), CdrError> {
let mut w = CdrWriter::new(buf)?;
w.write_string(&self.name);
w.write_u32(self.offset);
w.write_u8(self.datatype);
w.write_u32(self.count);
w.finish()
}
pub fn build(&self) -> Result<PointField<Vec<u8>>, CdrError> {
let mut buf = vec![0u8; self.size()];
self.write_into(&mut buf)?;
PointField::from_cdr(buf)
}
pub fn encode_into_vec(&self, buf: &mut Vec<u8>) -> Result<(), CdrError> {
buf.resize(self.size(), 0);
self.write_into(buf)
}
pub fn encode_into_slice(&self, buf: &mut [u8]) -> Result<usize, CdrError> {
let need = self.size();
if buf.len() < need {
return Err(CdrError::BufferTooShort {
need,
have: buf.len(),
});
}
self.write_into(&mut buf[..need])?;
Ok(need)
}
}
impl<B: AsRef<[u8]> + AsMut<[u8]>> PointField<B> {
#[inline]
fn offset_pos(&self) -> usize {
cdr_align(self.offsets[0], 4)
}
pub fn set_offset(&mut self, v: u32) -> Result<(), CdrError> {
let p = self.offset_pos();
wr_u32(self.buf.as_mut(), p, v)
}
pub fn set_datatype(&mut self, v: u8) -> Result<(), CdrError> {
let p = self.offset_pos() + 4;
wr_u8(self.buf.as_mut(), p, v)
}
pub fn set_count(&mut self, v: u32) -> Result<(), CdrError> {
let p = cdr_align(self.offset_pos() + 5, 4);
wr_u32(self.buf.as_mut(), p, v)
}
}
pub struct PointCloud2<B> {
buf: B,
offsets: [usize; 3],
}
impl<B: AsRef<[u8]>> PointCloud2<B> {
pub fn from_cdr(buf: B) -> Result<Self, CdrError> {
let header = Header::<&[u8]>::from_cdr(buf.as_ref())?;
let o0 = header.end_offset();
let mut c = CdrCursor::resume(buf.as_ref(), o0);
c.read_u32()?; c.read_u32()?; let raw_fields = c.read_u32()?;
let fields_count = c.check_seq_count(raw_fields, 9)?;
for _ in 0..fields_count {
scan_point_field_element(&mut c)?;
}
let o1 = c.offset();
c.read_bool()?; c.read_u32()?; c.read_u32()?; let _ = c.read_bytes()?; let o2 = c.offset();
c.read_bool()?; Ok(PointCloud2 {
offsets: [o0, o1, o2],
buf,
})
}
pub fn header(&self) -> Header<&[u8]> {
Header::from_cdr(self.buf.as_ref()).expect("header bytes validated during from_cdr")
}
pub fn stamp(&self) -> Time {
rd_time(self.buf.as_ref(), CDR_HEADER_SIZE)
}
pub fn frame_id(&self) -> &str {
rd_string(self.buf.as_ref(), CDR_HEADER_SIZE + 8).0
}
pub fn height(&self) -> u32 {
rd_u32(self.buf.as_ref(), align(self.offsets[0], 4))
}
pub fn width(&self) -> u32 {
rd_u32(self.buf.as_ref(), align(self.offsets[0], 4) + 4)
}
pub fn fields_len(&self) -> u32 {
rd_u32(self.buf.as_ref(), align(self.offsets[0], 4) + 8)
}
pub fn fields(&self) -> Vec<PointFieldView<'_>> {
let b = self.buf.as_ref();
let p = align(self.offsets[0], 4) + 8;
let count = rd_u32(b, p) as usize;
let mut c = CdrCursor::resume(b, p + 4);
(0..count)
.map(|_| {
scan_point_field_element(&mut c)
.expect("point field elements validated during from_cdr")
})
.collect()
}
pub fn fields_iter(&self) -> PointFieldIter<'_> {
let b = self.buf.as_ref();
let p = align(self.offsets[0], 4) + 8;
let count = rd_u32(b, p) as usize;
let cursor = CdrCursor::resume(b, p + 4);
PointFieldIter {
cursor,
remaining: count,
}
}
pub fn point_count(&self) -> usize {
(self.height() as usize) * (self.width() as usize)
}
pub fn as_dyn_cloud(
&self,
) -> Result<pointcloud::DynPointCloud<'_>, pointcloud::PointCloudError> {
pointcloud::DynPointCloud::from_pointcloud2(self)
}
pub fn as_typed_cloud<P: pointcloud::Point>(
&self,
) -> Result<pointcloud::PointCloud<'_, P>, pointcloud::PointCloudError> {
pointcloud::PointCloud::from_pointcloud2(self)
}
pub fn is_bigendian(&self) -> bool {
rd_bool(self.buf.as_ref(), self.offsets[1])
}
pub fn point_step(&self) -> u32 {
rd_u32(self.buf.as_ref(), align(self.offsets[1] + 1, 4))
}
pub fn row_step(&self) -> u32 {
rd_u32(self.buf.as_ref(), align(self.offsets[1] + 1, 4) + 4)
}
pub fn data(&self) -> &[u8] {
rd_bytes(self.buf.as_ref(), align(self.offsets[1] + 1, 4) + 8).0
}
pub fn is_dense(&self) -> bool {
rd_bool(self.buf.as_ref(), self.offsets[2])
}
pub fn as_cdr(&self) -> &[u8] {
self.buf.as_ref()
}
pub fn to_cdr(&self) -> Vec<u8> {
self.buf.as_ref().to_vec()
}
}
impl PointCloud2<Vec<u8>> {
#[deprecated(
since = "3.2.0",
note = "use PointCloud2::builder() for allocation-free buffer reuse; PointCloud2::new will be removed in 4.0"
)]
pub fn new(
stamp: Time,
frame_id: &str,
height: u32,
width: u32,
fields: &[PointFieldView<'_>],
is_bigendian: bool,
point_step: u32,
row_step: u32,
data: &[u8],
is_dense: bool,
) -> Result<Self, CdrError> {
let mut sizer = CdrSizer::new();
Time::size_cdr(&mut sizer);
sizer.size_string(frame_id);
let o0 = sizer.offset();
sizer.size_u32(); sizer.size_u32(); sizer.size_u32(); for f in fields {
size_point_field_element(&mut sizer, f.name);
}
let o1 = sizer.offset();
sizer.size_bool(); sizer.size_u32(); sizer.size_u32(); sizer.size_bytes(data.len());
let o2 = sizer.offset();
sizer.size_bool();
let mut buf = vec![0u8; sizer.size()];
let mut w = CdrWriter::new(&mut buf)?;
stamp.write_cdr(&mut w);
w.write_string(frame_id);
w.write_u32(height);
w.write_u32(width);
w.write_u32(fields.len() as u32);
for f in fields {
write_point_field_element(&mut w, f);
}
w.write_bool(is_bigendian);
w.write_u32(point_step);
w.write_u32(row_step);
w.write_bytes(data);
w.write_bool(is_dense);
w.finish()?;
Ok(PointCloud2 {
offsets: [o0, o1, o2],
buf,
})
}
pub fn into_cdr(self) -> Vec<u8> {
self.buf
}
pub fn builder<'a>() -> PointCloud2Builder<'a> {
PointCloud2Builder::new()
}
}
pub struct PointCloud2Builder<'a> {
stamp: Time,
frame_id: std::borrow::Cow<'a, str>,
height: u32,
width: u32,
fields: &'a [PointFieldView<'a>],
is_bigendian: bool,
point_step: u32,
row_step: u32,
data: &'a [u8],
is_dense: bool,
}
impl<'a> Default for PointCloud2Builder<'a> {
fn default() -> Self {
Self {
stamp: Time { sec: 0, nanosec: 0 },
frame_id: std::borrow::Cow::Borrowed(""),
height: 0,
width: 0,
fields: &[],
is_bigendian: false,
point_step: 0,
row_step: 0,
data: &[],
is_dense: false,
}
}
}
impl<'a> PointCloud2Builder<'a> {
pub fn new() -> Self {
Self::default()
}
pub fn stamp(&mut self, t: Time) -> &mut Self {
self.stamp = t;
self
}
pub fn frame_id(&mut self, s: impl Into<std::borrow::Cow<'a, str>>) -> &mut Self {
self.frame_id = s.into();
self
}
pub fn height(&mut self, v: u32) -> &mut Self {
self.height = v;
self
}
pub fn width(&mut self, v: u32) -> &mut Self {
self.width = v;
self
}
pub fn fields(&mut self, f: &'a [PointFieldView<'a>]) -> &mut Self {
self.fields = f;
self
}
pub fn is_bigendian(&mut self, v: bool) -> &mut Self {
self.is_bigendian = v;
self
}
pub fn point_step(&mut self, v: u32) -> &mut Self {
self.point_step = v;
self
}
pub fn row_step(&mut self, v: u32) -> &mut Self {
self.row_step = v;
self
}
pub fn data(&mut self, d: &'a [u8]) -> &mut Self {
self.data = d;
self
}
pub fn is_dense(&mut self, v: bool) -> &mut Self {
self.is_dense = v;
self
}
fn size(&self) -> usize {
let mut s = CdrSizer::new();
Time::size_cdr(&mut s);
s.size_string(&self.frame_id);
s.size_u32(); s.size_u32(); s.size_u32(); for f in self.fields {
size_point_field_element(&mut s, f.name);
}
s.size_bool(); s.size_u32(); s.size_u32(); s.size_bytes(self.data.len());
s.size_bool(); s.size()
}
fn write_into(&self, buf: &mut [u8]) -> Result<(), CdrError> {
let mut w = CdrWriter::new(buf)?;
self.stamp.write_cdr(&mut w);
w.write_string(&self.frame_id);
w.write_u32(self.height);
w.write_u32(self.width);
w.write_u32(self.fields.len() as u32);
for f in self.fields {
write_point_field_element(&mut w, f);
}
w.write_bool(self.is_bigendian);
w.write_u32(self.point_step);
w.write_u32(self.row_step);
w.write_bytes(self.data);
w.write_bool(self.is_dense);
w.finish()
}
pub fn build(&self) -> Result<PointCloud2<Vec<u8>>, CdrError> {
let mut buf = vec![0u8; self.size()];
self.write_into(&mut buf)?;
PointCloud2::from_cdr(buf)
}
pub fn encode_into_vec(&self, buf: &mut Vec<u8>) -> Result<(), CdrError> {
buf.resize(self.size(), 0);
self.write_into(buf)
}
pub fn encode_into_slice(&self, buf: &mut [u8]) -> Result<usize, CdrError> {
let need = self.size();
if buf.len() < need {
return Err(CdrError::BufferTooShort {
need,
have: buf.len(),
});
}
self.write_into(&mut buf[..need])?;
Ok(need)
}
}
impl<B: AsRef<[u8]> + AsMut<[u8]>> PointCloud2<B> {
pub fn set_stamp(&mut self, t: Time) -> Result<(), CdrError> {
let b = self.buf.as_mut();
wr_i32(b, CDR_HEADER_SIZE, t.sec)?;
wr_u32(b, CDR_HEADER_SIZE + 4, t.nanosec)
}
pub fn set_height(&mut self, h: u32) -> Result<(), CdrError> {
let p = align(self.offsets[0], 4);
wr_u32(self.buf.as_mut(), p, h)
}
pub fn set_width(&mut self, w: u32) -> Result<(), CdrError> {
let p = align(self.offsets[0], 4) + 4;
wr_u32(self.buf.as_mut(), p, w)
}
pub fn set_is_bigendian(&mut self, v: bool) -> Result<(), CdrError> {
wr_bool(self.buf.as_mut(), self.offsets[1], v)
}
pub fn set_point_step(&mut self, v: u32) -> Result<(), CdrError> {
let p = align(self.offsets[1] + 1, 4);
wr_u32(self.buf.as_mut(), p, v)
}
pub fn set_row_step(&mut self, v: u32) -> Result<(), CdrError> {
let p = align(self.offsets[1] + 1, 4) + 4;
wr_u32(self.buf.as_mut(), p, v)
}
pub fn set_is_dense(&mut self, v: bool) -> Result<(), CdrError> {
wr_bool(self.buf.as_mut(), self.offsets[2], v)
}
}
pub struct CameraInfo<B> {
buf: B,
offsets: [usize; 3],
}
impl<B: AsRef<[u8]>> CameraInfo<B> {
pub fn from_cdr(buf: B) -> Result<Self, CdrError> {
let header = Header::<&[u8]>::from_cdr(buf.as_ref())?;
let o0 = header.end_offset();
let mut c = CdrCursor::resume(buf.as_ref(), o0);
c.read_u32()?; c.read_u32()?; let _ = c.read_string()?; let o1 = c.offset();
let d_count = c.read_u32()? as usize;
c.skip_seq_8(d_count)?;
let o2 = c.offset();
read_f64_array9(&mut c)?; read_f64_array9(&mut c)?; read_f64_array12(&mut c)?; c.read_u32()?; c.read_u32()?; RegionOfInterest::read_cdr(&mut c)?;
Ok(CameraInfo {
offsets: [o0, o1, o2],
buf,
})
}
pub fn header(&self) -> Header<&[u8]> {
Header::from_cdr(self.buf.as_ref()).expect("header bytes validated during from_cdr")
}
pub fn stamp(&self) -> Time {
rd_time(self.buf.as_ref(), CDR_HEADER_SIZE)
}
pub fn frame_id(&self) -> &str {
rd_string(self.buf.as_ref(), CDR_HEADER_SIZE + 8).0
}
pub fn height(&self) -> u32 {
rd_u32(self.buf.as_ref(), align(self.offsets[0], 4))
}
pub fn width(&self) -> u32 {
rd_u32(self.buf.as_ref(), align(self.offsets[0], 4) + 4)
}
pub fn distortion_model(&self) -> &str {
rd_string(self.buf.as_ref(), align(self.offsets[0], 4) + 8).0
}
pub fn d_len(&self) -> usize {
rd_u32(self.buf.as_ref(), align(self.offsets[1], 4)) as usize
}
pub fn d_get(&self, i: usize) -> f64 {
let start = cdr_align(align(self.offsets[1], 4) + 4, 8);
rd_f64(self.buf.as_ref(), start + i * 8)
}
fn fixed_base(&self) -> usize {
cdr_align(self.offsets[2], 8)
}
pub fn k(&self) -> [f64; 9] {
let mut c = CdrCursor::resume(self.buf.as_ref(), self.fixed_base());
read_f64_array9(&mut c).expect("covariance field validated during from_cdr")
}
pub fn r(&self) -> [f64; 9] {
let mut c = CdrCursor::resume(self.buf.as_ref(), self.fixed_base() + 72);
read_f64_array9(&mut c).expect("covariance field validated during from_cdr")
}
pub fn p(&self) -> [f64; 12] {
let mut c = CdrCursor::resume(self.buf.as_ref(), self.fixed_base() + 144);
read_f64_array12(&mut c).expect("projection matrix validated during from_cdr")
}
pub fn binning_x(&self) -> u32 {
rd_u32(self.buf.as_ref(), self.fixed_base() + 240)
}
pub fn binning_y(&self) -> u32 {
rd_u32(self.buf.as_ref(), self.fixed_base() + 244)
}
pub fn roi(&self) -> RegionOfInterest {
let mut c = CdrCursor::resume(self.buf.as_ref(), self.fixed_base() + 248);
RegionOfInterest::read_cdr(&mut c).expect("roi field validated during from_cdr")
}
pub fn as_cdr(&self) -> &[u8] {
self.buf.as_ref()
}
pub fn to_cdr(&self) -> Vec<u8> {
self.buf.as_ref().to_vec()
}
}
impl CameraInfo<Vec<u8>> {
#[deprecated(
since = "3.2.0",
note = "use CameraInfo::builder() for allocation-free buffer reuse; CameraInfo::new will be removed in 4.0"
)]
#[allow(clippy::too_many_arguments)]
pub fn new(
stamp: Time,
frame_id: &str,
height: u32,
width: u32,
distortion_model: &str,
d: &[f64],
k: [f64; 9],
r: [f64; 9],
p: [f64; 12],
binning_x: u32,
binning_y: u32,
roi: RegionOfInterest,
) -> Result<Self, CdrError> {
let mut sizer = CdrSizer::new();
Time::size_cdr(&mut sizer);
sizer.size_string(frame_id);
let o0 = sizer.offset();
sizer.size_u32(); sizer.size_u32(); sizer.size_string(distortion_model);
let o1 = sizer.offset();
sizer.size_u32();
sizer.size_seq_8(d.len());
let o2 = sizer.offset();
size_f64_array9(&mut sizer);
size_f64_array9(&mut sizer);
size_f64_array12(&mut sizer);
sizer.size_u32(); sizer.size_u32(); RegionOfInterest::size_cdr(&mut sizer);
let mut buf = vec![0u8; sizer.size()];
let mut w = CdrWriter::new(&mut buf)?;
stamp.write_cdr(&mut w);
w.write_string(frame_id);
w.write_u32(height);
w.write_u32(width);
w.write_string(distortion_model);
w.write_u32(d.len() as u32);
w.write_slice_f64(d);
write_f64_array9(&mut w, &k);
write_f64_array9(&mut w, &r);
write_f64_array12(&mut w, &p);
w.write_u32(binning_x);
w.write_u32(binning_y);
roi.write_cdr(&mut w);
w.finish()?;
Ok(CameraInfo {
offsets: [o0, o1, o2],
buf,
})
}
pub fn into_cdr(self) -> Vec<u8> {
self.buf
}
pub fn builder<'a>() -> CameraInfoBuilder<'a> {
CameraInfoBuilder::new()
}
}
pub struct CameraInfoBuilder<'a> {
stamp: Time,
frame_id: std::borrow::Cow<'a, str>,
height: u32,
width: u32,
distortion_model: std::borrow::Cow<'a, str>,
d: &'a [f64],
k: [f64; 9],
r: [f64; 9],
p: [f64; 12],
binning_x: u32,
binning_y: u32,
roi: RegionOfInterest,
}
impl<'a> Default for CameraInfoBuilder<'a> {
fn default() -> Self {
Self {
stamp: Time { sec: 0, nanosec: 0 },
frame_id: std::borrow::Cow::Borrowed(""),
height: 0,
width: 0,
distortion_model: std::borrow::Cow::Borrowed(""),
d: &[],
k: [0.0; 9],
r: [0.0; 9],
p: [0.0; 12],
binning_x: 0,
binning_y: 0,
roi: RegionOfInterest {
x_offset: 0,
y_offset: 0,
height: 0,
width: 0,
do_rectify: false,
},
}
}
}
impl<'a> CameraInfoBuilder<'a> {
pub fn new() -> Self {
Self::default()
}
pub fn stamp(&mut self, t: Time) -> &mut Self {
self.stamp = t;
self
}
pub fn frame_id(&mut self, s: impl Into<std::borrow::Cow<'a, str>>) -> &mut Self {
self.frame_id = s.into();
self
}
pub fn height(&mut self, v: u32) -> &mut Self {
self.height = v;
self
}
pub fn width(&mut self, v: u32) -> &mut Self {
self.width = v;
self
}
pub fn distortion_model(&mut self, s: impl Into<std::borrow::Cow<'a, str>>) -> &mut Self {
self.distortion_model = s.into();
self
}
pub fn d(&mut self, d: &'a [f64]) -> &mut Self {
self.d = d;
self
}
pub fn k(&mut self, k: [f64; 9]) -> &mut Self {
self.k = k;
self
}
pub fn r(&mut self, r: [f64; 9]) -> &mut Self {
self.r = r;
self
}
pub fn p(&mut self, p: [f64; 12]) -> &mut Self {
self.p = p;
self
}
pub fn binning_x(&mut self, v: u32) -> &mut Self {
self.binning_x = v;
self
}
pub fn binning_y(&mut self, v: u32) -> &mut Self {
self.binning_y = v;
self
}
pub fn roi(&mut self, r: RegionOfInterest) -> &mut Self {
self.roi = r;
self
}
fn size(&self) -> usize {
let mut s = CdrSizer::new();
Time::size_cdr(&mut s);
s.size_string(&self.frame_id);
s.size_u32(); s.size_u32(); s.size_string(&self.distortion_model);
s.size_u32();
s.size_seq_8(self.d.len());
size_f64_array9(&mut s);
size_f64_array9(&mut s);
size_f64_array12(&mut s);
s.size_u32(); s.size_u32(); RegionOfInterest::size_cdr(&mut s);
s.size()
}
fn write_into(&self, buf: &mut [u8]) -> Result<(), CdrError> {
let mut w = CdrWriter::new(buf)?;
self.stamp.write_cdr(&mut w);
w.write_string(&self.frame_id);
w.write_u32(self.height);
w.write_u32(self.width);
w.write_string(&self.distortion_model);
w.write_u32(self.d.len() as u32);
w.write_slice_f64(self.d);
write_f64_array9(&mut w, &self.k);
write_f64_array9(&mut w, &self.r);
write_f64_array12(&mut w, &self.p);
w.write_u32(self.binning_x);
w.write_u32(self.binning_y);
self.roi.write_cdr(&mut w);
w.finish()
}
pub fn build(&self) -> Result<CameraInfo<Vec<u8>>, CdrError> {
let mut buf = vec![0u8; self.size()];
self.write_into(&mut buf)?;
CameraInfo::from_cdr(buf)
}
pub fn encode_into_vec(&self, buf: &mut Vec<u8>) -> Result<(), CdrError> {
buf.resize(self.size(), 0);
self.write_into(buf)
}
pub fn encode_into_slice(&self, buf: &mut [u8]) -> Result<usize, CdrError> {
let need = self.size();
if buf.len() < need {
return Err(CdrError::BufferTooShort {
need,
have: buf.len(),
});
}
self.write_into(&mut buf[..need])?;
Ok(need)
}
}
impl<B: AsRef<[u8]> + AsMut<[u8]>> CameraInfo<B> {
pub fn set_stamp(&mut self, t: Time) -> Result<(), CdrError> {
let b = self.buf.as_mut();
wr_i32(b, CDR_HEADER_SIZE, t.sec)?;
wr_u32(b, CDR_HEADER_SIZE + 4, t.nanosec)
}
pub fn set_height(&mut self, h: u32) -> Result<(), CdrError> {
let p = align(self.offsets[0], 4);
wr_u32(self.buf.as_mut(), p, h)
}
pub fn set_width(&mut self, w: u32) -> Result<(), CdrError> {
let p = align(self.offsets[0], 4) + 4;
wr_u32(self.buf.as_mut(), p, w)
}
pub fn set_k(&mut self, k: [f64; 9]) -> Result<(), CdrError> {
let p = self.fixed_base();
let b = self.buf.as_mut();
for (i, v) in k.iter().enumerate() {
wr_f64(b, p + i * 8, *v)?;
}
Ok(())
}
pub fn set_r(&mut self, r: [f64; 9]) -> Result<(), CdrError> {
let p = self.fixed_base() + 72;
let b = self.buf.as_mut();
for (i, v) in r.iter().enumerate() {
wr_f64(b, p + i * 8, *v)?;
}
Ok(())
}
pub fn set_p(&mut self, p_mat: [f64; 12]) -> Result<(), CdrError> {
let p = self.fixed_base() + 144;
let b = self.buf.as_mut();
for (i, v) in p_mat.iter().enumerate() {
wr_f64(b, p + i * 8, *v)?;
}
Ok(())
}
pub fn set_binning_x(&mut self, v: u32) -> Result<(), CdrError> {
let p = self.fixed_base() + 240;
wr_u32(self.buf.as_mut(), p, v)
}
pub fn set_binning_y(&mut self, v: u32) -> Result<(), CdrError> {
let p = self.fixed_base() + 244;
wr_u32(self.buf.as_mut(), p, v)
}
pub fn set_roi(&mut self, r: RegionOfInterest) -> Result<(), CdrError> {
let p = self.fixed_base() + 248;
let b = self.buf.as_mut();
wr_u32(b, p, r.x_offset)?;
wr_u32(b, p + 4, r.y_offset)?;
wr_u32(b, p + 8, r.height)?;
wr_u32(b, p + 12, r.width)?;
wr_bool(b, p + 16, r.do_rectify)
}
}
pub mod nav_sat_fix {
pub const COVARIANCE_TYPE_UNKNOWN: u8 = 0;
pub const COVARIANCE_TYPE_APPROXIMATED: u8 = 1;
pub const COVARIANCE_TYPE_DIAGONAL_KNOWN: u8 = 2;
pub const COVARIANCE_TYPE_KNOWN: u8 = 3;
}
pub mod nav_sat_status {
pub const STATUS_NO_FIX: i8 = -1;
pub const STATUS_FIX: i8 = 0;
pub const STATUS_SBAS_FIX: i8 = 1;
pub const STATUS_GBAS_FIX: i8 = 2;
pub const SERVICE_GPS: u8 = 1;
pub const SERVICE_GLONASS: u8 = 2;
pub const SERVICE_COMPASS: u8 = 4;
pub const SERVICE_GALILEO: u8 = 8;
}
pub mod point_field {
pub const INT8: u8 = 1;
pub const UINT8: u8 = 2;
pub const INT16: u8 = 3;
pub const UINT16: u8 = 4;
pub const INT32: u8 = 5;
pub const UINT32: u8 = 6;
pub const FLOAT32: u8 = 7;
pub const FLOAT64: u8 = 8;
}
pub struct MagneticField<B> {
buf: B,
offsets: [usize; 1],
}
impl<B: AsRef<[u8]>> MagneticField<B> {
pub fn from_cdr(buf: B) -> Result<Self, CdrError> {
let header = Header::<&[u8]>::from_cdr(buf.as_ref())?;
let pre = header.end_offset();
let mut c = CdrCursor::resume(buf.as_ref(), pre);
c.align(8);
let o0 = c.offset();
Vector3::read_cdr(&mut c)?;
read_f64_array9(&mut c)?;
Ok(MagneticField { offsets: [o0], buf })
}
pub fn header(&self) -> Header<&[u8]> {
Header::from_cdr(self.buf.as_ref()).expect("header bytes validated during from_cdr")
}
pub fn stamp(&self) -> Time {
rd_time(self.buf.as_ref(), CDR_HEADER_SIZE)
}
pub fn frame_id(&self) -> &str {
rd_string(self.buf.as_ref(), CDR_HEADER_SIZE + 8).0
}
pub fn magnetic_field(&self) -> Vector3 {
let mut c = CdrCursor::resume(self.buf.as_ref(), self.offsets[0]);
Vector3::read_cdr(&mut c).expect("magnetic_field validated during from_cdr")
}
pub fn magnetic_field_covariance(&self) -> [f64; 9] {
let mut c = CdrCursor::resume(self.buf.as_ref(), self.offsets[0] + 24);
read_f64_array9(&mut c).expect("covariance validated during from_cdr")
}
pub fn as_cdr(&self) -> &[u8] {
self.buf.as_ref()
}
pub fn to_cdr(&self) -> Vec<u8> {
self.buf.as_ref().to_vec()
}
}
impl MagneticField<Vec<u8>> {
#[deprecated(
since = "3.2.0",
note = "use MagneticField::builder() for allocation-free buffer reuse; MagneticField::new will be removed in 4.0"
)]
pub fn new(
stamp: Time,
frame_id: &str,
magnetic_field: Vector3,
magnetic_field_covariance: [f64; 9],
) -> Result<Self, CdrError> {
let mut sizer = CdrSizer::new();
Time::size_cdr(&mut sizer);
sizer.size_string(frame_id);
sizer.align(8);
let o0 = sizer.offset();
Vector3::size_cdr(&mut sizer);
size_f64_array9(&mut sizer);
let mut buf = vec![0u8; sizer.size()];
let mut w = CdrWriter::new(&mut buf)?;
stamp.write_cdr(&mut w);
w.write_string(frame_id);
magnetic_field.write_cdr(&mut w);
write_f64_array9(&mut w, &magnetic_field_covariance);
w.finish()?;
Ok(MagneticField { offsets: [o0], buf })
}
pub fn into_cdr(self) -> Vec<u8> {
self.buf
}
pub fn builder<'a>() -> MagneticFieldBuilder<'a> {
MagneticFieldBuilder::new()
}
}
pub struct MagneticFieldBuilder<'a> {
stamp: Time,
frame_id: std::borrow::Cow<'a, str>,
magnetic_field: Vector3,
magnetic_field_covariance: [f64; 9],
}
impl<'a> Default for MagneticFieldBuilder<'a> {
fn default() -> Self {
Self {
stamp: Time { sec: 0, nanosec: 0 },
frame_id: std::borrow::Cow::Borrowed(""),
magnetic_field: Vector3 {
x: 0.0,
y: 0.0,
z: 0.0,
},
magnetic_field_covariance: [0.0; 9],
}
}
}
impl<'a> MagneticFieldBuilder<'a> {
pub fn new() -> Self {
Self::default()
}
pub fn stamp(&mut self, t: Time) -> &mut Self {
self.stamp = t;
self
}
pub fn frame_id(&mut self, s: impl Into<std::borrow::Cow<'a, str>>) -> &mut Self {
self.frame_id = s.into();
self
}
pub fn magnetic_field(&mut self, v: Vector3) -> &mut Self {
self.magnetic_field = v;
self
}
pub fn magnetic_field_covariance(&mut self, c: [f64; 9]) -> &mut Self {
self.magnetic_field_covariance = c;
self
}
fn size(&self) -> usize {
let mut s = CdrSizer::new();
Time::size_cdr(&mut s);
s.size_string(&self.frame_id);
s.align(8);
Vector3::size_cdr(&mut s);
size_f64_array9(&mut s);
s.size()
}
fn write_into(&self, buf: &mut [u8]) -> Result<(), CdrError> {
let mut w = CdrWriter::new(buf)?;
self.stamp.write_cdr(&mut w);
w.write_string(&self.frame_id);
self.magnetic_field.write_cdr(&mut w);
write_f64_array9(&mut w, &self.magnetic_field_covariance);
w.finish()
}
pub fn build(&self) -> Result<MagneticField<Vec<u8>>, CdrError> {
let mut buf = vec![0u8; self.size()];
self.write_into(&mut buf)?;
MagneticField::from_cdr(buf)
}
pub fn encode_into_vec(&self, buf: &mut Vec<u8>) -> Result<(), CdrError> {
buf.resize(self.size(), 0);
self.write_into(buf)
}
pub fn encode_into_slice(&self, buf: &mut [u8]) -> Result<usize, CdrError> {
let need = self.size();
if buf.len() < need {
return Err(CdrError::BufferTooShort {
need,
have: buf.len(),
});
}
self.write_into(&mut buf[..need])?;
Ok(need)
}
}
impl<B: AsRef<[u8]> + AsMut<[u8]>> MagneticField<B> {
pub fn set_stamp(&mut self, t: Time) -> Result<(), CdrError> {
let b = self.buf.as_mut();
wr_i32(b, CDR_HEADER_SIZE, t.sec)?;
wr_u32(b, CDR_HEADER_SIZE + 4, t.nanosec)
}
pub fn set_magnetic_field(&mut self, v: Vector3) -> Result<(), CdrError> {
let p = self.offsets[0];
let b = self.buf.as_mut();
wr_f64(b, p, v.x)?;
wr_f64(b, p + 8, v.y)?;
wr_f64(b, p + 16, v.z)
}
pub fn set_magnetic_field_covariance(&mut self, c: [f64; 9]) -> Result<(), CdrError> {
let p = self.offsets[0] + 24;
let b = self.buf.as_mut();
for (i, v) in c.iter().enumerate() {
wr_f64(b, p + i * 8, *v)?;
}
Ok(())
}
}
pub struct FluidPressure<B> {
buf: B,
offsets: [usize; 1],
}
impl<B: AsRef<[u8]>> FluidPressure<B> {
pub fn from_cdr(buf: B) -> Result<Self, CdrError> {
let header = Header::<&[u8]>::from_cdr(buf.as_ref())?;
let pre = header.end_offset();
let mut c = CdrCursor::resume(buf.as_ref(), pre);
c.align(8);
let o0 = c.offset();
c.read_f64()?; c.read_f64()?; Ok(FluidPressure { offsets: [o0], buf })
}
pub fn header(&self) -> Header<&[u8]> {
Header::from_cdr(self.buf.as_ref()).expect("header bytes validated during from_cdr")
}
pub fn stamp(&self) -> Time {
rd_time(self.buf.as_ref(), CDR_HEADER_SIZE)
}
pub fn frame_id(&self) -> &str {
rd_string(self.buf.as_ref(), CDR_HEADER_SIZE + 8).0
}
pub fn fluid_pressure(&self) -> f64 {
rd_f64(self.buf.as_ref(), self.offsets[0])
}
pub fn variance(&self) -> f64 {
rd_f64(self.buf.as_ref(), self.offsets[0] + 8)
}
pub fn as_cdr(&self) -> &[u8] {
self.buf.as_ref()
}
pub fn to_cdr(&self) -> Vec<u8> {
self.buf.as_ref().to_vec()
}
}
impl FluidPressure<Vec<u8>> {
#[deprecated(
since = "3.2.0",
note = "use FluidPressure::builder() for allocation-free buffer reuse; FluidPressure::new will be removed in 4.0"
)]
pub fn new(
stamp: Time,
frame_id: &str,
fluid_pressure: f64,
variance: f64,
) -> Result<Self, CdrError> {
let mut sizer = CdrSizer::new();
Time::size_cdr(&mut sizer);
sizer.size_string(frame_id);
sizer.align(8);
let o0 = sizer.offset();
sizer.size_f64();
sizer.size_f64();
let mut buf = vec![0u8; sizer.size()];
let mut w = CdrWriter::new(&mut buf)?;
stamp.write_cdr(&mut w);
w.write_string(frame_id);
w.write_f64(fluid_pressure);
w.write_f64(variance);
w.finish()?;
Ok(FluidPressure { offsets: [o0], buf })
}
pub fn into_cdr(self) -> Vec<u8> {
self.buf
}
pub fn builder<'a>() -> FluidPressureBuilder<'a> {
FluidPressureBuilder::new()
}
}
pub struct FluidPressureBuilder<'a> {
stamp: Time,
frame_id: std::borrow::Cow<'a, str>,
fluid_pressure: f64,
variance: f64,
}
impl<'a> Default for FluidPressureBuilder<'a> {
fn default() -> Self {
Self {
stamp: Time { sec: 0, nanosec: 0 },
frame_id: std::borrow::Cow::Borrowed(""),
fluid_pressure: 0.0,
variance: 0.0,
}
}
}
impl<'a> FluidPressureBuilder<'a> {
pub fn new() -> Self {
Self::default()
}
pub fn stamp(&mut self, t: Time) -> &mut Self {
self.stamp = t;
self
}
pub fn frame_id(&mut self, s: impl Into<std::borrow::Cow<'a, str>>) -> &mut Self {
self.frame_id = s.into();
self
}
pub fn fluid_pressure(&mut self, v: f64) -> &mut Self {
self.fluid_pressure = v;
self
}
pub fn variance(&mut self, v: f64) -> &mut Self {
self.variance = v;
self
}
fn size(&self) -> usize {
let mut s = CdrSizer::new();
Time::size_cdr(&mut s);
s.size_string(&self.frame_id);
s.align(8);
s.size_f64();
s.size_f64();
s.size()
}
fn write_into(&self, buf: &mut [u8]) -> Result<(), CdrError> {
let mut w = CdrWriter::new(buf)?;
self.stamp.write_cdr(&mut w);
w.write_string(&self.frame_id);
w.write_f64(self.fluid_pressure);
w.write_f64(self.variance);
w.finish()
}
pub fn build(&self) -> Result<FluidPressure<Vec<u8>>, CdrError> {
let mut buf = vec![0u8; self.size()];
self.write_into(&mut buf)?;
FluidPressure::from_cdr(buf)
}
pub fn encode_into_vec(&self, buf: &mut Vec<u8>) -> Result<(), CdrError> {
buf.resize(self.size(), 0);
self.write_into(buf)
}
pub fn encode_into_slice(&self, buf: &mut [u8]) -> Result<usize, CdrError> {
let need = self.size();
if buf.len() < need {
return Err(CdrError::BufferTooShort {
need,
have: buf.len(),
});
}
self.write_into(&mut buf[..need])?;
Ok(need)
}
}
impl<B: AsRef<[u8]> + AsMut<[u8]>> FluidPressure<B> {
pub fn set_stamp(&mut self, t: Time) -> Result<(), CdrError> {
let b = self.buf.as_mut();
wr_i32(b, CDR_HEADER_SIZE, t.sec)?;
wr_u32(b, CDR_HEADER_SIZE + 4, t.nanosec)
}
pub fn set_fluid_pressure(&mut self, v: f64) -> Result<(), CdrError> {
wr_f64(self.buf.as_mut(), self.offsets[0], v)
}
pub fn set_variance(&mut self, v: f64) -> Result<(), CdrError> {
wr_f64(self.buf.as_mut(), self.offsets[0] + 8, v)
}
}
pub struct Temperature<B> {
buf: B,
offsets: [usize; 1],
}
impl<B: AsRef<[u8]>> Temperature<B> {
pub fn from_cdr(buf: B) -> Result<Self, CdrError> {
let header = Header::<&[u8]>::from_cdr(buf.as_ref())?;
let pre = header.end_offset();
let mut c = CdrCursor::resume(buf.as_ref(), pre);
c.align(8);
let o0 = c.offset();
c.read_f64()?; c.read_f64()?; Ok(Temperature { offsets: [o0], buf })
}
pub fn header(&self) -> Header<&[u8]> {
Header::from_cdr(self.buf.as_ref()).expect("header bytes validated during from_cdr")
}
pub fn stamp(&self) -> Time {
rd_time(self.buf.as_ref(), CDR_HEADER_SIZE)
}
pub fn frame_id(&self) -> &str {
rd_string(self.buf.as_ref(), CDR_HEADER_SIZE + 8).0
}
pub fn temperature(&self) -> f64 {
rd_f64(self.buf.as_ref(), self.offsets[0])
}
pub fn variance(&self) -> f64 {
rd_f64(self.buf.as_ref(), self.offsets[0] + 8)
}
pub fn as_cdr(&self) -> &[u8] {
self.buf.as_ref()
}
pub fn to_cdr(&self) -> Vec<u8> {
self.buf.as_ref().to_vec()
}
}
impl Temperature<Vec<u8>> {
#[deprecated(
since = "3.2.0",
note = "use Temperature::builder() for allocation-free buffer reuse; Temperature::new will be removed in 4.0"
)]
pub fn new(
stamp: Time,
frame_id: &str,
temperature: f64,
variance: f64,
) -> Result<Self, CdrError> {
let mut sizer = CdrSizer::new();
Time::size_cdr(&mut sizer);
sizer.size_string(frame_id);
sizer.align(8);
let o0 = sizer.offset();
sizer.size_f64();
sizer.size_f64();
let mut buf = vec![0u8; sizer.size()];
let mut w = CdrWriter::new(&mut buf)?;
stamp.write_cdr(&mut w);
w.write_string(frame_id);
w.write_f64(temperature);
w.write_f64(variance);
w.finish()?;
Ok(Temperature { offsets: [o0], buf })
}
pub fn into_cdr(self) -> Vec<u8> {
self.buf
}
pub fn builder<'a>() -> TemperatureBuilder<'a> {
TemperatureBuilder::new()
}
}
pub struct TemperatureBuilder<'a> {
stamp: Time,
frame_id: std::borrow::Cow<'a, str>,
temperature: f64,
variance: f64,
}
impl<'a> Default for TemperatureBuilder<'a> {
fn default() -> Self {
Self {
stamp: Time { sec: 0, nanosec: 0 },
frame_id: std::borrow::Cow::Borrowed(""),
temperature: 0.0,
variance: 0.0,
}
}
}
impl<'a> TemperatureBuilder<'a> {
pub fn new() -> Self {
Self::default()
}
pub fn stamp(&mut self, t: Time) -> &mut Self {
self.stamp = t;
self
}
pub fn frame_id(&mut self, s: impl Into<std::borrow::Cow<'a, str>>) -> &mut Self {
self.frame_id = s.into();
self
}
pub fn temperature(&mut self, v: f64) -> &mut Self {
self.temperature = v;
self
}
pub fn variance(&mut self, v: f64) -> &mut Self {
self.variance = v;
self
}
fn size(&self) -> usize {
let mut s = CdrSizer::new();
Time::size_cdr(&mut s);
s.size_string(&self.frame_id);
s.align(8);
s.size_f64();
s.size_f64();
s.size()
}
fn write_into(&self, buf: &mut [u8]) -> Result<(), CdrError> {
let mut w = CdrWriter::new(buf)?;
self.stamp.write_cdr(&mut w);
w.write_string(&self.frame_id);
w.write_f64(self.temperature);
w.write_f64(self.variance);
w.finish()
}
pub fn build(&self) -> Result<Temperature<Vec<u8>>, CdrError> {
let mut buf = vec![0u8; self.size()];
self.write_into(&mut buf)?;
Temperature::from_cdr(buf)
}
pub fn encode_into_vec(&self, buf: &mut Vec<u8>) -> Result<(), CdrError> {
buf.resize(self.size(), 0);
self.write_into(buf)
}
pub fn encode_into_slice(&self, buf: &mut [u8]) -> Result<usize, CdrError> {
let need = self.size();
if buf.len() < need {
return Err(CdrError::BufferTooShort {
need,
have: buf.len(),
});
}
self.write_into(&mut buf[..need])?;
Ok(need)
}
}
impl<B: AsRef<[u8]> + AsMut<[u8]>> Temperature<B> {
pub fn set_stamp(&mut self, t: Time) -> Result<(), CdrError> {
let b = self.buf.as_mut();
wr_i32(b, CDR_HEADER_SIZE, t.sec)?;
wr_u32(b, CDR_HEADER_SIZE + 4, t.nanosec)
}
pub fn set_temperature(&mut self, v: f64) -> Result<(), CdrError> {
wr_f64(self.buf.as_mut(), self.offsets[0], v)
}
pub fn set_variance(&mut self, v: f64) -> Result<(), CdrError> {
wr_f64(self.buf.as_mut(), self.offsets[0] + 8, v)
}
}
pub mod power_supply_status {
pub const UNKNOWN: u8 = 0;
pub const CHARGING: u8 = 1;
pub const DISCHARGING: u8 = 2;
pub const NOT_CHARGING: u8 = 3;
pub const FULL: u8 = 4;
}
pub mod power_supply_health {
pub const UNKNOWN: u8 = 0;
pub const GOOD: u8 = 1;
pub const OVERHEAT: u8 = 2;
pub const DEAD: u8 = 3;
pub const OVERVOLTAGE: u8 = 4;
pub const UNSPEC_FAILURE: u8 = 5;
pub const COLD: u8 = 6;
pub const WATCHDOG_TIMER_EXPIRE: u8 = 7;
pub const SAFETY_TIMER_EXPIRE: u8 = 8;
}
pub mod power_supply_technology {
pub const UNKNOWN: u8 = 0;
pub const NIMH: u8 = 1;
pub const LION: u8 = 2;
pub const LIPO: u8 = 3;
pub const LIFE: u8 = 4;
pub const NICD: u8 = 5;
pub const LIMN: u8 = 6;
}
pub struct BatteryState<B> {
buf: B,
offsets: [usize; 5],
}
impl<B: AsRef<[u8]>> BatteryState<B> {
pub fn from_cdr(buf: B) -> Result<Self, CdrError> {
let header = Header::<&[u8]>::from_cdr(buf.as_ref())?;
let pre = header.end_offset();
let mut c = CdrCursor::resume(buf.as_ref(), pre);
c.align(4);
let o0 = c.offset();
for _ in 0..7 {
c.read_f32()?;
}
c.read_u8()?; c.read_u8()?; c.read_u8()?; c.read_bool()?; let o1 = c.offset();
let raw = c.read_u32()?;
let cv_len = c.check_seq_count(raw, 4)?;
for _ in 0..cv_len {
c.read_f32()?;
}
let o2 = c.offset();
let raw = c.read_u32()?;
let ct_len = c.check_seq_count(raw, 4)?;
for _ in 0..ct_len {
c.read_f32()?;
}
let o3 = c.offset();
c.read_string()?; let o4 = c.offset();
c.read_string()?; Ok(BatteryState {
offsets: [o0, o1, o2, o3, o4],
buf,
})
}
pub fn header(&self) -> Header<&[u8]> {
Header::from_cdr(self.buf.as_ref()).expect("header bytes validated during from_cdr")
}
pub fn stamp(&self) -> Time {
rd_time(self.buf.as_ref(), CDR_HEADER_SIZE)
}
pub fn frame_id(&self) -> &str {
rd_string(self.buf.as_ref(), CDR_HEADER_SIZE + 8).0
}
pub fn voltage(&self) -> f32 {
rd_f32(self.buf.as_ref(), self.offsets[0])
}
pub fn temperature(&self) -> f32 {
rd_f32(self.buf.as_ref(), self.offsets[0] + 4)
}
pub fn current(&self) -> f32 {
rd_f32(self.buf.as_ref(), self.offsets[0] + 8)
}
pub fn charge(&self) -> f32 {
rd_f32(self.buf.as_ref(), self.offsets[0] + 12)
}
pub fn capacity(&self) -> f32 {
rd_f32(self.buf.as_ref(), self.offsets[0] + 16)
}
pub fn design_capacity(&self) -> f32 {
rd_f32(self.buf.as_ref(), self.offsets[0] + 20)
}
pub fn percentage(&self) -> f32 {
rd_f32(self.buf.as_ref(), self.offsets[0] + 24)
}
pub fn power_supply_status(&self) -> u8 {
rd_u8(self.buf.as_ref(), self.offsets[0] + 28)
}
pub fn power_supply_health(&self) -> u8 {
rd_u8(self.buf.as_ref(), self.offsets[0] + 29)
}
pub fn power_supply_technology(&self) -> u8 {
rd_u8(self.buf.as_ref(), self.offsets[0] + 30)
}
pub fn present(&self) -> bool {
rd_bool(self.buf.as_ref(), self.offsets[0] + 31)
}
pub fn cell_voltage_len(&self) -> u32 {
rd_u32(self.buf.as_ref(), self.offsets[1])
}
pub fn cell_voltage_seq_offset(&self) -> usize {
self.offsets[1]
}
pub fn cell_voltage(&self) -> Vec<f32> {
let mut c = CdrCursor::resume(self.buf.as_ref(), self.offsets[1]);
let n = c
.read_u32()
.expect("cell_voltage length validated during from_cdr") as usize;
let mut out = Vec::with_capacity(n);
for _ in 0..n {
out.push(
c.read_f32()
.expect("cell_voltage element validated during from_cdr"),
);
}
out
}
pub fn cell_temperature_len(&self) -> u32 {
rd_u32(self.buf.as_ref(), self.offsets[2])
}
pub fn cell_temperature_seq_offset(&self) -> usize {
self.offsets[2]
}
pub fn cell_temperature(&self) -> Vec<f32> {
let mut c = CdrCursor::resume(self.buf.as_ref(), self.offsets[2]);
let n = c
.read_u32()
.expect("cell_temperature length validated during from_cdr") as usize;
let mut out = Vec::with_capacity(n);
for _ in 0..n {
out.push(
c.read_f32()
.expect("cell_temperature element validated during from_cdr"),
);
}
out
}
pub fn location(&self) -> &str {
rd_string(self.buf.as_ref(), self.offsets[3]).0
}
pub fn serial_number(&self) -> &str {
rd_string(self.buf.as_ref(), self.offsets[4]).0
}
pub fn as_cdr(&self) -> &[u8] {
self.buf.as_ref()
}
pub fn to_cdr(&self) -> Vec<u8> {
self.buf.as_ref().to_vec()
}
}
impl BatteryState<Vec<u8>> {
#[deprecated(
since = "3.2.0",
note = "use BatteryState::builder() for allocation-free buffer reuse; BatteryState::new will be removed in 4.0"
)]
#[allow(clippy::too_many_arguments)]
pub fn new(
stamp: Time,
frame_id: &str,
voltage: f32,
temperature: f32,
current: f32,
charge: f32,
capacity: f32,
design_capacity: f32,
percentage: f32,
power_supply_status: u8,
power_supply_health: u8,
power_supply_technology: u8,
present: bool,
cell_voltage: &[f32],
cell_temperature: &[f32],
location: &str,
serial_number: &str,
) -> Result<Self, CdrError> {
let mut sizer = CdrSizer::new();
Time::size_cdr(&mut sizer);
sizer.size_string(frame_id);
sizer.align(4);
let o0 = sizer.offset();
for _ in 0..7 {
sizer.size_f32();
}
sizer.size_u8();
sizer.size_u8();
sizer.size_u8();
sizer.size_bool();
let o1 = sizer.offset();
sizer.size_u32();
for _ in cell_voltage {
sizer.size_f32();
}
let o2 = sizer.offset();
sizer.size_u32();
for _ in cell_temperature {
sizer.size_f32();
}
let o3 = sizer.offset();
sizer.size_string(location);
let o4 = sizer.offset();
sizer.size_string(serial_number);
let mut buf = vec![0u8; sizer.size()];
let mut w = CdrWriter::new(&mut buf)?;
stamp.write_cdr(&mut w);
w.write_string(frame_id);
w.write_f32(voltage);
w.write_f32(temperature);
w.write_f32(current);
w.write_f32(charge);
w.write_f32(capacity);
w.write_f32(design_capacity);
w.write_f32(percentage);
w.write_u8(power_supply_status);
w.write_u8(power_supply_health);
w.write_u8(power_supply_technology);
w.write_bool(present);
w.write_u32(cell_voltage.len() as u32);
for v in cell_voltage {
w.write_f32(*v);
}
w.write_u32(cell_temperature.len() as u32);
for v in cell_temperature {
w.write_f32(*v);
}
w.write_string(location);
w.write_string(serial_number);
w.finish()?;
Ok(BatteryState {
offsets: [o0, o1, o2, o3, o4],
buf,
})
}
pub fn into_cdr(self) -> Vec<u8> {
self.buf
}
pub fn builder<'a>() -> BatteryStateBuilder<'a> {
BatteryStateBuilder::new()
}
}
pub struct BatteryStateBuilder<'a> {
stamp: Time,
frame_id: std::borrow::Cow<'a, str>,
voltage: f32,
temperature: f32,
current: f32,
charge: f32,
capacity: f32,
design_capacity: f32,
percentage: f32,
power_supply_status: u8,
power_supply_health: u8,
power_supply_technology: u8,
present: bool,
cell_voltage: &'a [f32],
cell_temperature: &'a [f32],
location: std::borrow::Cow<'a, str>,
serial_number: std::borrow::Cow<'a, str>,
}
impl<'a> Default for BatteryStateBuilder<'a> {
fn default() -> Self {
Self {
stamp: Time { sec: 0, nanosec: 0 },
frame_id: std::borrow::Cow::Borrowed(""),
voltage: 0.0,
temperature: 0.0,
current: 0.0,
charge: 0.0,
capacity: 0.0,
design_capacity: 0.0,
percentage: 0.0,
power_supply_status: 0,
power_supply_health: 0,
power_supply_technology: 0,
present: false,
cell_voltage: &[],
cell_temperature: &[],
location: std::borrow::Cow::Borrowed(""),
serial_number: std::borrow::Cow::Borrowed(""),
}
}
}
impl<'a> BatteryStateBuilder<'a> {
pub fn new() -> Self {
Self::default()
}
pub fn stamp(&mut self, t: Time) -> &mut Self {
self.stamp = t;
self
}
pub fn frame_id(&mut self, s: impl Into<std::borrow::Cow<'a, str>>) -> &mut Self {
self.frame_id = s.into();
self
}
pub fn voltage(&mut self, v: f32) -> &mut Self {
self.voltage = v;
self
}
pub fn temperature(&mut self, v: f32) -> &mut Self {
self.temperature = v;
self
}
pub fn current(&mut self, v: f32) -> &mut Self {
self.current = v;
self
}
pub fn charge(&mut self, v: f32) -> &mut Self {
self.charge = v;
self
}
pub fn capacity(&mut self, v: f32) -> &mut Self {
self.capacity = v;
self
}
pub fn design_capacity(&mut self, v: f32) -> &mut Self {
self.design_capacity = v;
self
}
pub fn percentage(&mut self, v: f32) -> &mut Self {
self.percentage = v;
self
}
pub fn power_supply_status(&mut self, v: u8) -> &mut Self {
self.power_supply_status = v;
self
}
pub fn power_supply_health(&mut self, v: u8) -> &mut Self {
self.power_supply_health = v;
self
}
pub fn power_supply_technology(&mut self, v: u8) -> &mut Self {
self.power_supply_technology = v;
self
}
pub fn present(&mut self, v: bool) -> &mut Self {
self.present = v;
self
}
pub fn cell_voltage(&mut self, v: &'a [f32]) -> &mut Self {
self.cell_voltage = v;
self
}
pub fn cell_temperature(&mut self, v: &'a [f32]) -> &mut Self {
self.cell_temperature = v;
self
}
pub fn location(&mut self, s: impl Into<std::borrow::Cow<'a, str>>) -> &mut Self {
self.location = s.into();
self
}
pub fn serial_number(&mut self, s: impl Into<std::borrow::Cow<'a, str>>) -> &mut Self {
self.serial_number = s.into();
self
}
fn size(&self) -> usize {
let mut s = CdrSizer::new();
Time::size_cdr(&mut s);
s.size_string(&self.frame_id);
s.align(4);
for _ in 0..7 {
s.size_f32();
}
s.size_u8();
s.size_u8();
s.size_u8();
s.size_bool();
s.size_u32();
for _ in self.cell_voltage {
s.size_f32();
}
s.size_u32();
for _ in self.cell_temperature {
s.size_f32();
}
s.size_string(&self.location);
s.size_string(&self.serial_number);
s.size()
}
fn write_into(&self, buf: &mut [u8]) -> Result<(), CdrError> {
let mut w = CdrWriter::new(buf)?;
self.stamp.write_cdr(&mut w);
w.write_string(&self.frame_id);
w.write_f32(self.voltage);
w.write_f32(self.temperature);
w.write_f32(self.current);
w.write_f32(self.charge);
w.write_f32(self.capacity);
w.write_f32(self.design_capacity);
w.write_f32(self.percentage);
w.write_u8(self.power_supply_status);
w.write_u8(self.power_supply_health);
w.write_u8(self.power_supply_technology);
w.write_bool(self.present);
w.write_u32(self.cell_voltage.len() as u32);
for v in self.cell_voltage {
w.write_f32(*v);
}
w.write_u32(self.cell_temperature.len() as u32);
for v in self.cell_temperature {
w.write_f32(*v);
}
w.write_string(&self.location);
w.write_string(&self.serial_number);
w.finish()
}
pub fn build(&self) -> Result<BatteryState<Vec<u8>>, CdrError> {
let mut buf = vec![0u8; self.size()];
self.write_into(&mut buf)?;
BatteryState::from_cdr(buf)
}
pub fn encode_into_vec(&self, buf: &mut Vec<u8>) -> Result<(), CdrError> {
buf.resize(self.size(), 0);
self.write_into(buf)
}
pub fn encode_into_slice(&self, buf: &mut [u8]) -> Result<usize, CdrError> {
let need = self.size();
if buf.len() < need {
return Err(CdrError::BufferTooShort {
need,
have: buf.len(),
});
}
self.write_into(&mut buf[..need])?;
Ok(need)
}
}
impl<B: AsRef<[u8]> + AsMut<[u8]>> BatteryState<B> {
pub fn set_stamp(&mut self, t: Time) -> Result<(), CdrError> {
let b = self.buf.as_mut();
wr_i32(b, CDR_HEADER_SIZE, t.sec)?;
wr_u32(b, CDR_HEADER_SIZE + 4, t.nanosec)
}
pub fn set_voltage(&mut self, v: f32) -> Result<(), CdrError> {
wr_f32(self.buf.as_mut(), self.offsets[0], v)
}
pub fn set_temperature(&mut self, v: f32) -> Result<(), CdrError> {
wr_f32(self.buf.as_mut(), self.offsets[0] + 4, v)
}
pub fn set_current(&mut self, v: f32) -> Result<(), CdrError> {
wr_f32(self.buf.as_mut(), self.offsets[0] + 8, v)
}
pub fn set_charge(&mut self, v: f32) -> Result<(), CdrError> {
wr_f32(self.buf.as_mut(), self.offsets[0] + 12, v)
}
pub fn set_capacity(&mut self, v: f32) -> Result<(), CdrError> {
wr_f32(self.buf.as_mut(), self.offsets[0] + 16, v)
}
pub fn set_design_capacity(&mut self, v: f32) -> Result<(), CdrError> {
wr_f32(self.buf.as_mut(), self.offsets[0] + 20, v)
}
pub fn set_percentage(&mut self, v: f32) -> Result<(), CdrError> {
wr_f32(self.buf.as_mut(), self.offsets[0] + 24, v)
}
pub fn set_power_supply_status(&mut self, v: u8) -> Result<(), CdrError> {
wr_u8(self.buf.as_mut(), self.offsets[0] + 28, v)
}
pub fn set_power_supply_health(&mut self, v: u8) -> Result<(), CdrError> {
wr_u8(self.buf.as_mut(), self.offsets[0] + 29, v)
}
pub fn set_power_supply_technology(&mut self, v: u8) -> Result<(), CdrError> {
wr_u8(self.buf.as_mut(), self.offsets[0] + 30, v)
}
pub fn set_present(&mut self, v: bool) -> Result<(), CdrError> {
wr_bool(self.buf.as_mut(), self.offsets[0] + 31, v)
}
}
pub fn is_type_supported(type_name: &str) -> bool {
matches!(
type_name,
"BatteryState"
| "CameraInfo"
| "CompressedImage"
| "FluidPressure"
| "Image"
| "Imu"
| "MagneticField"
| "NavSatFix"
| "NavSatStatus"
| "PointCloud2"
| "PointField"
| "RegionOfInterest"
| "Temperature"
)
}
pub fn list_types() -> &'static [&'static str] {
&[
"sensor_msgs/msg/BatteryState",
"sensor_msgs/msg/CameraInfo",
"sensor_msgs/msg/CompressedImage",
"sensor_msgs/msg/FluidPressure",
"sensor_msgs/msg/Image",
"sensor_msgs/msg/Imu",
"sensor_msgs/msg/MagneticField",
"sensor_msgs/msg/NavSatFix",
"sensor_msgs/msg/NavSatStatus",
"sensor_msgs/msg/PointCloud2",
"sensor_msgs/msg/PointField",
"sensor_msgs/msg/RegionOfInterest",
"sensor_msgs/msg/Temperature",
]
}
use crate::schema_registry::SchemaType;
impl SchemaType for NavSatStatus {
const SCHEMA_NAME: &'static str = "sensor_msgs/msg/NavSatStatus";
}
impl SchemaType for RegionOfInterest {
const SCHEMA_NAME: &'static str = "sensor_msgs/msg/RegionOfInterest";
}
#[cfg(test)]
#[allow(deprecated)] mod tests {
use super::*;
use crate::builtin_interfaces::Time;
use crate::cdr::{decode_fixed, encode_fixed};
use crate::geometry_msgs::{Quaternion, Vector3};
#[test]
fn compressed_image_roundtrip() {
let img = CompressedImage::new(
Time::new(100, 500_000_000),
"camera",
"jpeg",
&[0xFF, 0xD8, 0xFF],
)
.unwrap();
assert_eq!(img.stamp(), Time::new(100, 500_000_000));
assert_eq!(img.frame_id(), "camera");
assert_eq!(img.format(), "jpeg");
assert_eq!(img.data(), &[0xFF, 0xD8, 0xFF]);
let bytes = img.to_cdr();
let decoded = CompressedImage::from_cdr(bytes).unwrap();
assert_eq!(decoded.format(), "jpeg");
assert_eq!(decoded.data(), &[0xFF, 0xD8, 0xFF]);
}
#[test]
fn image_roundtrip() {
let data = vec![128u8; 1920 * 480];
let img = Image::new(
Time::new(100, 500_000_000),
"camera_optical",
480,
640,
"rgb8",
0,
1920,
&data,
)
.unwrap();
assert_eq!(img.height(), 480);
assert_eq!(img.width(), 640);
assert_eq!(img.encoding(), "rgb8");
assert_eq!(img.is_bigendian(), 0);
assert_eq!(img.step(), 1920);
assert_eq!(img.data().len(), 1920 * 480);
let bytes = img.to_cdr();
let decoded = Image::from_cdr(bytes).unwrap();
assert_eq!(decoded.height(), 480);
assert_eq!(decoded.width(), 640);
}
#[test]
fn imu_roundtrip() {
let imu = Imu::new(
Time::new(100, 0),
"imu_link",
Quaternion {
x: 0.0,
y: 0.0,
z: 0.0,
w: 1.0,
},
[0.0; 9],
Vector3 {
x: 0.1,
y: 0.2,
z: 9.8,
},
[0.0; 9],
Vector3 {
x: 0.0,
y: 0.0,
z: 0.0,
},
[0.0; 9],
)
.unwrap();
assert_eq!(imu.stamp(), Time::new(100, 0));
let bytes = imu.to_cdr();
let decoded = Imu::from_cdr(bytes).unwrap();
assert_eq!(decoded.orientation().w, 1.0);
assert!((decoded.angular_velocity().z - 9.8).abs() < 1e-10);
}
#[test]
fn nav_sat_fix_roundtrip() {
let fix = NavSatFix::new(
Time::new(100, 0),
"gps",
NavSatStatus {
status: 0,
service: 1,
},
45.5017,
-73.5673,
100.0,
[1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0],
2,
)
.unwrap();
let bytes = fix.to_cdr();
let decoded = NavSatFix::from_cdr(bytes).unwrap();
assert!((decoded.latitude() - 45.5017).abs() < 1e-10);
assert_eq!(decoded.position_covariance_type(), 2);
}
#[test]
fn nav_sat_status_roundtrip() {
let status = NavSatStatus {
status: 0,
service: 1,
};
let bytes = encode_fixed(&status).unwrap();
let decoded: NavSatStatus = decode_fixed(&bytes).unwrap();
assert_eq!(status, decoded);
}
#[test]
fn region_of_interest_roundtrip() {
let roi = RegionOfInterest {
x_offset: 10,
y_offset: 20,
height: 100,
width: 200,
do_rectify: true,
};
let bytes = encode_fixed(&roi).unwrap();
let decoded: RegionOfInterest = decode_fixed(&bytes).unwrap();
assert_eq!(roi, decoded);
}
#[test]
fn point_cloud2_roundtrip() {
let fields = [
PointFieldView {
name: "x",
offset: 0,
datatype: 7,
count: 1,
},
PointFieldView {
name: "y",
offset: 4,
datatype: 7,
count: 1,
},
PointFieldView {
name: "z",
offset: 8,
datatype: 7,
count: 1,
},
];
let data = vec![0u8; 12288];
let cloud = PointCloud2::new(
Time::new(100, 0),
"lidar",
1,
1024,
&fields,
false,
12,
12288,
&data,
true,
)
.unwrap();
let bytes = cloud.to_cdr();
let decoded = PointCloud2::from_cdr(bytes).unwrap();
assert_eq!(decoded.height(), 1);
assert_eq!(decoded.width(), 1024);
assert_eq!(decoded.fields_len(), 3);
assert!(decoded.is_dense());
}
#[test]
fn point_cloud2_fields_iter() {
let fields = [
PointFieldView {
name: "x",
offset: 0,
datatype: 7,
count: 1,
},
PointFieldView {
name: "y",
offset: 4,
datatype: 7,
count: 1,
},
PointFieldView {
name: "z",
offset: 8,
datatype: 7,
count: 1,
},
];
let data = vec![0u8; 36]; let cloud = PointCloud2::new(
Time::new(100, 0),
"lidar",
1,
3,
&fields,
false,
12,
36,
&data,
true,
)
.unwrap();
let cdr = cloud.to_cdr();
let decoded = PointCloud2::from_cdr(cdr).unwrap();
let iter_fields: Vec<_> = decoded.fields_iter().collect();
assert_eq!(iter_fields.len(), 3);
assert_eq!(iter_fields[0].name, "x");
assert_eq!(iter_fields[1].name, "y");
assert_eq!(iter_fields[2].name, "z");
assert_eq!(iter_fields[0].offset, 0);
assert_eq!(iter_fields[1].offset, 4);
assert_eq!(iter_fields[2].offset, 8);
assert_eq!(decoded.point_count(), 3);
}
#[test]
fn camera_info_roundtrip() {
let roi = RegionOfInterest {
x_offset: 0,
y_offset: 0,
height: 480,
width: 640,
do_rectify: false,
};
let cam = CameraInfo::new(
Time::new(100, 0),
"camera",
480,
640,
"plumb_bob",
&[0.1, -0.2, 0.0, 0.0, 0.0],
[500.0, 0.0, 320.0, 0.0, 500.0, 240.0, 0.0, 0.0, 1.0],
[1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0],
[
500.0, 0.0, 320.0, 0.0, 0.0, 500.0, 240.0, 0.0, 0.0, 0.0, 1.0, 0.0,
],
1,
1,
roi,
)
.unwrap();
let bytes = cam.to_cdr();
let decoded = CameraInfo::from_cdr(bytes).unwrap();
assert_eq!(decoded.height(), 480);
assert_eq!(decoded.width(), 640);
assert_eq!(decoded.distortion_model(), "plumb_bob");
assert_eq!(decoded.d_len(), 5);
assert_eq!(decoded.binning_x(), 1);
}
#[test]
fn navsatfix_accessors_robust_across_frame_id_alignments() {
let lat = 43.6532_f64;
let lon = -79.3832_f64;
let alt = 150.0_f64;
let cov = [0.1, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, 0.3_f64];
let cov_type = 2_u8;
let status = NavSatStatus {
status: 0,
service: 1,
};
for len in 0..=16_usize {
let frame_id: String = "x".repeat(len);
let fix = NavSatFix::new(
Time::new(1, 0),
&frame_id,
status,
lat,
lon,
alt,
cov,
cov_type,
)
.unwrap();
let bytes = fix.to_cdr();
let view = NavSatFix::from_cdr(&bytes[..]).unwrap();
assert_eq!(view.frame_id(), frame_id, "frame_id at len={len}");
let rx_status = view.status();
assert_eq!(rx_status.status, 0, "status.status at len={len}");
assert_eq!(rx_status.service, 1, "status.service at len={len}");
assert_eq!(view.latitude(), lat, "latitude at len={len}");
assert_eq!(view.longitude(), lon, "longitude at len={len}");
assert_eq!(view.altitude(), alt, "altitude at len={len}");
assert_eq!(
view.position_covariance(),
cov,
"position_covariance at len={len}"
);
assert_eq!(
view.position_covariance_type(),
cov_type,
"position_covariance_type at len={len}"
);
}
}
#[test]
fn navsatfix_gps_link_frame_id_regression() {
let status = NavSatStatus {
status: 0,
service: 1,
};
let fix = NavSatFix::new(
Time::new(0, 0),
"gps_link",
status,
43.6532,
-79.3832,
150.0,
[0.0; 9],
0,
)
.unwrap();
let bytes = fix.to_cdr();
let rx = NavSatFix::from_cdr(&bytes[..]).unwrap();
assert_eq!(rx.latitude(), 43.6532);
assert_eq!(rx.longitude(), -79.3832);
assert_eq!(rx.altitude(), 150.0);
}
#[test]
fn sensor_setter_byte_parity() {
let imu_a = Imu::builder()
.stamp(Time::new(100, 500))
.frame_id("imu_link")
.orientation(Quaternion {
x: 0.1,
y: 0.2,
z: 0.3,
w: 0.4,
})
.orientation_covariance([1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0])
.angular_velocity(Vector3 {
x: 0.11,
y: 0.22,
z: 0.33,
})
.angular_velocity_covariance([10.0; 9])
.linear_acceleration(Vector3 {
x: 0.44,
y: 0.55,
z: 0.66,
})
.linear_acceleration_covariance([20.0; 9])
.build()
.unwrap();
let mut imu_b = Imu::builder()
.stamp(Time::new(0, 0))
.frame_id("imu_link")
.build()
.unwrap();
imu_b.set_stamp(Time::new(100, 500)).unwrap();
imu_b
.set_orientation(Quaternion {
x: 0.1,
y: 0.2,
z: 0.3,
w: 0.4,
})
.unwrap();
imu_b
.set_orientation_covariance([1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0])
.unwrap();
imu_b
.set_angular_velocity(Vector3 {
x: 0.11,
y: 0.22,
z: 0.33,
})
.unwrap();
imu_b.set_angular_velocity_covariance([10.0; 9]).unwrap();
imu_b
.set_linear_acceleration(Vector3 {
x: 0.44,
y: 0.55,
z: 0.66,
})
.unwrap();
imu_b.set_linear_acceleration_covariance([20.0; 9]).unwrap();
assert_eq!(imu_a.as_cdr(), imu_b.as_cdr(), "Imu byte mismatch");
let nsf_a = NavSatFix::builder()
.stamp(Time::new(5, 6))
.frame_id("gps")
.status(NavSatStatus {
status: 1,
service: 3,
})
.latitude(45.5)
.longitude(-73.6)
.altitude(100.0)
.position_covariance([0.1, 0.2, 0.3, 0.4, 0.5, 0.6, 0.7, 0.8, 0.9])
.position_covariance_type(2)
.build()
.unwrap();
let mut nsf_b = NavSatFix::builder()
.stamp(Time::new(0, 0))
.frame_id("gps")
.build()
.unwrap();
nsf_b.set_stamp(Time::new(5, 6)).unwrap();
nsf_b
.set_status(NavSatStatus {
status: 1,
service: 3,
})
.unwrap();
nsf_b.set_latitude(45.5).unwrap();
nsf_b.set_longitude(-73.6).unwrap();
nsf_b.set_altitude(100.0).unwrap();
nsf_b
.set_position_covariance([0.1, 0.2, 0.3, 0.4, 0.5, 0.6, 0.7, 0.8, 0.9])
.unwrap();
nsf_b.set_position_covariance_type(2).unwrap();
assert_eq!(nsf_a.as_cdr(), nsf_b.as_cdr(), "NavSatFix byte mismatch");
let pf_a = PointField::builder()
.name("x")
.offset(16)
.datatype(7)
.count(3)
.build()
.unwrap();
let mut pf_b = PointField::builder().name("x").build().unwrap();
pf_b.set_offset(16).unwrap();
pf_b.set_datatype(7).unwrap();
pf_b.set_count(3).unwrap();
assert_eq!(pf_a.as_cdr(), pf_b.as_cdr(), "PointField byte mismatch");
let pc_a = PointCloud2::builder()
.stamp(Time::new(1, 2))
.frame_id("base_link")
.height(480)
.width(640)
.is_bigendian(true)
.point_step(16)
.row_step(16 * 640)
.is_dense(true)
.build()
.unwrap();
let mut pc_b = PointCloud2::builder()
.stamp(Time::new(0, 0))
.frame_id("base_link")
.build()
.unwrap();
pc_b.set_stamp(Time::new(1, 2)).unwrap();
pc_b.set_height(480).unwrap();
pc_b.set_width(640).unwrap();
pc_b.set_is_bigendian(true).unwrap();
pc_b.set_point_step(16).unwrap();
pc_b.set_row_step(16 * 640).unwrap();
pc_b.set_is_dense(true).unwrap();
assert_eq!(pc_a.as_cdr(), pc_b.as_cdr(), "PointCloud2 byte mismatch");
let k = [1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0];
let r = [10.0, 11.0, 12.0, 13.0, 14.0, 15.0, 16.0, 17.0, 18.0];
let p = [
20.0, 21.0, 22.0, 23.0, 24.0, 25.0, 26.0, 27.0, 28.0, 29.0, 30.0, 31.0,
];
let roi = RegionOfInterest {
x_offset: 1,
y_offset: 2,
height: 3,
width: 4,
do_rectify: true,
};
let ci_a = CameraInfo::builder()
.stamp(Time::new(7, 8))
.frame_id("cam")
.height(480)
.width(640)
.distortion_model("plumb_bob")
.d(&[0.1, 0.2])
.k(k)
.r(r)
.p(p)
.binning_x(2)
.binning_y(3)
.roi(roi)
.build()
.unwrap();
let mut ci_b = CameraInfo::builder()
.stamp(Time::new(0, 0))
.frame_id("cam")
.distortion_model("plumb_bob")
.d(&[0.1, 0.2])
.build()
.unwrap();
ci_b.set_stamp(Time::new(7, 8)).unwrap();
ci_b.set_height(480).unwrap();
ci_b.set_width(640).unwrap();
ci_b.set_k(k).unwrap();
ci_b.set_r(r).unwrap();
ci_b.set_p(p).unwrap();
ci_b.set_binning_x(2).unwrap();
ci_b.set_binning_y(3).unwrap();
ci_b.set_roi(roi).unwrap();
assert_eq!(ci_a.as_cdr(), ci_b.as_cdr(), "CameraInfo byte mismatch");
let mf_a = MagneticField::builder()
.stamp(Time::new(9, 10))
.frame_id("imu")
.magnetic_field(Vector3 {
x: 1.0,
y: 2.0,
z: 3.0,
})
.magnetic_field_covariance([1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0])
.build()
.unwrap();
let mut mf_b = MagneticField::builder()
.stamp(Time::new(0, 0))
.frame_id("imu")
.build()
.unwrap();
mf_b.set_stamp(Time::new(9, 10)).unwrap();
mf_b.set_magnetic_field(Vector3 {
x: 1.0,
y: 2.0,
z: 3.0,
})
.unwrap();
mf_b.set_magnetic_field_covariance([1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0])
.unwrap();
assert_eq!(mf_a.as_cdr(), mf_b.as_cdr(), "MagneticField byte mismatch");
let fp_a = FluidPressure::builder()
.stamp(Time::new(11, 12))
.frame_id("barometer")
.fluid_pressure(101_325.0)
.variance(0.5)
.build()
.unwrap();
let mut fp_b = FluidPressure::builder()
.stamp(Time::new(0, 0))
.frame_id("barometer")
.build()
.unwrap();
fp_b.set_stamp(Time::new(11, 12)).unwrap();
fp_b.set_fluid_pressure(101_325.0).unwrap();
fp_b.set_variance(0.5).unwrap();
assert_eq!(fp_a.as_cdr(), fp_b.as_cdr(), "FluidPressure byte mismatch");
let t_a = Temperature::builder()
.stamp(Time::new(13, 14))
.frame_id("temp")
.temperature(25.5)
.variance(0.1)
.build()
.unwrap();
let mut t_b = Temperature::builder()
.stamp(Time::new(0, 0))
.frame_id("temp")
.build()
.unwrap();
t_b.set_stamp(Time::new(13, 14)).unwrap();
t_b.set_temperature(25.5).unwrap();
t_b.set_variance(0.1).unwrap();
assert_eq!(t_a.as_cdr(), t_b.as_cdr(), "Temperature byte mismatch");
let bs_a = BatteryState::builder()
.stamp(Time::new(15, 16))
.frame_id("batt")
.voltage(12.1)
.temperature(25.0)
.current(-1.5)
.charge(0.5)
.capacity(2.0)
.design_capacity(2.5)
.percentage(0.75)
.power_supply_status(1)
.power_supply_health(2)
.power_supply_technology(3)
.present(true)
.build()
.unwrap();
let mut bs_b = BatteryState::builder()
.stamp(Time::new(0, 0))
.frame_id("batt")
.build()
.unwrap();
bs_b.set_stamp(Time::new(15, 16)).unwrap();
bs_b.set_voltage(12.1).unwrap();
bs_b.set_temperature(25.0).unwrap();
bs_b.set_current(-1.5).unwrap();
bs_b.set_charge(0.5).unwrap();
bs_b.set_capacity(2.0).unwrap();
bs_b.set_design_capacity(2.5).unwrap();
bs_b.set_percentage(0.75).unwrap();
bs_b.set_power_supply_status(1).unwrap();
bs_b.set_power_supply_health(2).unwrap();
bs_b.set_power_supply_technology(3).unwrap();
bs_b.set_present(true).unwrap();
assert_eq!(bs_a.as_cdr(), bs_b.as_cdr(), "BatteryState byte mismatch");
}
}