Skip to content

Commit 30c8339

Browse files
committed
chore: bump rerun API compatibiliy to 0.18.2
1 parent 04c2c3c commit 30c8339

File tree

3 files changed

+25
-14
lines changed

3 files changed

+25
-14
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: 15 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -22,9 +22,20 @@ 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),
25+
inline rerun::WidthHeight width_height(const cv::Mat& img) {
26+
return rerun::WidthHeight(
2827
static_cast<size_t>(img.cols),
29-
static_cast<size_t>(img.channels())};
28+
static_cast<size_t>(img.rows)
29+
);
3030
};
31+
32+
template<typename T>
33+
rerun::Collection<T> img_data_as_collection(const cv::Mat& img) {
34+
const T* img_data = reinterpret_cast<const T*>(img.data);
35+
36+
size_t img_size = img.total() * img.channels();
37+
38+
std::vector<T> img_vec(img_data, img_data + img_size);
39+
40+
return rerun::Collection<T>::take_ownership(std::move(img_vec));
41+
}

rerun_bridge/src/rerun_bridge/rerun_ros_interface.cpp

Lines changed: 9 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -117,8 +117,8 @@ void log_image(
117117
rec.log(
118118
entity_path,
119119
rerun::DepthImage(
120-
{static_cast<size_t>(img.rows), static_cast<size_t>(img.cols)},
121-
rerun::TensorBuffer::u16(img)
120+
img_data_as_collection<uint16_t>(img),
121+
{static_cast<size_t>(img.rows), static_cast<size_t>(img.cols)}
122122
)
123123
.with_meter(1000)
124124
);
@@ -133,14 +133,14 @@ void log_image(
133133
rec.log(
134134
entity_path,
135135
rerun::DepthImage(
136-
{static_cast<size_t>(img.rows), static_cast<size_t>(img.cols)},
137-
rerun::TensorBuffer::f32(img)
136+
img_data_as_collection<float>(img),
137+
{static_cast<size_t>(img.rows), static_cast<size_t>(img.cols)}
138138
)
139139
.with_meter(1.0)
140140
);
141141
} else {
142142
cv::Mat img = cv_bridge::toCvCopy(msg, "rgb8")->image;
143-
rec.log(entity_path, rerun::Image(tensor_shape(img), rerun::TensorBuffer::u8(img)));
143+
rec.log(entity_path, rerun::Image::from_rgb24(img_data_as_collection<uint8_t>(img), width_height(img)));
144144
}
145145
}
146146

@@ -156,7 +156,7 @@ void log_pose_stamped(
156156
rec.log(
157157
entity_path,
158158
rerun::Transform3D(
159-
rerun::Vector3D(msg->pose.position.x, msg->pose.position.y, msg->pose.position.z),
159+
rerun::components::Translation3D(msg->pose.position.x, msg->pose.position.y, msg->pose.position.z),
160160
rerun::Quaternion::from_wxyz(
161161
msg->pose.orientation.w,
162162
msg->pose.orientation.x,
@@ -200,7 +200,7 @@ void log_tf_message(
200200
rec.log(
201201
tf_frame_to_entity_path.at(transform.child_frame_id),
202202
rerun::Transform3D(
203-
rerun::Vector3D(
203+
rerun::components::Translation3D(
204204
transform.transform.translation.x,
205205
transform.transform.translation.y,
206206
transform.transform.translation.z
@@ -228,7 +228,7 @@ void log_odometry(
228228
rec.log(
229229
entity_path,
230230
rerun::Transform3D(
231-
rerun::Vector3D(
231+
rerun::components::Translation3D(
232232
msg->pose.pose.position.x,
233233
msg->pose.pose.position.y,
234234
msg->pose.pose.position.z
@@ -278,7 +278,7 @@ void log_transform(
278278
rec.log(
279279
entity_path,
280280
rerun::Transform3D(
281-
rerun::Vector3D(
281+
rerun::components::Translation3D(
282282
msg->transform.translation.x,
283283
msg->transform.translation.y,
284284
msg->transform.translation.z

0 commit comments

Comments
 (0)