Skip to content

Commit 4c85450

Browse files
grtlroxkitsune
andauthored
Extract extra fields from ROS2 PointCloud2 messages (#11193)
### What This extracts additional values that are associated with points in the `PointCloud2` ROS2 messages. The fields will be added to the `Points3d` archetype as partially tagged. ### Screenshot <img width="393" height="77" alt="image" src="https://github.com/user-attachments/assets/c04d46ee-4685-4f3f-8973-b6e59d2e226f" /> ### Test We can use `autoware_all_sensors.mcap` to test. --------- Co-authored-by: Gijs de Jong <14833076+oxkitsune@users.noreply.github.com>
1 parent 6aa7f8d commit 4c85450

File tree

3 files changed

+224
-16
lines changed

3 files changed

+224
-16
lines changed
Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,3 @@
11
version https://git-lfs.github.com/spec/v1
2-
oid sha256:3fe309bc865899cacf618eb9a2c38ba16aa457bce7032b44defb44ef3161b1ed
3-
size 441989
2+
oid sha256:a5007101f4ae92b50171c12aed1b51ceb482503aade827248c8d8c8fabb146f4
3+
size 442998

crates/utils/re_mcap/src/parsers/ros2msg/definitions/sensor_msgs.rs

Lines changed: 12 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -110,11 +110,9 @@ pub struct Imu {
110110
}
111111

112112
#[derive(Copy, Clone, Debug, Serialize, Deserialize)]
113-
#[serde(from = "u8", into = "u8")]
113+
#[serde(try_from = "u8", into = "u8")]
114114
#[repr(u8)]
115115
pub enum PointFieldDatatype {
116-
/// Does not exist in original spec.
117-
Unknown = 0,
118116
Int8 = 1,
119117
UInt8 = 2,
120118
Int16 = 3,
@@ -125,9 +123,15 @@ pub enum PointFieldDatatype {
125123
Float64 = 8,
126124
}
127125

128-
impl From<u8> for PointFieldDatatype {
129-
fn from(value: u8) -> Self {
130-
match value {
126+
#[derive(Debug, thiserror::Error)]
127+
#[error("unknown point field datatype: {0}")]
128+
pub struct UnknownPointFieldDatatype(u8);
129+
130+
impl TryFrom<u8> for PointFieldDatatype {
131+
type Error = UnknownPointFieldDatatype;
132+
133+
fn try_from(value: u8) -> Result<Self, Self::Error> {
134+
Ok(match value {
131135
1 => Self::Int8,
132136
2 => Self::UInt8,
133137
3 => Self::Int16,
@@ -136,8 +140,8 @@ impl From<u8> for PointFieldDatatype {
136140
6 => Self::UInt32,
137141
7 => Self::Float32,
138142
8 => Self::Float64,
139-
_ => Self::Unknown,
140-
}
143+
other => Err(UnknownPointFieldDatatype(other))?,
144+
})
141145
}
142146
}
143147

crates/utils/re_mcap/src/parsers/ros2msg/sensor_msgs/point_cloud_2.rs

Lines changed: 210 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -1,18 +1,20 @@
11
use std::io::Cursor;
22

33
use super::super::definitions::sensor_msgs::{self, PointField, PointFieldDatatype};
4+
use anyhow::Context as _;
45
use arrow::{
56
array::{
6-
BooleanBuilder, FixedSizeListBuilder, ListBuilder, StringBuilder, StructBuilder,
7-
UInt8Builder, UInt32Builder,
7+
ArrayBuilder, BooleanBuilder, FixedSizeListBuilder, Float32Builder, Float64Builder,
8+
Int8Builder, Int16Builder, Int32Builder, ListBuilder, StringBuilder, StructBuilder,
9+
UInt8Builder, UInt16Builder, UInt32Builder,
810
},
911
datatypes::{DataType, Field, Fields},
1012
};
1113
use byteorder::{BigEndian, LittleEndian, ReadBytesExt as _};
1214
use re_chunk::{Chunk, ChunkComponents, ChunkId};
1315
use re_types::{
14-
AsComponents as _, Component as _, ComponentDescriptor, SerializedComponentColumn, archetypes,
15-
components, reflection::ComponentDescriptorExt as _,
16+
Archetype as _, AsComponents as _, Component as _, ComponentDescriptor,
17+
SerializedComponentColumn, archetypes, components, reflection::ComponentDescriptorExt as _,
1618
};
1719
use std::collections::HashMap;
1820

@@ -38,6 +40,8 @@ pub struct PointCloud2MessageParser {
3840
data: FixedSizeListBuilder<ListBuilder<UInt8Builder>>,
3941
is_dense: FixedSizeListBuilder<BooleanBuilder>,
4042

43+
extracted_fields: Vec<(String, ListBuilder<Box<dyn ArrayBuilder>>)>,
44+
4145
// We lazily create this, only if we can interpret the point cloud semantically.
4246
// For now, this is the case if there are fields with names `x`,`y`, and `z` present.
4347
points_3ds: Option<Vec<archetypes::Points3D>>,
@@ -80,15 +84,29 @@ impl Ros2MessageParser for PointCloud2MessageParser {
8084
data: blob_list_builder(num_rows),
8185
is_dense: fixed_size_list_builder(1, num_rows),
8286

87+
extracted_fields: Default::default(),
88+
8389
points_3ds: None,
8490
}
8591
}
8692
}
8793

94+
fn builder_from_datatype(datatype: PointFieldDatatype) -> Box<dyn ArrayBuilder> {
95+
match datatype {
96+
PointFieldDatatype::Int8 => Box::new(Int8Builder::new()),
97+
PointFieldDatatype::UInt8 => Box::new(UInt8Builder::new()),
98+
PointFieldDatatype::Int16 => Box::new(Int16Builder::new()),
99+
PointFieldDatatype::UInt16 => Box::new(UInt16Builder::new()),
100+
PointFieldDatatype::Int32 => Box::new(Int32Builder::new()),
101+
PointFieldDatatype::UInt32 => Box::new(UInt32Builder::new()),
102+
PointFieldDatatype::Float32 => Box::new(Float32Builder::new()),
103+
PointFieldDatatype::Float64 => Box::new(Float64Builder::new()),
104+
}
105+
}
106+
88107
fn access(data: &[u8], datatype: PointFieldDatatype, is_big_endian: bool) -> std::io::Result<f32> {
89108
let mut rdr = Cursor::new(data);
90109
match (is_big_endian, datatype) {
91-
(_, PointFieldDatatype::Unknown) => Ok(0f32), // Not in the original spec.
92110
(_, PointFieldDatatype::UInt8) => rdr.read_u8().map(|x| x as f32),
93111
(_, PointFieldDatatype::Int8) => rdr.read_i8().map(|x| x as f32),
94112
(true, PointFieldDatatype::Int16) => rdr.read_i16::<BigEndian>().map(|x| x as f32),
@@ -106,6 +124,21 @@ fn access(data: &[u8], datatype: PointFieldDatatype, is_big_endian: bool) -> std
106124
}
107125
}
108126

127+
impl From<PointFieldDatatype> for DataType {
128+
fn from(value: PointFieldDatatype) -> Self {
129+
match value {
130+
PointFieldDatatype::Int8 => Self::Int8,
131+
PointFieldDatatype::UInt8 => Self::UInt8,
132+
PointFieldDatatype::Int16 => Self::Int16,
133+
PointFieldDatatype::UInt16 => Self::UInt16,
134+
PointFieldDatatype::Int32 => Self::Int32,
135+
PointFieldDatatype::UInt32 => Self::UInt32,
136+
PointFieldDatatype::Float32 => Self::Float32,
137+
PointFieldDatatype::Float64 => Self::Float64,
138+
}
139+
}
140+
}
141+
109142
pub struct Position3DIter<'a> {
110143
point_iter: std::slice::ChunksExact<'a, u8>,
111144
is_big_endian: bool,
@@ -172,6 +205,127 @@ impl Iterator for Position3DIter<'_> {
172205
}
173206
}
174207

208+
fn add_field_value(
209+
builder: &mut Box<dyn ArrayBuilder>,
210+
field: &PointField,
211+
is_big_endian: bool,
212+
data: &[u8],
213+
) -> anyhow::Result<()> {
214+
let mut rdr = Cursor::new(data);
215+
match field.datatype {
216+
PointFieldDatatype::Int8 => {
217+
let builder = builder
218+
.as_any_mut()
219+
.downcast_mut::<Int8Builder>()
220+
.with_context(|| {
221+
format!("found datatype {:?}, but `Int8Builder`", field.datatype)
222+
})?;
223+
let val = rdr.read_i8()?;
224+
builder.append_value(val);
225+
}
226+
PointFieldDatatype::UInt8 => {
227+
let builder = builder
228+
.as_any_mut()
229+
.downcast_mut::<UInt8Builder>()
230+
.with_context(|| {
231+
format!("found datatype {:?}, but `UInt8Builder`", field.datatype)
232+
})?;
233+
let val = rdr.read_u8()?;
234+
builder.append_value(val);
235+
}
236+
PointFieldDatatype::Int16 => {
237+
let builder = builder
238+
.as_any_mut()
239+
.downcast_mut::<Int16Builder>()
240+
.with_context(|| {
241+
format!("found datatype {:?}, but `Int16Builder`", field.datatype)
242+
})?;
243+
let val = if is_big_endian {
244+
rdr.read_i16::<BigEndian>()?
245+
} else {
246+
rdr.read_i16::<LittleEndian>()?
247+
};
248+
builder.append_value(val);
249+
}
250+
PointFieldDatatype::UInt16 => {
251+
let builder = builder
252+
.as_any_mut()
253+
.downcast_mut::<UInt16Builder>()
254+
.with_context(|| {
255+
format!("found datatype {:?}, but `UInt16Builder`", field.datatype)
256+
})?;
257+
let val = if is_big_endian {
258+
rdr.read_u16::<BigEndian>()?
259+
} else {
260+
rdr.read_u16::<LittleEndian>()?
261+
};
262+
builder.append_value(val);
263+
}
264+
265+
PointFieldDatatype::Int32 => {
266+
let builder = builder
267+
.as_any_mut()
268+
.downcast_mut::<Int32Builder>()
269+
.with_context(|| {
270+
format!("found datatype {:?}, but `Int32Builder`", field.datatype)
271+
})?;
272+
273+
let val = if is_big_endian {
274+
rdr.read_i32::<BigEndian>()?
275+
} else {
276+
rdr.read_i32::<LittleEndian>()?
277+
};
278+
builder.append_value(val);
279+
}
280+
PointFieldDatatype::UInt32 => {
281+
let builder = builder
282+
.as_any_mut()
283+
.downcast_mut::<UInt32Builder>()
284+
.with_context(|| {
285+
format!("found datatype {:?}, but `UInt16Builder`", field.datatype)
286+
})?;
287+
let val = if is_big_endian {
288+
rdr.read_u32::<BigEndian>()?
289+
} else {
290+
rdr.read_u32::<LittleEndian>()?
291+
};
292+
builder.append_value(val);
293+
}
294+
295+
PointFieldDatatype::Float32 => {
296+
let builder = builder
297+
.as_any_mut()
298+
.downcast_mut::<Float32Builder>()
299+
.with_context(|| {
300+
format!("found datatype {:?}, but `Float32Builder`", field.datatype)
301+
})?;
302+
let val = if is_big_endian {
303+
rdr.read_f32::<BigEndian>()?
304+
} else {
305+
rdr.read_f32::<LittleEndian>()?
306+
};
307+
builder.append_value(val);
308+
}
309+
310+
PointFieldDatatype::Float64 => {
311+
let builder = builder
312+
.as_any_mut()
313+
.downcast_mut::<Float64Builder>()
314+
.with_context(|| {
315+
format!("found datatype {:?}, but `Float64Builder`", field.datatype)
316+
})?;
317+
let val = if is_big_endian {
318+
rdr.read_f64::<BigEndian>()?
319+
} else {
320+
rdr.read_f64::<LittleEndian>()?
321+
};
322+
builder.append_value(val);
323+
}
324+
}
325+
326+
Ok(())
327+
}
328+
175329
impl MessageParser for PointCloud2MessageParser {
176330
fn append(&mut self, ctx: &mut ParserContext, msg: &mcap::Message<'_>) -> anyhow::Result<()> {
177331
let point_cloud = cdr::try_decode_message::<sensor_msgs::PointCloud2>(msg.data.as_ref())
@@ -194,6 +348,8 @@ impl MessageParser for PointCloud2MessageParser {
194348
data,
195349
is_dense,
196350

351+
extracted_fields,
352+
197353
points_3ds,
198354
} = self;
199355

@@ -207,6 +363,34 @@ impl MessageParser for PointCloud2MessageParser {
207363
&point_cloud.fields,
208364
);
209365

366+
// We lazily initialize the builders that store the extracted fields from
367+
// the blob when we receive the first message.
368+
if extracted_fields.len() != point_cloud.fields.len() {
369+
*extracted_fields = point_cloud
370+
.fields
371+
.iter()
372+
.map(|field| {
373+
(
374+
field.name.clone(),
375+
ListBuilder::new(builder_from_datatype(field.datatype)),
376+
)
377+
})
378+
.collect();
379+
}
380+
381+
for point in point_cloud.data.chunks(point_cloud.point_step as usize) {
382+
for (field, (_name, builder)) in
383+
point_cloud.fields.iter().zip(extracted_fields.iter_mut())
384+
{
385+
let field_builder = builder.values();
386+
add_field_value(field_builder, field, point_cloud.is_bigendian, point)?;
387+
}
388+
}
389+
390+
for (_name, builder) in extracted_fields {
391+
builder.append(true);
392+
}
393+
210394
if let Some(position_iter) = position_iter {
211395
points_3ds
212396
.get_or_insert_with(|| Vec::with_capacity(*num_rows))
@@ -290,12 +474,14 @@ impl MessageParser for PointCloud2MessageParser {
290474
mut data,
291475
mut is_dense,
292476

477+
extracted_fields: points,
478+
293479
points_3ds,
294480
} = *self;
295481

296482
let mut chunks = Vec::new();
297483

298-
for (i, points_3d) in points_3ds.into_iter().enumerate() {
484+
for (i, points_3d) in points_3ds.iter().enumerate() {
299485
let timelines = timelines
300486
.iter()
301487
.map(|(timeline, time_col)| (*timeline, time_col.row_sliced(i, 1).clone()))
@@ -365,6 +551,24 @@ impl MessageParser for PointCloud2MessageParser {
365551
),
366552
]
367553
.into_iter()
554+
.chain(points.into_iter().filter_map(|(name, mut builder)| {
555+
// We only extract additional fields when we have a `Points3d`
556+
// archetype to attach them to. In that case we're not interested
557+
// in the other components.
558+
// TODO(grtlr): It would be nice to never initialize the unnecessary builders
559+
// in the first place. But, we'll soon move the semantic extraction of `Points3d`
560+
// into a different layer anyways, making that optimization obsolete.
561+
points_3ds.as_ref()?;
562+
if ["x", "y", "z"].contains(&name.as_str()) {
563+
None
564+
} else {
565+
Some((
566+
ComponentDescriptor::partial(name.clone())
567+
.with_builtin_archetype(archetypes::Points3D::name()),
568+
builder.finish(),
569+
))
570+
}
571+
}))
368572
.collect(),
369573
)?;
370574

0 commit comments

Comments
 (0)