Skip to content

Commit d4958e8

Browse files
authored
Merge pull request #16 from tfoldi/v0.18.2
update Rerun API V0.18.2
2 parents 04c2c3c + eeb63ae commit d4958e8

File tree

3 files changed

+43
-25
lines changed

3 files changed

+43
-25
lines changed

rerun_bridge/CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,7 @@ find_package(OpenCV REQUIRED)
2222
find_package(yaml-cpp REQUIRED)
2323

2424
include(FetchContent)
25-
FetchContent_Declare(rerun_sdk URL https://github.com/rerun-io/rerun/releases/download/0.16.0/rerun_cpp_sdk.zip)
25+
FetchContent_Declare(rerun_sdk URL https://github.com/rerun-io/rerun/releases/download/0.18.2/rerun_cpp_sdk.zip)
2626
FetchContent_MakeAvailable(rerun_sdk)
2727

2828
# setup targets (has to be done before ament_package call)

rerun_bridge/src/rerun_bridge/collection_adapters.hpp

Lines changed: 2 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -22,9 +22,6 @@ struct rerun::CollectionAdapter<TElement, cv::Mat> {
2222
}
2323
};
2424

25-
inline rerun::Collection<rerun::TensorDimension> tensor_shape(const cv::Mat& img) {
26-
return {
27-
static_cast<size_t>(img.rows),
28-
static_cast<size_t>(img.cols),
29-
static_cast<size_t>(img.channels())};
25+
inline rerun::WidthHeight width_height(const cv::Mat& img) {
26+
return rerun::WidthHeight(static_cast<size_t>(img.cols), static_cast<size_t>(img.rows));
3027
};

rerun_bridge/src/rerun_bridge/rerun_ros_interface.cpp

Lines changed: 40 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -116,11 +116,7 @@ void log_image(
116116
cv::Mat img = cv_bridge::toCvCopy(msg)->image;
117117
rec.log(
118118
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)
124120
);
125121
} else if (msg->encoding == "32FC1") {
126122
cv::Mat img = cv_bridge::toCvCopy(msg)->image;
@@ -132,15 +128,14 @@ void log_image(
132128
}
133129
rec.log(
134130
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)
140132
);
141133
} else {
142134
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+
);
144139
}
145140
}
146141

@@ -156,7 +151,11 @@ void log_pose_stamped(
156151
rec.log(
157152
entity_path,
158153
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+
),
160159
rerun::Quaternion::from_wxyz(
161160
msg->pose.orientation.w,
162161
msg->pose.orientation.x,
@@ -200,7 +199,7 @@ void log_tf_message(
200199
rec.log(
201200
tf_frame_to_entity_path.at(transform.child_frame_id),
202201
rerun::Transform3D(
203-
rerun::Vector3D(
202+
rerun::components::Translation3D(
204203
transform.transform.translation.x,
205204
transform.transform.translation.y,
206205
transform.transform.translation.z
@@ -228,7 +227,7 @@ void log_odometry(
228227
rec.log(
229228
entity_path,
230229
rerun::Transform3D(
231-
rerun::Vector3D(
230+
rerun::components::Translation3D(
232231
msg->pose.pose.position.x,
233232
msg->pose.pose.position.y,
234233
msg->pose.pose.position.z
@@ -278,7 +277,7 @@ void log_transform(
278277
rec.log(
279278
entity_path,
280279
rerun::Transform3D(
281-
rerun::Vector3D(
280+
rerun::components::Translation3D(
282281
msg->transform.translation.x,
283282
msg->transform.translation.y,
284283
msg->transform.translation.z
@@ -307,8 +306,8 @@ void log_point_cloud2(
307306
// TODO(leo) if not specified, check if 2D points or 3D points
308307
// TODO(leo) allow arbitrary color mapping
309308

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};
312311

313312
for (const auto& field : msg->fields) {
314313
if (field.name == "x") {
@@ -332,6 +331,15 @@ void log_point_cloud2(
332331
return;
333332
}
334333
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+
}
335343
}
336344
}
337345

@@ -346,6 +354,10 @@ void log_point_cloud2(
346354
std::vector<rerun::Position3D> points(msg->width * msg->height);
347355
std::vector<rerun::Color> colors;
348356

357+
if (has_rgb) {
358+
colors.reserve(msg->width * msg->height);
359+
}
360+
349361
for (size_t i = 0; i < msg->height; ++i) {
350362
for (size_t j = 0; j < msg->width; ++j) {
351363
auto point_offset = i * msg->row_step + j * msg->point_step;
@@ -354,7 +366,12 @@ void log_point_cloud2(
354366
std::memcpy(&position.xyz.xyz[0], &msg->data[point_offset + x_offset], sizeof(float));
355367
std::memcpy(&position.xyz.xyz[1], &msg->data[point_offset + y_offset], sizeof(float));
356368
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;
358375
}
359376
}
360377

@@ -372,10 +389,14 @@ void log_point_cloud2(
372389
&msg->data[i * msg->row_step + j * msg->point_step + colormap_field.offset],
373390
sizeof(float)
374391
);
375-
values.emplace_back(value);
392+
values[i * msg->width + j] = value;
376393
}
377394
}
378395
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+
}
379400
} else if (options.colormap) {
380401
rec.log("/", rerun::TextLog("Unsupported colormap specified: " + options.colormap.value()));
381402
}

0 commit comments

Comments
 (0)