A comprehensive ROS2 client library for interfacing with the Hammerhead stereo vision system
- Overview
- Quick Start
- Message Types & Topics
- Project Structure
- Examples & Tutorials
- 3D Coordinate System & Point Cloud Conversion
- API Reference
- Best Practices & Tips
The Hammerhead system is a high-performance stereo vision processing unit that publishes various types of data over ROS2. This library provides easy-to-use APIs for receiving and processing:
- Stereo Images - Raw and rectified left/right camera feeds
- Depth Data - Disparity maps and color-blended depth images
- Point Clouds - 3D point cloud data with or without RGB information
- Obstacle Detection - Real-time obstacle data with bounding boxes
- Camera Control - Parameter adjustment and recording control
You can also use the Topbot Publisher examples to learn how to send messages to Hammerhead for processing.
| Feature | Description |
|---|---|
| 🐍 Python Ready | Complete Python packages with examples and utilities |
| ⚡ High Performance C++ | Optimized C++ implementation for real-time applications |
| 🔌 ROS2 Native | Full ROS2 integration with standard message types |
# Get the Hammerhead ROS2 repository
git clone git@github.com:nodarhub/hammerhead_ros2.git
# If you received the HDK with version X.X.X, you can check out the corresponding tag (skip this step if you want the latest version):
git checkout X.X.X
# Make sure that the submodules are up to date
git submodule update --init --recursive# Build the workspace
cd hammerhead_ros2
colcon build
# Source the workspace
source install/setup.bash
# IMPORTANT!: Load the DDS transport config
# See "DDS Transport Configuration" section below.
# If you are seeing bad throughput over UDP, check your buffer sizes:
# sysctl net.core.rmem_max net.core.wmem_max
export FASTRTPS_DEFAULT_PROFILES_FILE=$(pwd)/config/fastdds.xml
# View live left raw image from Hammerhead
ros2 run image_viewer image_viewer /nodar/left/image_raw
# Generate point cloud data and save to rosbag
ros2 run generate_rosbag2 generate_rosbag2
# Record obstacle detection data
ros2 run obstacle_data_recorder obstacle_data_recorderCorrect DDS configuration is one of the most important steps you can take to get Ros2 running smoothly. Using the Ros2 defaults, a system that is capable of 20fps can see performance drop under 1fps! See "DDS Transport Configuration" section below on how to tune this.
The convenience scripts compile.sh and clean.sh build and clean all the examples while making sure that all the
build artifacts always remain in the same place.
# Build all examples
./compile.sh
# Clean build artifacts
./clean.shHammerhead publishes data using standard ROS2 message types over predefined topics:
| Topic | Description | Message Type |
|---|---|---|
/nodar/left/image_raw |
Raw left camera feed | sensor_msgs/Image |
/nodar/right/image_raw |
Raw right camera feed | sensor_msgs/Image |
/nodar/left/image_rect |
Rectified left image | sensor_msgs/Image |
/nodar/right/image_rect |
Rectified right image | sensor_msgs/Image |
/nodar/disparity |
Disparity map (Q12.4 format) | sensor_msgs/Image |
/nodar/color_blended_depth/image_raw |
Color-coded depth visualization | sensor_msgs/Image |
/nodar/topbot_raw |
Raw topbot image (left is top-half, right is bottom-half) | sensor_msgs/Image |
/nodar/topbot_rect |
Rectified topbot image (left is top-half, right is bottom-half) | sensor_msgs/Image |
/nodar/confidence_map |
Confidence map | sensor_msgs/Image |
| Topic | Description | Message Type |
|---|---|---|
/nodar/point_cloud |
3D point cloud data (XYZ) | sensor_msgs/PointCloud2 |
/nodar/point_cloud_rgb |
3D point cloud data with RGB color | sensor_msgs/PointCloud2 |
/nodar/point_cloud_soup |
Bandwidth-efficient point cloud representation | hammerhead_msgs/PointCloudSoup |
/nodar/obstacle |
Obstacle detection data | hammerhead_msgs/ObstacleData |
| Topic | Description | Message Type |
|---|---|---|
/nodar/camera_param |
Camera parameter control | hammerhead_msgs/CameraParam |
/nodar/recording |
Recording on/off control | std_msgs/Bool |
The hammerhead_msgs folder contains custom message definitions for Hammerhead-specific data types like obstacle detection and camera parameters.
The examples folder contains comprehensive examples that demonstrate how to interact with Hammerhead using ROS2. We envision that you will use these examples as a jumping-off point for your application.
We suggest that you start by examining the code and README's in the individual example directories for more details about what each example does.
Python examples provide easy-to-use scripts for common Hammerhead integration tasks.
- Image Viewer - Real-time OpenCV viewer for stereo images, disparity maps, and depth data
- Generate ROS Bag - Generate point cloud data and save to ROS2 bag files
- Point Cloud Generator - Generate 3D point clouds from stereo data
- Obstacle Data Recorder - Record obstacle detection data
- Topbot Publisher - Publish stereo topbot images from disk to Hammerhead over ROS2
- Camera Parameter Control - Real-time camera parameter adjustment
High-performance C++ implementations for real-time applications and system integration.
- Image Viewer - Real-time OpenCV viewer for stereo images, disparity maps, and depth data
- Generate ROS Bag - Generate point cloud data and save to ROS2 bag files
- Point Cloud Generator - Generate 3D point clouds from stereo data
- Obstacle Data Recorder - Record obstacle detection data
- Topbot Publisher - Publish stereo topbot images from disk to Hammerhead over ROS2
- Camera Parameter Control - Real-time camera parameter adjustment
- Start with Image Viewer to verify camera feeds
- Use Generate ROS Bag to capture datasets
- Process images with custom algorithms
- Subscribe to point cloud topics to get 3D data
- Use Point Cloud Generator to create custom point clouds
- Process with 3D algorithms
- Integrate with navigation or mapping frameworks
- Use Obstacle Data Recorder to understand data format
- Implement real-time processing of obstacle messages
- Integrate with path planning or control systems
- Add custom filtering or tracking algorithms
Hammerhead follows standard stereo reconstruction principles for converting disparity to 3D point clouds:
The disparity is in Q12.4 format. We scale the disparity by 1 / 16.0 to get the disparity in float32 format:
disparity_scaled = disparity.astype(np.float32) / 16.0The scaled disparity map is reprojected into 3D space using OpenCV's cv2.reprojectImageTo3D() and a 4×4 reprojection
matrix Q:
# Important: Negate the last row for correct coordinate frame
Q_corrected = Q.copy()
Q_corrected[3, :] = -Q_corrected[3, :]
# Reproject to 3D
points_3d = cv2.reprojectImageTo3D(disparity_scaled, Q_corrected)A negative translation vector (Tx < 0) is used when creating the Q matrix to conform to the definition in OpenCV. This
ensures that the point cloud is generated in a consistent right-handed coordinate frame. As a result, the entire last
row of Q must be negated before passing to the cv2.reprojectImageTo3D() call.
This conversion scheme has been used in the following examples:
- Generate ROS Bag - C++ point cloud generation
- Point Cloud Generator - C++ real-time point cloud processing
- Generate ROS Bag - Python point cloud generation
- Point Cloud Generator - Python real-time point cloud processing
All Hammerhead ROS2 messages use standard ROS2 message types where possible, with custom messages defined in hammerhead_msgs.
Used for all image data including raw stereo images, rectified images, and disparity maps.
#include <sensor_msgs/msg/image.hpp>
#include <rclcpp/rclcpp.hpp>
class ImageSubscriber : public rclcpp::Node
{
public:
ImageSubscriber() : Node("image_subscriber")
{
subscription_ = this->create_subscription<sensor_msgs::msg::Image>(
"/nodar/left/image_raw", 10,
std::bind(&ImageSubscriber::image_callback, this, std::placeholders::_1));
}
private:
void image_callback(const sensor_msgs::msg::Image::SharedPtr msg)
{
// Process image data
RCLCPP_INFO(this->get_logger(), "Received image: %dx%d", msg->width, msg->height);
}
rclcpp::Subscription<sensor_msgs::msg::Image>::SharedPtr subscription_;
};Contains real-time obstacle detection information with bounding boxes and velocity vectors.
#include <hammerhead_msgs/msg/obstacle_data.hpp>
#include <rclcpp/rclcpp.hpp>
class ObstacleSubscriber : public rclcpp::Node
{
public:
ObstacleSubscriber() : Node("obstacle_subscriber")
{
subscription_ = this->create_subscription<hammerhead_msgs::msg::ObstacleData>(
"/nodar/obstacle", 10,
std::bind(&ObstacleSubscriber::obstacle_callback, this, std::placeholders::_1));
}
private:
void obstacle_callback(const hammerhead_msgs::msg::ObstacleData::SharedPtr msg)
{
// Process obstacle data
for (const auto& obstacle : msg->obstacles) {
RCLCPP_INFO(this->get_logger(), "Obstacle detected with %zu points",
obstacle.bounding_box.points.size());
}
}
rclcpp::Subscription<hammerhead_msgs::msg::ObstacleData>::SharedPtr subscription_;
};A bandwidth-efficient representation of point cloud data. Instead of transmitting a full PointCloud2 message, the PointCloudSoup contains the rectified image, disparity map, and calibration parameters needed to reconstruct the point cloud on the subscriber side. This can use a fraction of the bandwidth compared to a full point cloud.
To enable this topic, set publish_point_cloud_type = 5 in the master configuration.
Message fields:
header— Standard ROS2 headerrectified— Rectified left image (sensor_msgs/Image)disparity— Disparity map in Q12.4 format (sensor_msgs/Image)baseline— Stereo baseline distancefocal_length— Camera focal lengthdisparity_to_depth4x4— 4x4 reprojection matrixrotation_disparity_to_raw_cam— 3x3 rotation from disparity frame to raw camera framerotation_world_to_raw_cam— 3x3 rotation from world frame to raw camera frame
For complete examples that subscribe to PointCloudSoup and reconstruct a full PointCloud2, see:
When sending or receiving large images (e.g. full-resolution topbot stereo pairs),
the ROS2 middleware is almost always problematic.
We have tried several different DDS suppliers,
and our conclusion is that the default middleware is
sufficient as long as you tune it for high-throughput image transfer.
The easiest way we have found to do this is to use the XML profiles we include in the config/ folder.
In the terminal where hammerhead runs AND the terminal where the sender/reciever runs, you should run this command first:
export FASTRTPS_DEFAULT_PROFILES_FILE=/path/to/config/fastdds.xml- If sending and receiving messages on the same machine, you should to use shared memory, not the networking stack. The default shared memory segment seems to be tuned for fast, small messages. The aforementioned XML increases it by orders of magnitude.
- If you are sending over the network, the issue is also the buffer size. The default size is small, meaning that large images are broken into many small packets, and dropping a single one of those packets then brings the whole pipeline to a halt. The aforementioned XML increases the buffer size so that messages are sent in fewer, larger packets.
The config/ folder contains 2 XML profiles for tuning DDS:
fastdds.xml: Tells Ros2 (technically the FASTRTPS middleware) to use shared memory by default, and UDP as a fallback. Both are set up with large buffer sizes. The builtin transports (with small buffers) are explicitly disabled.fastdds_udp.xml: Tells Ros2 to only use UDP with large buffers.
Note: The 8 MB buffer sizes require the kernel to allow large socket buffers. If the defaults are too small (common on stock Linux), increase them:
# Check current limits
sysctl net.core.rmem_max net.core.wmem_max
# Set to 8 MB (must be >= the buffer sizes in the XML)
sudo sysctl -w net.core.rmem_max=8388608
sudo sysctl -w net.core.wmem_max=8388608To make this persistent across reboots, add to /etc/sysctl.conf:
net.core.rmem_max=8388608
net.core.wmem_max=8388608
Then apply immediately with:
sudo sysctl -pWithout this, the kernel silently caps the buffer size and large image transfers will be slow.
If you feel like Hammerhead is running slow, follow these steps:
- Check that you're using FastDDS (not CycloneDDS or another middleware):
echo $RMW_IMPLEMENTATIONThis should be empty (FastDDS is the default) or rmw_fastrtps_cpp. If it's set to something else
(e.g. rmw_cyclonedds_cpp), the XML profiles will be silently ignored. Unset it:
unset RMW_IMPLEMENTATION- Check that the XML profile is being loaded:
When a ROS2 node starts, FastDDS will print XML parsing errors to stderr if the file is malformed or missing. If you see no errors and no improvement, the file is likely not being read. Verify:
echo $FASTRTPS_DEFAULT_PROFILES_FILEIf publisher and subscriber are on the same machine, then you can check that shared memory is actually used with something like:
ls /dev/shm/ | grep fastIf you see fastrtps_* files, SHM is active. If not, FastDDS fell back to UDP - usually because
the segment size is too small for your messages.
- If you are unsure of whether these profiles are having an effect, we recommend running hammerhead and the publisher subscriber 3 times...
- In the first run, try with the Ros2 defaults in the terminal where Hammerhead and the publisher and/or subscriber are running:
unset FASTRTPS_DEFAULT_PROFILES_FILEThat is the performance you would get without tuning the DDS.
- Next, you can see what the throughput would be if Ros2 could only use UDP with large buffers by running this in all of your terminals:
export FASTRTPS_DEFAULT_PROFILES_FILE=$(pwd)/config/fastdds_udp.xml- Finally, you can see what type of performance you can achieve when Ros2 is allowed to use shared memory for communication:
export FASTRTPS_DEFAULT_PROFILES_FILE=$(pwd)/config/fastdds.xmlWe suspect that the default configs we supply will drastically increase your throughput compared to the defaults.
- The environment variable must be set in every terminal that runs a ROS2 node (both publisher and subscriber). If only one side is configured, they will still communicate (both have UDP in common), but the unconfigured side becomes the bottleneck — its default buffer sizes (~512KB for SHM, ~212KB for UDP) are far too small for large images, and you'll see the same slow/dropped frame behavior as having no config at all.
- The publisher and subscriber should use compatible transports. The SHM config includes UDP as a fallback, so it is compatible with the UDP-only config. However, you won't get SHM benefits unless both sides have it enabled.
- Use C++ for real-time applications
- Consider message buffering for high-frequency data
- Monitor system resources with large point clouds
- Use appropriate QoS settings for your application
- Always validate message types and versions
- Implement proper error handling
- Use ROS2 lifecycle nodes for complex applications
- Add logging for debugging
- Follow ROS2 naming conventions
- Use appropriate QoS policies
- Integrate with standard ROS2 tools (rviz2, rqt)
- Consider using composition for performance
- Start with simple subscribers before custom code
- Use ROS2 command-line tools for inspection
- Check topic types and message frequencies
- Use ROS2 debugging tools and visualization
