Skip to content

Commit d64ec2d

Browse files
committed
restore old time logging
1 parent d7822ff commit d64ec2d

File tree

1 file changed

+67
-23
lines changed

1 file changed

+67
-23
lines changed

rerun_bridge/src/rerun_bridge/rerun_ros_interface.cpp

Lines changed: 67 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -63,7 +63,8 @@ constexpr float TurboBytes[256][3] = {
6363
{169, 22, 1}, {167, 20, 1}, {164, 19, 1}, {161, 18, 1}, {158, 16, 1},
6464
{155, 15, 1}, {152, 14, 1}, {149, 13, 1}, {146, 11, 1}, {142, 10, 1},
6565
{139, 9, 2}, {136, 8, 2}, {133, 7, 2}, {129, 6, 2}, {126, 5, 2},
66-
{122, 4, 3}};
66+
{122, 4, 3}
67+
};
6768

6869
std::vector<rerun::Color> colormap(
6970
const std::vector<float>& values, std::optional<float> min_value, std::optional<float> max_value
@@ -81,7 +82,8 @@ std::vector<rerun::Color> colormap(
8182
auto idx = static_cast<size_t>(
8283
255 * (value - min_value.value()) / (max_value.value() - min_value.value())
8384
);
84-
colors.emplace_back(rerun::Color(TurboBytes[idx][0], TurboBytes[idx][1], TurboBytes[idx][2])
85+
colors.emplace_back(
86+
rerun::Color(TurboBytes[idx][0], TurboBytes[idx][1], TurboBytes[idx][2])
8587
);
8688
}
8789
return colors;
@@ -91,21 +93,42 @@ void log_imu(
9193
const rerun::RecordingStream& rec, const std::string& entity_path,
9294
const sensor_msgs::msg::Imu::ConstSharedPtr& msg
9395
) {
94-
rec.set_time_timestamp_secs_since_epoch(
96+
rec.set_time_seconds(
9597
"timestamp",
9698
rclcpp::Time(msg->header.stamp.sec, msg->header.stamp.nanosec).seconds()
9799
);
98100

99-
rec.log(entity_path + "/x", rerun::Scalars(rerun::Collection<rerun::components::Scalar>::take_ownership({rerun::components::Scalar(msg->linear_acceleration.x)})));
100-
rec.log(entity_path + "/y", rerun::Scalars(rerun::Collection<rerun::components::Scalar>::take_ownership({rerun::components::Scalar(msg->linear_acceleration.y)})));
101-
rec.log(entity_path + "/z", rerun::Scalars(rerun::Collection<rerun::components::Scalar>::take_ownership({rerun::components::Scalar(msg->linear_acceleration.z)})));
101+
rec.log(
102+
entity_path + "/x",
103+
rerun::Scalars(
104+
rerun::Collection<rerun::components::Scalar>::take_ownership(
105+
{rerun::components::Scalar(msg->linear_acceleration.x)}
106+
)
107+
)
108+
);
109+
rec.log(
110+
entity_path + "/y",
111+
rerun::Scalars(
112+
rerun::Collection<rerun::components::Scalar>::take_ownership(
113+
{rerun::components::Scalar(msg->linear_acceleration.y)}
114+
)
115+
)
116+
);
117+
rec.log(
118+
entity_path + "/z",
119+
rerun::Scalars(
120+
rerun::Collection<rerun::components::Scalar>::take_ownership(
121+
{rerun::components::Scalar(msg->linear_acceleration.z)}
122+
)
123+
)
124+
);
102125
}
103126

104127
void log_image(
105128
const rerun::RecordingStream& rec, const std::string& entity_path,
106129
const sensor_msgs::msg::Image::ConstSharedPtr& msg, const ImageOptions& options
107130
) {
108-
rec.set_time_timestamp_secs_since_epoch(
131+
rec.set_time_seconds(
109132
"timestamp",
110133
rclcpp::Time(msg->header.stamp.sec, msg->header.stamp.nanosec).seconds()
111134
);
@@ -143,7 +166,7 @@ void log_pose_stamped(
143166
const rerun::RecordingStream& rec, const std::string& entity_path,
144167
const geometry_msgs::msg::PoseStamped::ConstSharedPtr& msg
145168
) {
146-
rec.set_time_timestamp_secs_since_epoch(
169+
rec.set_time_seconds(
147170
"timestamp",
148171
rclcpp::Time(msg->header.stamp.sec, msg->header.stamp.nanosec).seconds()
149172
);
@@ -191,7 +214,7 @@ void log_tf_message(
191214
continue;
192215
}
193216

194-
rec.set_time_timestamp_secs_since_epoch(
217+
rec.set_time_seconds(
195218
"timestamp",
196219
rclcpp::Time(transform.header.stamp.sec, transform.header.stamp.nanosec).seconds()
197220
);
@@ -219,7 +242,7 @@ void log_odometry(
219242
const rerun::RecordingStream& rec, const std::string& entity_path,
220243
const nav_msgs::msg::Odometry::ConstSharedPtr& msg
221244
) {
222-
rec.set_time_timestamp_secs_since_epoch(
245+
rec.set_time_seconds(
223246
"timestamp",
224247
rclcpp::Time(msg->header.stamp.sec, msg->header.stamp.nanosec).seconds()
225248
);
@@ -269,7 +292,7 @@ void log_transform(
269292
const rerun::RecordingStream& rec, const std::string& entity_path,
270293
const geometry_msgs::msg::TransformStamped::ConstSharedPtr& msg
271294
) {
272-
rec.set_time_timestamp_secs_since_epoch(
295+
rec.set_time_seconds(
273296
"timestamp",
274297
rclcpp::Time(msg->header.stamp.sec, msg->header.stamp.nanosec).seconds()
275298
);
@@ -296,7 +319,7 @@ void log_point_cloud2(
296319
const rerun::RecordingStream& rec, const std::string& entity_path,
297320
const sensor_msgs::msg::PointCloud2::ConstSharedPtr& msg, const PointCloud2Options& options
298321
) {
299-
rec.set_time_timestamp_secs_since_epoch(
322+
rec.set_time_seconds(
300323
"timestamp",
301324
rclcpp::Time(msg->header.stamp.sec, msg->header.stamp.nanosec).seconds()
302325
);
@@ -410,44 +433,65 @@ void log_joint_state(
410433
) {
411434
// Set timestamp if available, otherwise skip timestamp logging to use current time
412435
if (msg->header.stamp.sec != 0 || msg->header.stamp.nanosec != 0) {
413-
rec.set_time_timestamp_secs_since_epoch(
436+
rec.set_time_seconds(
414437
"timestamp",
415438
rclcpp::Time(msg->header.stamp.sec, msg->header.stamp.nanosec).seconds()
416439
);
417440
}
418-
441+
419442
// Log joint angles as time series scalars using the new Rerun 0.24.0 API
420443
// This follows the pattern from the Rust and Python examples
421444
for (size_t i = 0; i < msg->name.size() && i < msg->position.size(); ++i) {
422445
const std::string& joint_name = msg->name[i];
423446
double joint_position = msg->position[i];
424-
447+
425448
// Log each joint angle as a separate time series scalar
426449
// Entity path format: /joint_angles/joint_name
427450
std::string joint_entity_path = entity_path + "/joint_angles/" + joint_name;
428-
429-
rec.log(joint_entity_path, rerun::Scalars(rerun::Collection<rerun::components::Scalar>::take_ownership({rerun::components::Scalar(joint_position)})));
451+
452+
rec.log(
453+
joint_entity_path,
454+
rerun::Scalars(
455+
rerun::Collection<rerun::components::Scalar>::take_ownership(
456+
{rerun::components::Scalar(joint_position)}
457+
)
458+
)
459+
);
430460
}
431-
461+
432462
// Also log joint velocities if available
433463
if (!msg->velocity.empty() && msg->velocity.size() == msg->name.size()) {
434464
for (size_t i = 0; i < msg->name.size(); ++i) {
435465
const std::string& joint_name = msg->name[i];
436466
double joint_velocity = msg->velocity[i];
437-
467+
438468
std::string velocity_entity_path = entity_path + "/joint_velocities/" + joint_name;
439-
rec.log(velocity_entity_path, rerun::Scalars(rerun::Collection<rerun::components::Scalar>::take_ownership({rerun::components::Scalar(joint_velocity)})));
469+
rec.log(
470+
velocity_entity_path,
471+
rerun::Scalars(
472+
rerun::Collection<rerun::components::Scalar>::take_ownership(
473+
{rerun::components::Scalar(joint_velocity)}
474+
)
475+
)
476+
);
440477
}
441478
}
442-
479+
443480
// Log joint efforts/torques if available
444481
if (!msg->effort.empty() && msg->effort.size() == msg->name.size()) {
445482
for (size_t i = 0; i < msg->name.size(); ++i) {
446483
const std::string& joint_name = msg->name[i];
447484
double joint_effort = msg->effort[i];
448-
485+
449486
std::string effort_entity_path = entity_path + "/joint_efforts/" + joint_name;
450-
rec.log(effort_entity_path, rerun::Scalars(rerun::Collection<rerun::components::Scalar>::take_ownership({rerun::components::Scalar(joint_effort)})));
487+
rec.log(
488+
effort_entity_path,
489+
rerun::Scalars(
490+
rerun::Collection<rerun::components::Scalar>::take_ownership(
491+
{rerun::components::Scalar(joint_effort)}
492+
)
493+
)
494+
);
451495
}
452496
}
453497
}

0 commit comments

Comments
 (0)