Skip to content

Feature/rerun 0.24 #21

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Draft
wants to merge 28 commits into
base: main
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
28 commits
Select commit Hold shift + click to select a range
0d1162d
[deps] update rerun-sdk to 0.24.0
blooop Jul 18, 2025
a9f2f9b
remove obsolete rerun urdf-loader
blooop Jul 18, 2025
472dd8c
example works now
blooop Jul 18, 2025
d7822ff
fix transform lookup errors
blooop Jul 18, 2025
d64ec2d
restore old time logging
blooop Jul 18, 2025
ec8c1f7
remove unused comments
blooop Jul 18, 2025
697523f
restore old logging
blooop Jul 18, 2025
cd0d234
restore old formatting
blooop Jul 18, 2025
988664b
use simple scalar logging instead of taking ownership
blooop Jul 18, 2025
6dcd1d3
factor out common code in log_joint_state
blooop Jul 18, 2025
b0f3357
remove comments
blooop Jul 18, 2025
fb72601
remove try catches
blooop Jul 18, 2025
fd596d6
restore yaml to originals
blooop Jul 18, 2025
0d28d60
remove view urdf.sh script
blooop Jul 18, 2025
d9ce9a2
update set_time_seconds -> set_time_timestamp_secs_since_epoch to rem…
blooop Jul 18, 2025
e0a4196
clang format
blooop Jul 18, 2025
2d0f8c5
update depends_on to depends-on to remove deprecation warnings in pix…
blooop Jul 19, 2025
74c6ffc
fix pixi ambiuous version specifier warnings
blooop Jul 19, 2025
f1efae5
update depends_on to depends-on to remove deprecation warnings in pix…
blooop Jul 19, 2025
4b36b88
fix pixi ambiuous version specifier warnings
blooop Jul 19, 2025
ef7c4bc
update pixi.lock
blooop Jul 21, 2025
f07dcfa
update pixi version to 0.49.0 in ci
blooop Jul 21, 2025
b434b65
Merge branch 'feature/pixi-fixes' into feature/rerun-0.24
blooop Jul 21, 2025
7bde89a
fix python and numpy versions
blooop Jul 21, 2025
aade107
update numpy version
blooop Jul 21, 2025
6a18601
restore previous urdf loader
blooop Jul 21, 2025
6f2f5b3
don't reinflate the zip archive
blooop Jul 21, 2025
a194e38
add outputs for rosbag2_storage_mcap and go2_interfaces to avoid nump…
blooop Jul 22, 2025
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
2 changes: 1 addition & 1 deletion .github/workflows/cpp.yml
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ jobs:

- uses: prefix-dev/[email protected]
with:
pixi-version: v0.26.1
pixi-version: v0.49.0
cache: true

