Skip to content
Open
Show file tree
Hide file tree
Changes from all 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
14 changes: 7 additions & 7 deletions rerun_bridge/include/rerun_bridge/rerun_ros_interface.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,36 +15,36 @@

void log_imu(
const rerun::RecordingStream& rec, const std::string& entity_path,
const sensor_msgs::Imu::ConstPtr& msg
const sensor_msgs::Imu::ConstPtr& msg, double normalized_timestamp
);

void log_image(
const rerun::RecordingStream& rec, const std::string& entity_path,
const sensor_msgs::Image::ConstPtr& msg
const sensor_msgs::Image::ConstPtr& msg, double normalized_timestamp
);

void log_pose_stamped(
const rerun::RecordingStream& rec, const std::string& entity_path,
const geometry_msgs::PoseStamped::ConstPtr& msg
const geometry_msgs::PoseStamped::ConstPtr& msg, double normalized_timestamp
);

void log_odometry(
const rerun::RecordingStream& rec, const std::string& entity_path,
const nav_msgs::Odometry::ConstPtr& msg
const nav_msgs::Odometry::ConstPtr& msg, double normalized_timestamp
);

void log_camera_info(
const rerun::RecordingStream& rec, const std::string& entity_path,
const sensor_msgs::CameraInfo::ConstPtr& msg
const sensor_msgs::CameraInfo::ConstPtr& msg, double normalized_timestamp
);

void log_tf_message(
const rerun::RecordingStream& rec,
const std::map<std::string, std::string>& tf_frame_to_entity_path,
const tf2_msgs::TFMessage::ConstPtr& msg
const tf2_msgs::TFMessage::ConstPtr& msg, double normalized_timestamp
);

void log_transform(
const rerun::RecordingStream& rec, const std::string& entity_path,
const geometry_msgs::TransformStamped& msg
const geometry_msgs::TransformStamped& msg, double normalized_timestamp
);
26 changes: 13 additions & 13 deletions rerun_bridge/src/rerun_bridge/rerun_ros_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,9 +7,9 @@

