@@ -63,7 +63,8 @@ constexpr float TurboBytes[256][3] = {
63
63
{169 , 22 , 1 }, {167 , 20 , 1 }, {164 , 19 , 1 }, {161 , 18 , 1 }, {158 , 16 , 1 },
64
64
{155 , 15 , 1 }, {152 , 14 , 1 }, {149 , 13 , 1 }, {146 , 11 , 1 }, {142 , 10 , 1 },
65
65
{139 , 9 , 2 }, {136 , 8 , 2 }, {133 , 7 , 2 }, {129 , 6 , 2 }, {126 , 5 , 2 },
66
- {122 , 4 , 3 }};
66
+ {122 , 4 , 3 }
67
+ };
67
68
68
69
std::vector<rerun::Color> colormap (
69
70
const std::vector<float >& values, std::optional<float > min_value, std::optional<float > max_value
@@ -81,7 +82,8 @@ std::vector<rerun::Color> colormap(
81
82
auto idx = static_cast <size_t >(
82
83
255 * (value - min_value.value ()) / (max_value.value () - min_value.value ())
83
84
);
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 ])
85
87
);
86
88
}
87
89
return colors;
@@ -91,21 +93,42 @@ void log_imu(
91
93
const rerun::RecordingStream& rec, const std::string& entity_path,
92
94
const sensor_msgs::msg::Imu::ConstSharedPtr& msg
93
95
) {
94
- rec.set_time_timestamp_secs_since_epoch (
96
+ rec.set_time_seconds (
95
97
" timestamp" ,
96
98
rclcpp::Time (msg->header .stamp .sec , msg->header .stamp .nanosec ).seconds ()
97
99
);
98
100
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
+ );
102
125
}
103
126
104
127
void log_image (
105
128
const rerun::RecordingStream& rec, const std::string& entity_path,
106
129
const sensor_msgs::msg::Image::ConstSharedPtr& msg, const ImageOptions& options
107
130
) {
108
- rec.set_time_timestamp_secs_since_epoch (
131
+ rec.set_time_seconds (
109
132
" timestamp" ,
110
133
rclcpp::Time (msg->header .stamp .sec , msg->header .stamp .nanosec ).seconds ()
111
134
);
@@ -143,7 +166,7 @@ void log_pose_stamped(
143
166
const rerun::RecordingStream& rec, const std::string& entity_path,
144
167
const geometry_msgs::msg::PoseStamped::ConstSharedPtr& msg
145
168
) {
146
- rec.set_time_timestamp_secs_since_epoch (
169
+ rec.set_time_seconds (
147
170
" timestamp" ,
148
171
rclcpp::Time (msg->header .stamp .sec , msg->header .stamp .nanosec ).seconds ()
149
172
);
@@ -191,7 +214,7 @@ void log_tf_message(
191
214
continue ;
192
215
}
193
216
194
- rec.set_time_timestamp_secs_since_epoch (
217
+ rec.set_time_seconds (
195
218
" timestamp" ,
196
219
rclcpp::Time (transform.header .stamp .sec , transform.header .stamp .nanosec ).seconds ()
197
220
);
@@ -219,7 +242,7 @@ void log_odometry(
219
242
const rerun::RecordingStream& rec, const std::string& entity_path,
220
243
const nav_msgs::msg::Odometry::ConstSharedPtr& msg
221
244
) {
222
- rec.set_time_timestamp_secs_since_epoch (
245
+ rec.set_time_seconds (
223
246
" timestamp" ,
224
247
rclcpp::Time (msg->header .stamp .sec , msg->header .stamp .nanosec ).seconds ()
225
248
);
@@ -269,7 +292,7 @@ void log_transform(
269
292
const rerun::RecordingStream& rec, const std::string& entity_path,
270
293
const geometry_msgs::msg::TransformStamped::ConstSharedPtr& msg
271
294
) {
272
- rec.set_time_timestamp_secs_since_epoch (
295
+ rec.set_time_seconds (
273
296
" timestamp" ,
274
297
rclcpp::Time (msg->header .stamp .sec , msg->header .stamp .nanosec ).seconds ()
275
298
);
@@ -296,7 +319,7 @@ void log_point_cloud2(
296
319
const rerun::RecordingStream& rec, const std::string& entity_path,
297
320
const sensor_msgs::msg::PointCloud2::ConstSharedPtr& msg, const PointCloud2Options& options
298
321
) {
299
- rec.set_time_timestamp_secs_since_epoch (
322
+ rec.set_time_seconds (
300
323
" timestamp" ,
301
324
rclcpp::Time (msg->header .stamp .sec , msg->header .stamp .nanosec ).seconds ()
302
325
);
@@ -410,44 +433,65 @@ void log_joint_state(
410
433
) {
411
434
// Set timestamp if available, otherwise skip timestamp logging to use current time
412
435
if (msg->header .stamp .sec != 0 || msg->header .stamp .nanosec != 0 ) {
413
- rec.set_time_timestamp_secs_since_epoch (
436
+ rec.set_time_seconds (
414
437
" timestamp" ,
415
438
rclcpp::Time (msg->header .stamp .sec , msg->header .stamp .nanosec ).seconds ()
416
439
);
417
440
}
418
-
441
+
419
442
// Log joint angles as time series scalars using the new Rerun 0.24.0 API
420
443
// This follows the pattern from the Rust and Python examples
421
444
for (size_t i = 0 ; i < msg->name .size () && i < msg->position .size (); ++i) {
422
445
const std::string& joint_name = msg->name [i];
423
446
double joint_position = msg->position [i];
424
-
447
+
425
448
// Log each joint angle as a separate time series scalar
426
449
// Entity path format: /joint_angles/joint_name
427
450
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
+ );
430
460
}
431
-
461
+
432
462
// Also log joint velocities if available
433
463
if (!msg->velocity .empty () && msg->velocity .size () == msg->name .size ()) {
434
464
for (size_t i = 0 ; i < msg->name .size (); ++i) {
435
465
const std::string& joint_name = msg->name [i];
436
466
double joint_velocity = msg->velocity [i];
437
-
467
+
438
468
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
+ );
440
477
}
441
478
}
442
-
479
+
443
480
// Log joint efforts/torques if available
444
481
if (!msg->effort .empty () && msg->effort .size () == msg->name .size ()) {
445
482
for (size_t i = 0 ; i < msg->name .size (); ++i) {
446
483
const std::string& joint_name = msg->name [i];
447
484
double joint_effort = msg->effort [i];
448
-
485
+
449
486
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
+ );
451
495
}
452
496
}
453
497
}
0 commit comments