- run: pixi run cpp-fmt-check
Expand Down
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ It works by subscribing to all topics with supported types, converting the messa
| --- | --- |
| ![carla](https://github.com/rerun-io/cpp-example-ros2-bridge/assets/9785832/f4e91f4b-18b4-4890-b2cc-ff00880ca65c) | ![go2](https://github.com/rerun-io/cpp-example-ros2-bridge/assets/9785832/2856b5af-d02b-426b-8e23-2cf6f7c2bfd8) |

This example is built for ROS 2. For more ROS examples, also check out the [ROS 2 example](https://www.rerun.io/docs/howto/ros2-nav-turtlebot), the [URDF data-loader](https://github.com/rerun-io/rerun-loader-python-example-urdf), and the [ROS 1 bridge](https://github.com/rerun-io/cpp-example-ros-bridge).
This example is built for ROS 2. For more ROS examples, also check out the [ROS 2 example](https://www.rerun.io/docs/howto/ros2-nav-turtlebot) and the [ROS 1 bridge](https://github.com/rerun-io/cpp-example-ros-bridge). URDF support is now built into Rerun 0.24.0+ natively.

> NOTE: Currently only some of the most common messages are supported (see https://github.com/rerun-io/cpp-example-ros2-bridge/issues/4 for an overview). However, extending to other messages should be straightforward.

Expand Down
55,677 changes: 18,438 additions & 37,239 deletions pixi.lock

Large diffs are not rendered by default.

33 changes: 20 additions & 13 deletions pixi.toml
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ cwd = "."

[tasks.build]
cmd = "colcon build --packages-select rerun_bridge --cmake-args -DCMAKE_BUILD_TYPE=Release -DCMAKE_EXPORT_COMPILE_COMMANDS=ON"
depends_on = ["ws"]
depends-on = ["ws"]
cwd = "humble_ws"

# Get mcap support from source since its not available in robostack channel
Expand All @@ -61,7 +61,9 @@ cmd = """
(test -d src/rosbag2_storage_mcap || git clone https://github.com/ros-tooling/rosbag2_storage_mcap.git src/rosbag2_storage_mcap)
&& colcon build --packages-select mcap_vendor rosbag2_storage_mcap_testdata rosbag2_storage_mcap --cmake-args -DCMAKE_BUILD_TYPE=Release
"""
depends_on = ["ws"]

outputs = ["humble_ws/install/mcap_vendor", "humble_ws/install/rosbag2_storage_mcap"]
depends-on = ["ws"]
cwd = "humble_ws"

# ------------------------------------------------------------------------------------------
Expand All @@ -71,21 +73,21 @@ cwd = "humble_ws"
cmd = "curl -L -C - -O https://storage.googleapis.com/rerun-example-datasets/carla_ros2.zip && unzip carla_ros2.zip"
cwd = "humble_ws/install/rerun_bridge/share/rerun_bridge"
outputs = ["humble_ws/install/rerun_bridge/share/rerun_bridge/carla_ros2"]
depends_on = ["build"]
depends-on = ["build"]

[tasks.carla_example]
cmd = "bash -c 'source ./install/local_setup.bash && ros2 launch rerun_bridge carla_example.launch'"
depends_on = ["build", "rerun_viewer", "carla_example_data"]
depends-on = ["build", "rerun_viewer", "carla_example_data"]
cwd = "humble_ws"

# ------------------------------------------------------------------------------------------
# Go2 example:

[tasks.go2_example_data]
cmd = "curl -L -C - -O https://storage.googleapis.com/rerun-example-datasets/go2_ros2.zip && unzip go2_ros2.zip"
cmd = "curl -L -C - -O https://storage.googleapis.com/rerun-example-datasets/go2_ros2.zip && unzip -n go2_ros2.zip"
cwd = "humble_ws/install/rerun_bridge/share/rerun_bridge"
outputs = ["humble_ws/install/rerun_bridge/share/rerun_bridge/go2_ros2"]
depends_on = ["build"]
depends-on = ["build"]

# Get the go2_ros2_sdk package
#
Expand All @@ -95,12 +97,14 @@ cmd = """
(test -d src/go2_ros2_sdk || git clone --recurse-submodules https://github.com/abizovnuralem/go2_ros2_sdk.git src/go2_ros2_sdk)
&& colcon build --packages-select unitree_go go2_interfaces go2_robot_sdk --cmake-args -DCMAKE_BUILD_TYPE=Release
"""
# Only track go2_interfaces output to prevent rebuilds that cause numpy header compilation errors
outputs = ["humble_ws/install/go2_interfaces"]
cwd = "humble_ws"
depends_on = ["ws"]
depends-on = ["ws"]

[tasks.go2_example]
cmd = "bash -c 'source ./install/local_setup.bash && ros2 launch rerun_bridge go2_example.launch'"
depends_on = [
depends-on = [
"build",
"go2_example_data",
"go2_ros2_sdk",
Expand All @@ -110,21 +114,24 @@ depends_on = [
]
cwd = "humble_ws"

# Install Rerun and URDF loader manually via pip3, this should be replaced with direct pypi dependencies in the future.
# Install Rerun 0.24.0 with native URDF support
[tasks.rerun_viewer]
cmd = "pip install rerun-sdk==0.23.4"
cmd = "pip install rerun-sdk==0.24.0"


[tasks.rerun_urdf_loader]
cmd = "pip install git+https://github.com/rerun-io/rerun-loader-python-example-urdf.git"

[dependencies]
pip = ">=24.0,<25" # To install rerun-sdk and rerun-loader-python-example-urdf
python = "3.11.*"
numpy = "1.26.*" #1.26.x fails during go2_interface compile
pip = ">=24.0,<25" # To install rerun-sdk

# C++ build-tools:
cmake = "3.27.6"
cmake = "==3.27.6"
clang-tools = ">=15,<16" # clang-format
cxx-compiler = "1.6.0.*"
ninja = "1.11.1"
ninja = "==1.11.1"

# ROS 2 build-tools:
colcon-core = ">=0.16.0,<0.17"
Expand Down
2 changes: 1 addition & 1 deletion rerun_bridge/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ find_package(OpenCV REQUIRED)
find_package(yaml-cpp REQUIRED)

include(FetchContent)
FetchContent_Declare(rerun_sdk URL https://github.com/rerun-io/rerun/releases/download/0.23.4/rerun_cpp_sdk.zip)
FetchContent_Declare(rerun_sdk URL https://github.com/rerun-io/rerun/releases/download/0.24.0/rerun_cpp_sdk.zip)
FetchContent_MakeAvailable(rerun_sdk)

# setup targets (has to be done before ament_package call)
Expand Down
6 changes: 6 additions & 0 deletions rerun_bridge/include/rerun_bridge/rerun_ros_interface.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
#include <sensor_msgs/msg/camera_info.hpp>
#include <sensor_msgs/msg/image.hpp>
#include <sensor_msgs/msg/imu.hpp>
#include <sensor_msgs/msg/joint_state.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <tf2_msgs/msg/tf_message.hpp>

Expand Down Expand Up @@ -66,3 +67,8 @@ void log_point_cloud2(
const rerun::RecordingStream& rec, const std::string& entity_path,
const sensor_msgs::msg::PointCloud2::ConstSharedPtr& msg, const PointCloud2Options& options
);

void log_joint_state(
const rerun::RecordingStream& rec, const std::string& entity_path,
const sensor_msgs::msg::JointState::ConstSharedPtr& msg
);
47 changes: 37 additions & 10 deletions rerun_bridge/src/rerun_bridge/rerun_ros_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -91,21 +91,21 @@ void log_imu(
const rerun::RecordingStream& rec, const std::string& entity_path,
const sensor_msgs::msg::Imu::ConstSharedPtr& msg
) {
rec.set_time_seconds(
rec.set_time_timestamp_secs_since_epoch(
"timestamp",
rclcpp::Time(msg->header.stamp.sec, msg->header.stamp.nanosec).seconds()
);

rec.log(entity_path + "/x", rerun::Scalar(msg->linear_acceleration.x));
rec.log(entity_path + "/y", rerun::Scalar(msg->linear_acceleration.y));
rec.log(entity_path + "/z", rerun::Scalar(msg->linear_acceleration.z));
rec.log(entity_path + "/x", rerun::Scalars(msg->linear_acceleration.x));
rec.log(entity_path + "/y", rerun::Scalars(msg->linear_acceleration.y));
rec.log(entity_path + "/z", rerun::Scalars(msg->linear_acceleration.z));
}

void log_image(
const rerun::RecordingStream& rec, const std::string& entity_path,
const sensor_msgs::msg::Image::ConstSharedPtr& msg, const ImageOptions& options
) {
rec.set_time_seconds(
rec.set_time_timestamp_secs_since_epoch(
"timestamp",
rclcpp::Time(msg->header.stamp.sec, msg->header.stamp.nanosec).seconds()
);
Expand Down Expand Up @@ -143,7 +143,7 @@ void log_pose_stamped(
const rerun::RecordingStream& rec, const std::string& entity_path,
const geometry_msgs::msg::PoseStamped::ConstSharedPtr& msg
) {
rec.set_time_seconds(
rec.set_time_timestamp_secs_since_epoch(
"timestamp",
rclcpp::Time(msg->header.stamp.sec, msg->header.stamp.nanosec).seconds()
);
Expand Down Expand Up @@ -191,7 +191,7 @@ void log_tf_message(
continue;
}

rec.set_time_seconds(
rec.set_time_timestamp_secs_since_epoch(
"timestamp",
rclcpp::Time(transform.header.stamp.sec, transform.header.stamp.nanosec).seconds()
);
Expand Down Expand Up @@ -219,7 +219,7 @@ void log_odometry(
const rerun::RecordingStream& rec, const std::string& entity_path,
const nav_msgs::msg::Odometry::ConstSharedPtr& msg
) {
rec.set_time_seconds(
rec.set_time_timestamp_secs_since_epoch(
"timestamp",
rclcpp::Time(msg->header.stamp.sec, msg->header.stamp.nanosec).seconds()
);
Expand Down Expand Up @@ -269,7 +269,7 @@ void log_transform(
const rerun::RecordingStream& rec, const std::string& entity_path,
const geometry_msgs::msg::TransformStamped::ConstSharedPtr& msg
) {
rec.set_time_seconds(
rec.set_time_timestamp_secs_since_epoch(
"timestamp",
rclcpp::Time(msg->header.stamp.sec, msg->header.stamp.nanosec).seconds()
);
Expand All @@ -296,7 +296,7 @@ void log_point_cloud2(
const rerun::RecordingStream& rec, const std::string& entity_path,
const sensor_msgs::msg::PointCloud2::ConstSharedPtr& msg, const PointCloud2Options& options
) {
rec.set_time_seconds(
rec.set_time_timestamp_secs_since_epoch(
"timestamp",
rclcpp::Time(msg->header.stamp.sec, msg->header.stamp.nanosec).seconds()
);
Expand Down Expand Up @@ -403,3 +403,30 @@ void log_point_cloud2(

rec.log(entity_path, rerun::Points3D(points).with_colors(colors));
}

void log_joint_state(
const rerun::RecordingStream& rec, const std::string& entity_path,
const sensor_msgs::msg::JointState::ConstSharedPtr& msg
) {
// Set timestamp if available, otherwise skip timestamp logging to use current time
if (msg->header.stamp.sec != 0 || msg->header.stamp.nanosec != 0) {
rec.set_time_timestamp_secs_since_epoch(
"timestamp",
rclcpp::Time(msg->header.stamp.sec, msg->header.stamp.nanosec).seconds()
);
}

// Helper lambda to log joint data arrays
auto log_joint_array = [&](const std::vector<double>& values, const std::string& suffix) {
if (!values.empty() && values.size() == msg->name.size()) {
for (size_t i = 0; i < msg->name.size(); ++i) {
rec.log(entity_path + "/" + suffix + "/" + msg->name[i], rerun::Scalars(values[i]));
}
}
};

// Log joint data using the helper lambda
log_joint_array(msg->position, "joint_positions");
log_joint_array(msg->velocity, "joint_velocities");
log_joint_array(msg->effort, "joint_efforts");
}
37 changes: 37 additions & 0 deletions rerun_bridge/src/rerun_bridge/visualizer_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -314,6 +314,9 @@ void RerunLoggerNode::_create_subscriptions() {
} else if (topic_type == "sensor_msgs/msg/PointCloud2") {
_topic_to_subscription[topic_name] =
_create_point_cloud2_subscription(topic_name, topic_options);
} else if (topic_type == "sensor_msgs/msg/JointState") {
_topic_to_subscription[topic_name] =
_create_joint_state_subscription(topic_name, topic_options);
}
}
}
Expand Down Expand Up @@ -560,6 +563,40 @@ std::shared_ptr<rclcpp::Subscription<sensor_msgs::msg::PointCloud2>>
);
}

std::shared_ptr<rclcpp::Subscription<sensor_msgs::msg::JointState>>
RerunLoggerNode::_create_joint_state_subscription(
const std::string& topic, const TopicOptions& topic_options
) {
std::string entity_path = _resolve_entity_path(topic, topic_options);
bool lookup_transform = false; // Joint states don't need coordinate transformations
bool restamp = false;
if (topic_options.find("restamp") != topic_options.end()) {
restamp = topic_options.at("restamp").as<bool>();
}

rclcpp::SubscriptionOptions subscription_options;
subscription_options.callback_group = _parallel_callback_group;

RCLCPP_INFO(
this->get_logger(),
"Subscribing to JointState topic %s, logging to entity path %s",
topic.c_str(),
entity_path.c_str()
);

return this->create_subscription<sensor_msgs::msg::JointState>(
topic,
1000,
[&, entity_path, lookup_transform, restamp](
const sensor_msgs::msg::JointState::SharedPtr msg
) {
_handle_msg_header(restamp, lookup_transform, entity_path, msg->header);
log_joint_state(_rec, entity_path, msg);
},
subscription_options
);
}

void RerunLoggerNode::_handle_msg_header(
bool restamp, bool lookup_transform, const std::string& entity_path,
std_msgs::msg::Header& header
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 @@ -13,6 +13,7 @@
#include <sensor_msgs/msg/camera_info.hpp>
#include <sensor_msgs/msg/image.hpp>
#include <sensor_msgs/msg/imu.hpp>
#include <sensor_msgs/msg/joint_state.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <tf2_msgs/msg/tf_message.hpp>

Expand Down Expand Up @@ -87,4 +88,8 @@ class RerunLoggerNode : public rclcpp::Node {
_create_point_cloud2_subscription(
const std::string& topic, const TopicOptions& topic_options
);
std::shared_ptr<rclcpp::Subscription<sensor_msgs::msg::JointState>>
_create_joint_state_subscription(
const std::string& topic, const TopicOptions& topic_options
);
};
Loading