Skip to content

Commit 472dd8c

Browse files
committed
example works now
1 parent a9f2f9b commit 472dd8c

File tree

10 files changed

+164
-17
lines changed

10 files changed

+164
-17
lines changed

README.md

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -8,7 +8,7 @@ It works by subscribing to all topics with supported types, converting the messa
88
| --- | --- |
99
| ![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) |
1010

11-
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).
11+
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.
1212

1313
> 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.
1414

pixi.toml

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -109,13 +109,12 @@ depends_on = [
109109
]
110110
cwd = "humble_ws"
111111

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

116-
117116
[dependencies]
118-
pip = ">=24.0,<25" # To install rerun-sdk and rerun-loader-python-example-urdf
117+
pip = ">=24.0,<25" # To install rerun-sdk
119118

120119
# C++ build-tools:
121120
cmake = "3.27.6"

rerun_bridge/CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,7 @@ find_package(OpenCV REQUIRED)
2222
find_package(yaml-cpp REQUIRED)
2323

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

2828
# setup targets (has to be done before ament_package call)

rerun_bridge/include/rerun_bridge/rerun_ros_interface.hpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@
99
#include <sensor_msgs/msg/camera_info.hpp>
1010
#include <sensor_msgs/msg/image.hpp>
1111
#include <sensor_msgs/msg/imu.hpp>
12+
#include <sensor_msgs/msg/joint_state.hpp>
1213
#include <sensor_msgs/msg/point_cloud2.hpp>
1314
#include <tf2_msgs/msg/tf_message.hpp>
1415

@@ -66,3 +67,8 @@ void log_point_cloud2(
6667
const rerun::RecordingStream& rec, const std::string& entity_path,
6768
const sensor_msgs::msg::PointCloud2::ConstSharedPtr& msg, const PointCloud2Options& options
6869
);
70+
71+
void log_joint_state(
72+
const rerun::RecordingStream& rec, const std::string& entity_path,
73+
const sensor_msgs::msg::JointState::ConstSharedPtr& msg
74+
);

rerun_bridge/launch/carla_example_params.yaml

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -37,5 +37,7 @@ topic_options:
3737
/carla/ego_vehicle/rgb_right/camera_info:
3838
entity_path: /map/ego_vehicle/ego_vehicle/rgb_right
3939
urdf:
40+
# URDF support using Rerun 0.24.0+ native URDF loader
41+
# Leave file_path empty if no URDF is available (e.g., for Carla simulation)
4042
file_path: ""
4143
entity_path: "odom"

rerun_bridge/launch/go2_example_params.yaml

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -51,5 +51,9 @@ topic_options:
5151
/go2_camera/color/image:
5252
entity_path: /map/odom/base_link/Head_upper/front_camera/image
5353
urdf:
54+
# URDF support using Rerun 0.24.0+ native URDF loader
55+
# Supports ROS package:// paths which are automatically resolved when ROS2 environment is sourced
56+
# Note: To view this URDF standalone with `rerun`, use:
57+
# cd humble_ws && source ./install/local_setup.bash && rerun install/go2_robot_sdk/share/go2_robot_sdk/urdf/go2.urdf
5458
file_path: "package://go2_robot_sdk/urdf/go2.urdf"
5559
entity_path: "/" # the root of this urdf is map

rerun_bridge/src/rerun_bridge/rerun_ros_interface.cpp

Lines changed: 50 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -91,21 +91,21 @@ void log_imu(
9191
const rerun::RecordingStream& rec, const std::string& entity_path,
9292
const sensor_msgs::msg::Imu::ConstSharedPtr& msg
9393
) {
94-
rec.set_time_seconds(
94+
rec.set_time_timestamp_secs_since_epoch(
9595
"timestamp",
9696
rclcpp::Time(msg->header.stamp.sec, msg->header.stamp.nanosec).seconds()
9797
);
9898

99-
rec.log(entity_path + "/x", rerun::Scalar(msg->linear_acceleration.x));
100-
rec.log(entity_path + "/y", rerun::Scalar(msg->linear_acceleration.y));
101-
rec.log(entity_path + "/z", rerun::Scalar(msg->linear_acceleration.z));
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)})));
102102
}
103103

