Skip to content

Commit d7822ff

Browse files
committed
fix transform lookup errors
1 parent 472dd8c commit d7822ff

File tree

2 files changed

+9
-1
lines changed

2 files changed

+9
-1
lines changed

rerun_bridge/src/rerun_bridge/rerun_ros_interface.cpp

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -408,6 +408,14 @@ void log_joint_state(
408408
const rerun::RecordingStream& rec, const std::string& entity_path,
409409
const sensor_msgs::msg::JointState::ConstSharedPtr& msg
410410
) {
411+
// Set timestamp if available, otherwise skip timestamp logging to use current time
412+
if (msg->header.stamp.sec != 0 || msg->header.stamp.nanosec != 0) {
413+
rec.set_time_timestamp_secs_since_epoch(
414+
"timestamp",
415+
rclcpp::Time(msg->header.stamp.sec, msg->header.stamp.nanosec).seconds()
416+
);
417+
}
418+
411419
// Log joint angles as time series scalars using the new Rerun 0.24.0 API
412420
// This follows the pattern from the Rust and Python examples
413421
for (size_t i = 0; i < msg->name.size() && i < msg->position.size(); ++i) {

rerun_bridge/src/rerun_bridge/visualizer_node.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -593,7 +593,7 @@ std::shared_ptr<rclcpp::Subscription<sensor_msgs::msg::JointState>>
593593
const std::string& topic, const TopicOptions& topic_options
594594
) {
595595
std::string entity_path = _resolve_entity_path(topic, topic_options);
596-
bool lookup_transform = (topic_options.find("entity_path") == topic_options.end());
596+
bool lookup_transform = false; // Joint states don't need coordinate transformations
597597
bool restamp = false;
598598
if (topic_options.find("restamp") != topic_options.end()) {
599599
restamp = topic_options.at("restamp").as<bool>();

0 commit comments

Comments
 (0)