1
1
use std:: io:: Cursor ;
2
2
3
3
use super :: super :: definitions:: sensor_msgs:: { self , PointField , PointFieldDatatype } ;
4
+ use anyhow:: Context as _;
4
5
use arrow:: {
5
6
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 ,
8
10
} ,
9
11
datatypes:: { DataType , Field , Fields } ,
10
12
} ;
11
13
use byteorder:: { BigEndian , LittleEndian , ReadBytesExt as _} ;
12
14
use re_chunk:: { Chunk , ChunkComponents , ChunkId } ;
13
15
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 _,
16
18
} ;
17
19
use std:: collections:: HashMap ;
18
20
@@ -38,6 +40,8 @@ pub struct PointCloud2MessageParser {
38
40
data : FixedSizeListBuilder < ListBuilder < UInt8Builder > > ,
39
41
is_dense : FixedSizeListBuilder < BooleanBuilder > ,
40
42
43
+ extracted_fields : Vec < ( String , ListBuilder < Box < dyn ArrayBuilder > > ) > ,
44
+
41
45
// We lazily create this, only if we can interpret the point cloud semantically.
42
46
// For now, this is the case if there are fields with names `x`,`y`, and `z` present.
43
47
points_3ds : Option < Vec < archetypes:: Points3D > > ,
@@ -80,15 +84,29 @@ impl Ros2MessageParser for PointCloud2MessageParser {
80
84
data : blob_list_builder ( num_rows) ,
81
85
is_dense : fixed_size_list_builder ( 1 , num_rows) ,
82
86
87
+ extracted_fields : Default :: default ( ) ,
88
+
83
89
points_3ds : None ,
84
90
}
85
91
}
86
92
}
87
93
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
+
88
107
fn access ( data : & [ u8 ] , datatype : PointFieldDatatype , is_big_endian : bool ) -> std:: io:: Result < f32 > {
89
108
let mut rdr = Cursor :: new ( data) ;
90
109
match ( is_big_endian, datatype) {
91
- ( _, PointFieldDatatype :: Unknown ) => Ok ( 0f32 ) , // Not in the original spec.
92
110
( _, PointFieldDatatype :: UInt8 ) => rdr. read_u8 ( ) . map ( |x| x as f32 ) ,
93
111
( _, PointFieldDatatype :: Int8 ) => rdr. read_i8 ( ) . map ( |x| x as f32 ) ,
94
112
( 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
106
124
}
107
125
}
108
126
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
+
109
142
pub struct Position3DIter < ' a > {
110
143
point_iter : std:: slice:: ChunksExact < ' a , u8 > ,
111
144
is_big_endian : bool ,
@@ -172,6 +205,127 @@ impl Iterator for Position3DIter<'_> {
172
205
}
173
206
}
174
207
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
+
175
329
impl MessageParser for PointCloud2MessageParser {
176
330
fn append ( & mut self , ctx : & mut ParserContext , msg : & mcap:: Message < ' _ > ) -> anyhow:: Result < ( ) > {
177
331
let point_cloud = cdr:: try_decode_message :: < sensor_msgs:: PointCloud2 > ( msg. data . as_ref ( ) )
@@ -194,6 +348,8 @@ impl MessageParser for PointCloud2MessageParser {
194
348
data,
195
349
is_dense,
196
350
351
+ extracted_fields,
352
+
197
353
points_3ds,
198
354
} = self ;
199
355
@@ -207,6 +363,34 @@ impl MessageParser for PointCloud2MessageParser {
207
363
& point_cloud. fields ,
208
364
) ;
209
365
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
+
210
394
if let Some ( position_iter) = position_iter {
211
395
points_3ds
212
396
. get_or_insert_with ( || Vec :: with_capacity ( * num_rows) )
@@ -290,12 +474,14 @@ impl MessageParser for PointCloud2MessageParser {
290
474
mut data,
291
475
mut is_dense,
292
476
477
+ extracted_fields : points,
478
+
293
479
points_3ds,
294
480
} = * self ;
295
481
296
482
let mut chunks = Vec :: new ( ) ;
297
483
298
- for ( i, points_3d) in points_3ds. into_iter ( ) . enumerate ( ) {
484
+ for ( i, points_3d) in points_3ds. iter ( ) . enumerate ( ) {
299
485
let timelines = timelines
300
486
. iter ( )
301
487
. map ( |( timeline, time_col) | ( * timeline, time_col. row_sliced ( i, 1 ) . clone ( ) ) )
@@ -365,6 +551,24 @@ impl MessageParser for PointCloud2MessageParser {
365
551
) ,
366
552
]
367
553
. 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
+ } ) )
368
572
. collect ( ) ,
369
573
) ?;
370
574
0 commit comments