void log_imu(
const rerun::RecordingStream& rec, const std::string& entity_path,
const sensor_msgs::Imu::ConstPtr& msg
const sensor_msgs::Imu::ConstPtr& msg, double normalized_timestamp
) {
rec.set_time_seconds("timestamp", msg->header.stamp.toSec());
rec.set_time_seconds("timestamp", normalized_timestamp);

rec.log(entity_path + "/x", rerun::Scalar(msg->linear_acceleration.x));
rec.log(entity_path + "/y", rerun::Scalar(msg->linear_acceleration.y));
Expand All @@ -18,9 +18,9 @@ void log_imu(

void log_image(
const rerun::RecordingStream& rec, const std::string& entity_path,
const sensor_msgs::Image::ConstPtr& msg
const sensor_msgs::Image::ConstPtr& msg, double normalized_timestamp
) {
rec.set_time_seconds("timestamp", msg->header.stamp.toSec());
rec.set_time_seconds("timestamp", normalized_timestamp);

// Depth images are 32-bit float (in meters) or 16-bit uint (in millimeters)
// See: https://ros.org/reps/rep-0118.html
Expand Down Expand Up @@ -48,9 +48,9 @@ void log_image(

void log_pose_stamped(
const rerun::RecordingStream& rec, const std::string& entity_path,
const geometry_msgs::PoseStamped::ConstPtr& msg
const geometry_msgs::PoseStamped::ConstPtr& msg, double normalized_timestamp
) {
rec.set_time_seconds("timestamp", msg->header.stamp.toSec());
rec.set_time_seconds("timestamp", normalized_timestamp);

rec.log(
entity_path,
Expand Down Expand Up @@ -81,7 +81,7 @@ void log_pose_stamped(
void log_tf_message(
const rerun::RecordingStream& rec,
const std::map<std::string, std::string>& tf_frame_to_entity_path,
const tf2_msgs::TFMessage::ConstPtr& msg
const tf2_msgs::TFMessage::ConstPtr& msg, double normalized_timestamp
) {
for (const auto& transform : msg->transforms) {
if (tf_frame_to_entity_path.find(transform.child_frame_id) ==
Expand All @@ -90,7 +90,7 @@ void log_tf_message(
continue;
}

rec.set_time_seconds("timestamp", transform.header.stamp.toSec());
rec.set_time_seconds("timestamp", normalized_timestamp);

rec.log(
tf_frame_to_entity_path.at(transform.child_frame_id),
Expand All @@ -113,9 +113,9 @@ void log_tf_message(

void log_odometry(
const rerun::RecordingStream& rec, const std::string& entity_path,
const nav_msgs::Odometry::ConstPtr& msg
const nav_msgs::Odometry::ConstPtr& msg, double normalized_timestamp
) {
rec.set_time_seconds("timestamp", msg->header.stamp.toSec());
rec.set_time_seconds("timestamp", normalized_timestamp);

rec.log(
entity_path,
Expand All @@ -137,7 +137,7 @@ void log_odometry(

void log_camera_info(
const rerun::RecordingStream& rec, const std::string& entity_path,
const sensor_msgs::CameraInfo::ConstPtr& msg
const sensor_msgs::CameraInfo::ConstPtr& msg, double normalized_timestamp
) {
// Rerun uses column-major order for Mat3x3
const std::array<float, 9> image_from_camera = {
Expand All @@ -160,9 +160,9 @@ void log_camera_info(

void log_transform(
const rerun::RecordingStream& rec, const std::string& entity_path,
const geometry_msgs::TransformStamped& msg
const geometry_msgs::TransformStamped& msg, double normalized_timestamp
) {
rec.set_time_seconds("timestamp", msg.header.stamp.toSec());
rec.set_time_seconds("timestamp", normalized_timestamp);

rec.log(
entity_path,
Expand Down
38 changes: 30 additions & 8 deletions rerun_bridge/src/rerun_bridge/visualizer_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,10 @@ std::string resolve_ros_path(const std::string& path) {
RerunLoggerNode::RerunLoggerNode() {
_rec.spawn().exit_on_failure();

// Initialize timestamp normalization
_time_offset_initialized = false;
_time_offset = 0.0;

// Read additional config from yaml file
// NOTE We're not using the ROS parameter server for this, because roscpp doesn't support
// reading nested data structures.
Expand All @@ -52,6 +56,15 @@ RerunLoggerNode::RerunLoggerNode() {
_read_yaml_config(yaml_path);
}

double RerunLoggerNode::_normalize_timestamp(const ros::Time& stamp) const {
if (!_time_offset_initialized) {
_time_offset = stamp.toSec();
_time_offset_initialized = true;
ROS_INFO("Initialized time offset to %.6f", _time_offset);
}
return stamp.toSec() - _time_offset;
}

/// Convert a topic name to its entity path.
/// If the topic is explicitly mapped to an entity path, use that.
/// Otherwise, the topic name will be automatically converted to a flattened entity path like this:
Expand Down Expand Up @@ -226,7 +239,8 @@ void RerunLoggerNode::_update_tf() const {
try {
auto transform =
_tf_buffer.lookupTransform(parent->second, frame, now - ros::Duration(1.0));
log_transform(_rec, entity_path, transform);
double normalized_timestamp = _normalize_timestamp(now);
log_transform(_rec, entity_path, transform, normalized_timestamp);
} catch (tf2::TransformException& ex) {
ROS_WARN_THROTTLE(
1.0,
Expand All @@ -247,6 +261,7 @@ ros::Subscriber RerunLoggerNode::_create_image_subscriber(const std::string& top
topic,
100,
[&, entity_path, lookup_transform](const sensor_msgs::Image::ConstPtr& msg) {
double normalized_timestamp = _normalize_timestamp(msg->header.stamp);
if (!_root_frame.empty() && lookup_transform) {
try {
auto transform = _tf_buffer.lookupTransform(
Expand All @@ -255,12 +270,12 @@ ros::Subscriber RerunLoggerNode::_create_image_subscriber(const std::string& top
msg->header.stamp,
ros::Duration(0.1)
);
log_transform(_rec, parent_entity_path(entity_path), transform);
log_transform(_rec, parent_entity_path(entity_path), transform, normalized_timestamp);
} catch (tf2::TransformException& ex) {
ROS_WARN("%s", ex.what());
}
}
log_image(_rec, entity_path, msg);
log_image(_rec, entity_path, msg, normalized_timestamp);
}
);
}
Expand All @@ -271,7 +286,10 @@ ros::Subscriber RerunLoggerNode::_create_imu_subscriber(const std::string& topic
return _nh.subscribe<sensor_msgs::Imu>(
topic,
100,
[&, entity_path](const sensor_msgs::Imu::ConstPtr& msg) { log_imu(_rec, entity_path, msg); }
[&, entity_path](const sensor_msgs::Imu::ConstPtr& msg) {
double normalized_timestamp = _normalize_timestamp(msg->header.stamp);
log_imu(_rec, entity_path, msg, normalized_timestamp);
}
);
}

Expand All @@ -282,7 +300,8 @@ ros::Subscriber RerunLoggerNode::_create_pose_stamped_subscriber(const std::stri
topic,
100,
[&, entity_path](const geometry_msgs::PoseStamped::ConstPtr& msg) {
log_pose_stamped(_rec, entity_path, msg);
double normalized_timestamp = _normalize_timestamp(msg->header.stamp);
log_pose_stamped(_rec, entity_path, msg, normalized_timestamp);
}
);
}
Expand All @@ -292,7 +311,8 @@ ros::Subscriber RerunLoggerNode::_create_tf_message_subscriber(const std::string

return _nh
.subscribe<tf2_msgs::TFMessage>(topic, 100, [&](const tf2_msgs::TFMessage::ConstPtr& msg) {
log_tf_message(_rec, _tf_frame_to_entity_path, msg);
double normalized_timestamp = _normalize_timestamp(msg->transforms[0].header.stamp);
log_tf_message(_rec, _tf_frame_to_entity_path, msg, normalized_timestamp);
});
}

Expand All @@ -303,7 +323,8 @@ ros::Subscriber RerunLoggerNode::_create_odometry_subscriber(const std::string&
topic,
100,
[&, entity_path](const nav_msgs::Odometry::ConstPtr& msg) {
log_odometry(_rec, entity_path, msg);
double normalized_timestamp = _normalize_timestamp(msg->header.stamp);
log_odometry(_rec, entity_path, msg, normalized_timestamp);
}
);
}
Expand All @@ -322,7 +343,8 @@ ros::Subscriber RerunLoggerNode::_create_camera_info_subscriber(const std::strin
topic,
100,
[&, entity_path](const sensor_msgs::CameraInfo::ConstPtr& msg) {
log_camera_info(_rec, entity_path, msg);
double normalized_timestamp = _normalize_timestamp(msg->header.stamp);
log_camera_info(_rec, entity_path, msg, normalized_timestamp);
}
);
}
Expand Down
5 changes: 5 additions & 0 deletions rerun_bridge/src/rerun_bridge/visualizer_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,11 @@ class RerunLoggerNode {
float _tf_fixed_rate;
tf2_ros::Buffer _tf_buffer;
tf2_ros::TransformListener _tf_listener{_tf_buffer};

// Timestamp normalization
mutable double _time_offset;
mutable bool _time_offset_initialized;
double _normalize_timestamp(const ros::Time& stamp) const;

void _create_subscribers();
void _update_tf() const;
Expand Down