Skip to content
Merged
Show file tree
Hide file tree
Changes from 4 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion rerun_bridge/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ find_package(OpenCV REQUIRED)
find_package(yaml-cpp REQUIRED)

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

# setup targets (has to be done before ament_package call)
Expand Down
7 changes: 2 additions & 5 deletions rerun_bridge/src/rerun_bridge/collection_adapters.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,9 +22,6 @@ struct rerun::CollectionAdapter<TElement, cv::Mat> {
}
};

inline rerun::Collection<rerun::TensorDimension> tensor_shape(const cv::Mat& img) {
return {
static_cast<size_t>(img.rows),
static_cast<size_t>(img.cols),
static_cast<size_t>(img.channels())};
inline rerun::WidthHeight width_height(const cv::Mat& img) {
return rerun::WidthHeight(static_cast<size_t>(img.cols), static_cast<size_t>(img.rows));
};
29 changes: 14 additions & 15 deletions rerun_bridge/src/rerun_bridge/rerun_ros_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -116,11 +116,7 @@ void log_image(
cv::Mat img = cv_bridge::toCvCopy(msg)->image;
rec.log(
entity_path,
rerun::DepthImage(
{static_cast<size_t>(img.rows), static_cast<size_t>(img.cols)},
rerun::TensorBuffer::u16(img)
)
.with_meter(1000)
rerun::DepthImage(rerun::Collection<uint16_t>(img), width_height(img)).with_meter(1000)
);
} else if (msg->encoding == "32FC1") {
cv::Mat img = cv_bridge::toCvCopy(msg)->image;
Expand All @@ -132,15 +128,14 @@ void log_image(
}
rec.log(
entity_path,
rerun::DepthImage(
{static_cast<size_t>(img.rows), static_cast<size_t>(img.cols)},
rerun::TensorBuffer::f32(img)
)
.with_meter(1.0)
rerun::DepthImage(rerun::Collection<float>(img), width_height(img)).with_meter(1.0)
);
} else {
cv::Mat img = cv_bridge::toCvCopy(msg, "rgb8")->image;
rec.log(entity_path, rerun::Image(tensor_shape(img), rerun::TensorBuffer::u8(img)));
rec.log(
entity_path,
rerun::Image::from_rgb24(rerun::Collection<uint8_t>(img), width_height(img))
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I honestly don't know what is the proper way to use CollectionAdapters here. Without contstructor/casting it does not compile and I yet to find a recent example that works

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Seems related to this issue:

But I think this code this is fine, since it borrows data that lives longer than rerun::Image

);
}
}

Expand All @@ -156,7 +151,11 @@ void log_pose_stamped(
rec.log(
entity_path,
rerun::Transform3D(
rerun::Vector3D(msg->pose.position.x, msg->pose.position.y, msg->pose.position.z),
rerun::components::Translation3D(
msg->pose.position.x,
msg->pose.position.y,
msg->pose.position.z
),
rerun::Quaternion::from_wxyz(
msg->pose.orientation.w,
msg->pose.orientation.x,
Expand Down Expand Up @@ -200,7 +199,7 @@ void log_tf_message(
rec.log(
tf_frame_to_entity_path.at(transform.child_frame_id),
rerun::Transform3D(
rerun::Vector3D(
rerun::components::Translation3D(
transform.transform.translation.x,
transform.transform.translation.y,
transform.transform.translation.z
Expand Down Expand Up @@ -228,7 +227,7 @@ void log_odometry(
rec.log(
entity_path,
rerun::Transform3D(
rerun::Vector3D(
rerun::components::Translation3D(
msg->pose.pose.position.x,
msg->pose.pose.position.y,
msg->pose.pose.position.z
Expand Down Expand Up @@ -278,7 +277,7 @@ void log_transform(
rec.log(
entity_path,
rerun::Transform3D(
rerun::Vector3D(
rerun::components::Translation3D(
msg->transform.translation.x,
msg->transform.translation.y,
msg->transform.translation.z
Expand Down