@@ -116,11 +116,7 @@ void log_image(
116
116
cv::Mat img = cv_bridge::toCvCopy (msg)->image ;
117
117
rec.log (
118
118
entity_path,
119
- rerun::DepthImage (
120
- {static_cast <size_t >(img.rows ), static_cast <size_t >(img.cols )},
121
- rerun::TensorBuffer::u16 (img)
122
- )
123
- .with_meter (1000 )
119
+ rerun::DepthImage (rerun::Collection<uint16_t >(img), width_height (img)).with_meter (1000 )
124
120
);
125
121
} else if (msg->encoding == " 32FC1" ) {
126
122
cv::Mat img = cv_bridge::toCvCopy (msg)->image ;
@@ -132,15 +128,14 @@ void log_image(
132
128
}
133
129
rec.log (
134
130
entity_path,
135
- rerun::DepthImage (
136
- {static_cast <size_t >(img.rows ), static_cast <size_t >(img.cols )},
137
- rerun::TensorBuffer::f32 (img)
138
- )
139
- .with_meter (1.0 )
131
+ rerun::DepthImage (rerun::Collection<float >(img), width_height (img)).with_meter (1.0 )
140
132
);
141
133
} else {
142
134
cv::Mat img = cv_bridge::toCvCopy (msg, " rgb8" )->image ;
143
- rec.log (entity_path, rerun::Image (tensor_shape (img), rerun::TensorBuffer::u8 (img)));
135
+ rec.log (
136
+ entity_path,
137
+ rerun::Image::from_rgb24 (rerun::Collection<uint8_t >(img), width_height (img))
138
+ );
144
139
}
145
140
}
146
141
@@ -156,7 +151,11 @@ void log_pose_stamped(
156
151
rec.log (
157
152
entity_path,
158
153
rerun::Transform3D (
159
- rerun::Vector3D (msg->pose .position .x , msg->pose .position .y , msg->pose .position .z ),
154
+ rerun::components::Translation3D (
155
+ msg->pose .position .x ,
156
+ msg->pose .position .y ,
157
+ msg->pose .position .z
158
+ ),
160
159
rerun::Quaternion::from_wxyz (
161
160
msg->pose .orientation .w ,
162
161
msg->pose .orientation .x ,
@@ -200,7 +199,7 @@ void log_tf_message(
200
199
rec.log (
201
200
tf_frame_to_entity_path.at (transform.child_frame_id ),
202
201
rerun::Transform3D (
203
- rerun::Vector3D (
202
+ rerun::components::Translation3D (
204
203
transform.transform .translation .x ,
205
204
transform.transform .translation .y ,
206
205
transform.transform .translation .z
@@ -228,7 +227,7 @@ void log_odometry(
228
227
rec.log (
229
228
entity_path,
230
229
rerun::Transform3D (
231
- rerun::Vector3D (
230
+ rerun::components::Translation3D (
232
231
msg->pose .pose .position .x ,
233
232
msg->pose .pose .position .y ,
234
233
msg->pose .pose .position .z
@@ -278,7 +277,7 @@ void log_transform(
278
277
rec.log (
279
278
entity_path,
280
279
rerun::Transform3D (
281
- rerun::Vector3D (
280
+ rerun::components::Translation3D (
282
281
msg->transform .translation .x ,
283
282
msg->transform .translation .y ,
284
283
msg->transform .translation .z
@@ -307,8 +306,8 @@ void log_point_cloud2(
307
306
// TODO(leo) if not specified, check if 2D points or 3D points
308
307
// TODO(leo) allow arbitrary color mapping
309
308
310
- size_t x_offset, y_offset, z_offset;
311
- bool has_x{false }, has_y{false }, has_z{false };
309
+ size_t x_offset, y_offset, z_offset, rgb_offset ;
310
+ bool has_x{false }, has_y{false }, has_z{false }, has_rgb{ false } ;
312
311
313
312
for (const auto & field : msg->fields ) {
314
313
if (field.name == " x" ) {
@@ -332,6 +331,15 @@ void log_point_cloud2(
332
331
return ;
333
332
}
334
333
has_z = true ;
334
+ } else if (field.name == options.colormap_field .value_or (" rgb" )) {
335
+ if (field.datatype == sensor_msgs::msg::PointField::UINT32 ||
336
+ field.datatype == sensor_msgs::msg::PointField::FLOAT32) {
337
+ has_rgb = true ;
338
+ rgb_offset = field.offset ;
339
+ } else {
340
+ rec.log (entity_path, rerun::TextLog (" Only UINT32 and FLOAT32 rgb field supported" ));
341
+ continue ;
342
+ }
335
343
}
336
344
}
337
345
@@ -346,6 +354,10 @@ void log_point_cloud2(
346
354
std::vector<rerun::Position3D> points (msg->width * msg->height );
347
355
std::vector<rerun::Color> colors;
348
356
357
+ if (has_rgb) {
358
+ colors.reserve (msg->width * msg->height );
359
+ }
360
+
349
361
for (size_t i = 0 ; i < msg->height ; ++i) {
350
362
for (size_t j = 0 ; j < msg->width ; ++j) {
351
363
auto point_offset = i * msg->row_step + j * msg->point_step ;
@@ -354,7 +366,12 @@ void log_point_cloud2(
354
366
std::memcpy (&position.xyz .xyz [0 ], &msg->data [point_offset + x_offset], sizeof (float ));
355
367
std::memcpy (&position.xyz .xyz [1 ], &msg->data [point_offset + y_offset], sizeof (float ));
356
368
std::memcpy (&position.xyz .xyz [2 ], &msg->data [point_offset + z_offset], sizeof (float ));
357
- points.emplace_back (std::move (position));
369
+ if (has_rgb) {
370
+ uint8_t bgra[4 ];
371
+ std::memcpy (&bgra, &msg->data [point_offset + rgb_offset], sizeof (uint32_t ));
372
+ colors.emplace_back (rerun::Color (bgra[2 ], bgra[1 ], bgra[0 ]));
373
+ }
374
+ points[i * msg->width + j] = position;
358
375
}
359
376
}
360
377
@@ -372,10 +389,14 @@ void log_point_cloud2(
372
389
&msg->data [i * msg->row_step + j * msg->point_step + colormap_field.offset ],
373
390
sizeof (float )
374
391
);
375
- values. emplace_back ( value) ;
392
+ values[i * msg-> width + j] = value;
376
393
}
377
394
}
378
395
colors = colormap (values, options.colormap_min , options.colormap_max );
396
+ } else if (options.colormap == " rgb" ) {
397
+ if (!has_rgb) {
398
+ rec.log (entity_path, rerun::TextLog (" RGB colormap specified but no RGB field present" ));
399
+ }
379
400
} else if (options.colormap ) {
380
401
rec.log (" /" , rerun::TextLog (" Unsupported colormap specified: " + options.colormap .value ()));
381
402
}
0 commit comments