104104
void log_image(
105105
const rerun::RecordingStream& rec, const std::string& entity_path,
106106
const sensor_msgs::msg::Image::ConstSharedPtr& msg, const ImageOptions& options
107107
) {
108-
rec.set_time_seconds(
108+
rec.set_time_timestamp_secs_since_epoch(
109109
"timestamp",
110110
rclcpp::Time(msg->header.stamp.sec, msg->header.stamp.nanosec).seconds()
111111
);
@@ -143,7 +143,7 @@ void log_pose_stamped(
143143
const rerun::RecordingStream& rec, const std::string& entity_path,
144144
const geometry_msgs::msg::PoseStamped::ConstSharedPtr& msg
145145
) {
146-
rec.set_time_seconds(
146+
rec.set_time_timestamp_secs_since_epoch(
147147
"timestamp",
148148
rclcpp::Time(msg->header.stamp.sec, msg->header.stamp.nanosec).seconds()
149149
);
@@ -191,7 +191,7 @@ void log_tf_message(
191191
continue;
192192
}
193193

194-
rec.set_time_seconds(
194+
rec.set_time_timestamp_secs_since_epoch(
195195
"timestamp",
196196
rclcpp::Time(transform.header.stamp.sec, transform.header.stamp.nanosec).seconds()
197197
);
@@ -219,7 +219,7 @@ void log_odometry(
219219
const rerun::RecordingStream& rec, const std::string& entity_path,
220220
const nav_msgs::msg::Odometry::ConstSharedPtr& msg
221221
) {
222-
rec.set_time_seconds(
222+
rec.set_time_timestamp_secs_since_epoch(
223223
"timestamp",
224224
rclcpp::Time(msg->header.stamp.sec, msg->header.stamp.nanosec).seconds()
225225
);
@@ -269,7 +269,7 @@ void log_transform(
269269
const rerun::RecordingStream& rec, const std::string& entity_path,
270270
const geometry_msgs::msg::TransformStamped::ConstSharedPtr& msg
271271
) {
272-
rec.set_time_seconds(
272+
rec.set_time_timestamp_secs_since_epoch(
273273
"timestamp",
274274
rclcpp::Time(msg->header.stamp.sec, msg->header.stamp.nanosec).seconds()
275275
);
@@ -296,7 +296,7 @@ void log_point_cloud2(
296296
const rerun::RecordingStream& rec, const std::string& entity_path,
297297
const sensor_msgs::msg::PointCloud2::ConstSharedPtr& msg, const PointCloud2Options& options
298298
) {
299-
rec.set_time_seconds(
299+
rec.set_time_timestamp_secs_since_epoch(
300300
"timestamp",
301301
rclcpp::Time(msg->header.stamp.sec, msg->header.stamp.nanosec).seconds()
302302
);
@@ -403,3 +403,43 @@ void log_point_cloud2(
403403

404404
rec.log(entity_path, rerun::Points3D(points).with_colors(colors));
405405
}
406+
407+
void log_joint_state(
408+
const rerun::RecordingStream& rec, const std::string& entity_path,
409+
const sensor_msgs::msg::JointState::ConstSharedPtr& msg
410+
) {
411+
// Log joint angles as time series scalars using the new Rerun 0.24.0 API
412+
// This follows the pattern from the Rust and Python examples
413+
for (size_t i = 0; i < msg->name.size() && i < msg->position.size(); ++i) {
414+
const std::string& joint_name = msg->name[i];
415+
double joint_position = msg->position[i];
416+
417+
// Log each joint angle as a separate time series scalar
418+
// Entity path format: /joint_angles/joint_name
419+
std::string joint_entity_path = entity_path + "/joint_angles/" + joint_name;
420+
421+
rec.log(joint_entity_path, rerun::Scalars(rerun::Collection<rerun::components::Scalar>::take_ownership({rerun::components::Scalar(joint_position)})));
422+
}
423+
424+
// Also log joint velocities if available
425+
if (!msg->velocity.empty() && msg->velocity.size() == msg->name.size()) {
426+
for (size_t i = 0; i < msg->name.size(); ++i) {
427+
const std::string& joint_name = msg->name[i];
428+
double joint_velocity = msg->velocity[i];
429+
430+
std::string velocity_entity_path = entity_path + "/joint_velocities/" + joint_name;
431+
rec.log(velocity_entity_path, rerun::Scalars(rerun::Collection<rerun::components::Scalar>::take_ownership({rerun::components::Scalar(joint_velocity)})));
432+
}
433+
}
434+
435+
// Log joint efforts/torques if available
436+
if (!msg->effort.empty() && msg->effort.size() == msg->name.size()) {
437+
for (size_t i = 0; i < msg->name.size(); ++i) {
438+
const std::string& joint_name = msg->name[i];
439+
double joint_effort = msg->effort[i];
440+
441+
std::string effort_entity_path = entity_path + "/joint_efforts/" + joint_name;
442+
rec.log(effort_entity_path, rerun::Scalars(rerun::Collection<rerun::components::Scalar>::take_ownership({rerun::components::Scalar(joint_effort)})));
443+
}
444+
}
445+
}

rerun_bridge/src/rerun_bridge/visualizer_node.cpp

Lines changed: 64 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -242,11 +242,36 @@ void RerunLoggerNode::_read_yaml_config(std::string yaml_path) {
242242
if (urdf_file_path.size()) {
243243
RCLCPP_INFO(
244244
this->get_logger(),
245-
"Logging URDF from file path %s",
245+
"Logging URDF from file path %s using native Rerun 0.24.0+ URDF loader",
246246
urdf_file_path.c_str()
247247
);
248-
_rec.log_file_from_path(urdf_file_path, urdf_entity_path, true);
248+
try {
249+
// Log URDF file using Rerun 0.24.0+ native URDF support
250+
// The static=true parameter ensures the URDF is logged as a static resource
251+
_rec.log_file_from_path(urdf_file_path, urdf_entity_path, true);
252+
RCLCPP_INFO(
253+
this->get_logger(),
254+
"Successfully logged URDF file to entity path: %s",
255+
urdf_entity_path.empty() ? "default" : urdf_entity_path.c_str()
256+
);
257+
} catch (const std::exception& e) {
258+
RCLCPP_ERROR(
259+
this->get_logger(),
260+
"Failed to log URDF file: %s",
261+
e.what()
262+
);
263+
}
264+
} else {
265+
RCLCPP_WARN(
266+
this->get_logger(),
267+
"URDF file path resolved to empty string"
268+
);
249269
}
270+
} else {
271+
RCLCPP_WARN(
272+
this->get_logger(),
273+
"URDF configuration found but no file_path specified"
274+
);
250275
}
251276
}
252277
}
@@ -314,6 +339,9 @@ void RerunLoggerNode::_create_subscriptions() {
314339
} else if (topic_type == "sensor_msgs/msg/PointCloud2") {
315340
_topic_to_subscription[topic_name] =
316341
_create_point_cloud2_subscription(topic_name, topic_options);
342+
} else if (topic_type == "sensor_msgs/msg/JointState") {
343+
_topic_to_subscription[topic_name] =
344+
_create_joint_state_subscription(topic_name, topic_options);
317345
}
318346
}
319347
}
@@ -560,6 +588,40 @@ std::shared_ptr<rclcpp::Subscription<sensor_msgs::msg::PointCloud2>>
560588
);
561589
}
562590

591+
std::shared_ptr<rclcpp::Subscription<sensor_msgs::msg::JointState>>
592+
RerunLoggerNode::_create_joint_state_subscription(
593+
const std::string& topic, const TopicOptions& topic_options
594+
) {
595+
std::string entity_path = _resolve_entity_path(topic, topic_options);
596+
bool lookup_transform = (topic_options.find("entity_path") == topic_options.end());
597+
bool restamp = false;
598+
if (topic_options.find("restamp") != topic_options.end()) {
599+
restamp = topic_options.at("restamp").as<bool>();
600+
}
601+
602+
rclcpp::SubscriptionOptions subscription_options;
603+
subscription_options.callback_group = _parallel_callback_group;
604+
605+
RCLCPP_INFO(
606+
this->get_logger(),
607+
"Subscribing to JointState topic %s, logging to entity path %s",
608+
topic.c_str(),
609+
entity_path.c_str()
610+
);
611+
612+
return this->create_subscription<sensor_msgs::msg::JointState>(
613+
topic,
614+
1000,
615+
[&, entity_path, lookup_transform, restamp](
616+
const sensor_msgs::msg::JointState::SharedPtr msg
617+
) {
618+
_handle_msg_header(restamp, lookup_transform, entity_path, msg->header);
619+
log_joint_state(_rec, entity_path, msg);
620+
},
621+
subscription_options
622+
);
623+
}
624+
563625
void RerunLoggerNode::_handle_msg_header(
564626
bool restamp, bool lookup_transform, const std::string& entity_path,
565627
std_msgs::msg::Header& header

rerun_bridge/src/rerun_bridge/visualizer_node.hpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@
1313
#include <sensor_msgs/msg/camera_info.hpp>
1414
#include <sensor_msgs/msg/image.hpp>
1515
#include <sensor_msgs/msg/imu.hpp>
16+
#include <sensor_msgs/msg/joint_state.hpp>
1617
#include <sensor_msgs/msg/point_cloud2.hpp>
1718
#include <tf2_msgs/msg/tf_message.hpp>
1819

@@ -87,4 +88,8 @@ class RerunLoggerNode : public rclcpp::Node {
8788
_create_point_cloud2_subscription(
8889
const std::string& topic, const TopicOptions& topic_options
8990
);
91+
std::shared_ptr<rclcpp::Subscription<sensor_msgs::msg::JointState>>
92+
_create_joint_state_subscription(
93+
const std::string& topic, const TopicOptions& topic_options
94+
);
9095
};

scripts/view_urdf.sh

Lines changed: 29 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,29 @@
1+
#!/bin/bash
2+
# Convenience script to view URDF files with Rerun in ROS2 environment
3+
4+
if [ $# -eq 0 ]; then
5+
echo "Usage: $0 <urdf_file_path>"
6+
echo "Example: $0 package://go2_robot_sdk/urdf/go2.urdf"
7+
echo " $0 install/go2_robot_sdk/share/go2_robot_sdk/urdf/go2.urdf"
8+
exit 1
9+
fi
10+
11+
URDF_PATH="$1"
12+
13+
# Change to the ROS workspace directory
14+
cd "$(dirname "$0")/../humble_ws" || exit 1
15+
16+
# Source the ROS2 environment
17+
source ./install/local_setup.bash
18+
19+
# If it's a package:// URI, convert it to a relative path
20+
if [[ "$URDF_PATH" == package://* ]]; then
21+
# Extract package name and path from package://package_name/path
22+
PACKAGE_PATH="${URDF_PATH#package://}"
23+
PACKAGE_NAME="${PACKAGE_PATH%%/*}"
24+
RELATIVE_PATH="${PACKAGE_PATH#*/}"
25+
URDF_PATH="install/${PACKAGE_NAME}/share/${PACKAGE_NAME}/${RELATIVE_PATH}"
26+
fi
27+
28+
echo "Loading URDF: $URDF_PATH"
29+
rerun "$URDF_PATH"

0 commit comments

Comments
 (0)