ROS 2 image_transport Guide 2026
Master ROS 2 camera pipelines with image_transport: automatic compressed topic variants, cv_bridge conversion between ROS and OpenCV, camera calibration with CameraInfo, and the republish tool for transport conversion.
Why image_transport?
A 1080p camera at 30fps produces ~180 MB/s of raw data. Sending that over WiFi to a laptop is impossible. image_transport solves this by creating compressed topic variants automatically — the publisher publishes once, and subscribers choose their preferred transport (raw, JPEG, H.264). No publisher code changes needed.
image_transport — Why Compressed Camera Topics?
Raw camera images (sensor_msgs/Image) are large: a 1920x1080 RGB frame is 6MB. image_transport adds a plugin layer so publishers and subscribers negotiate compression automatically — subscribers declare a transport type and receive compressed data without changing publisher code.
image_transport plugin architecture
Publisher Network Subscriber
────────── ─────── ──────────
publish(raw) → /camera/image_raw ← subscribe(raw)
→ /camera/image_raw/compressed ← subscribe(compressed)
→ /camera/image_raw/theora ← subscribe(theora)
→ /camera/image_raw/ffmpeg ← subscribe(ffmpeg)
One publisher → multiple topics created automatically.
Subscriber declares which transport via topic suffix.
Available transports:
raw (sensor_msgs/Image) — default, no compression
compressed (sensor_msgs/CompressedImage) — JPEG or PNG
theora (theora_image_transport) — video codec
ffmpeg (ffmpeg_image_transport) — H.264/H.265 (install separately)
Topic naming convention:
base topic: /camera/image_raw
compressed: /camera/image_raw/compressed
parameters: /camera/image_raw/compressed/format (jpeg/png)
/camera/image_raw/compressed/jpeg_quality (1-100)
Install:
sudo apt install ros-jazzy-image-transport
sudo apt install ros-jazzy-image-transport-plugins # compressed + theoraPublish with image_transport (C++)
Use image_transport::ImageTransport to create a publisher that automatically creates all transport-specific topic variants.
#include "rclcpp/rclcpp.hpp"
#include "image_transport/image_transport.hpp"
#include "sensor_msgs/msg/image.hpp"
#include "cv_bridge/cv_bridge.hpp"
#include <opencv2/opencv.hpp>
class CameraNode : public rclcpp::Node {
public:
CameraNode()
: Node("camera_node"),
it_(this) // ImageTransport wraps the node
{
// Creates /camera/image_raw AND /camera/image_raw/compressed, etc.
pub_ = it_.advertise("camera/image_raw", 1);
cap_ = cv::VideoCapture(0); // USB camera
timer_ = create_wall_timer(
std::chrono::milliseconds(33), // ~30 fps
[this]() { publish_frame(); }
);
}
private:
void publish_frame() {
cv::Mat frame;
if (!cap_.read(frame)) return;
// Convert cv::Mat to sensor_msgs/Image
auto msg = cv_bridge::CvImage(
std_msgs::msg::Header(),
"bgr8", // OpenCV default format
frame
).toImageMsg();
msg->header.stamp = this->now();
msg->header.frame_id = "camera_link";
pub_.publish(*msg);
}
image_transport::ImageTransport it_;
image_transport::Publisher pub_;
cv::VideoCapture cap_;
rclcpp::TimerBase::SharedPtr timer_;
};
int main(int argc, char * argv[]) {
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<CameraNode>());
rclcpp::shutdown();
}
// CMakeLists.txt dependencies:
// find_package(image_transport REQUIRED)
// find_package(cv_bridge REQUIRED)
// ament_target_dependencies(camera_node
// rclcpp image_transport cv_bridge sensor_msgs)image_transport::Publisher automatically creates both raw and compressed topics. Subscribers choose which transport to use — the publisher doesn't need to know.
Subscribe with image_transport (Python)
Subscribe to a camera topic using image_transport's Python API. Specify the transport type to receive compressed images directly.
#!/usr/bin/env python3
import rclpy
from rclpy.node import Node
from sensor_msgs.msg import Image, CompressedImage
from cv_bridge import CvBridge
import cv2
class ImageViewerNode(Node):
def __init__(self):
super().__init__("image_viewer")
self.bridge = CvBridge()
# ── Option 1: Subscribe to raw topic ─────────────────────
# Receives full uncompressed frames
self.sub_raw = self.create_subscription(
Image,
"/camera/image_raw",
self.raw_callback,
10
)
# ── Option 2: Subscribe to compressed topic ───────────────
# Transport type is encoded in the topic suffix
# The image_transport publisher auto-creates this topic
self.sub_compressed = self.create_subscription(
CompressedImage,
"/camera/image_raw/compressed",
self.compressed_callback,
10
)
def raw_callback(self, msg: Image):
# Convert ROS Image to OpenCV Mat
cv_image = self.bridge.imgmsg_to_cv2(msg, desired_encoding="bgr8")
cv2.imshow("Raw Camera", cv_image)
cv2.waitKey(1)
def compressed_callback(self, msg: CompressedImage):
# Convert CompressedImage directly to OpenCV Mat
cv_image = self.bridge.compressed_imgmsg_to_cv2(msg, desired_encoding="bgr8")
cv2.imshow("Compressed Camera", cv_image)
cv2.waitKey(1)
def main():
rclpy.init()
node = ImageViewerNode()
rclpy.spin(node)
cv2.destroyAllWindows()
rclpy.shutdown()compressed_imgmsg_to_cv2() decodes JPEG/PNG in one call. Use this instead of raw when bandwidth is limited (e.g., WiFi robots, Raspberry Pi cameras).
CameraInfo — Calibration Data
Every image topic should be published alongside a camera_info topic. It carries the calibration matrix (K), distortion coefficients (D), and projection matrix (P) needed for 3D reconstruction and undistortion.
import rclpy
from rclpy.node import Node
from sensor_msgs.msg import Image, CameraInfo
from image_transport import ImageTransport # rclpy wrapper (limited)
import yaml
class CalibCameraNode(Node):
def __init__(self):
super().__init__("calib_camera")
# Publish image and camera_info together
self.img_pub = self.create_publisher(Image, "camera/image_raw", 10)
self.info_pub = self.create_publisher(CameraInfo, "camera/camera_info", 10)
# Load calibration file (output of camera_calibration package)
with open("calibration.yaml") as f:
calib = yaml.safe_load(f)
self.camera_info_msg = CameraInfo()
self.camera_info_msg.width = calib["image_width"]
self.camera_info_msg.height = calib["image_height"]
# 3x3 intrinsic matrix
self.camera_info_msg.k = calib["camera_matrix"]["data"]
# Distortion coefficients (k1,k2,p1,p2,k3)
self.camera_info_msg.d = calib["distortion_coefficients"]["data"]
# Rectification matrix (identity for monocular)
self.camera_info_msg.r = calib["rectification_matrix"]["data"]
# Projection matrix (3x4)
self.camera_info_msg.p = calib["projection_matrix"]["data"]
self.camera_info_msg.distortion_model = "plumb_bob"
self.create_timer(0.033, self._publish)
def _publish(self):
now = self.get_clock().now().to_msg()
# Stamp must match between Image and CameraInfo
self.camera_info_msg.header.stamp = now
self.camera_info_msg.header.frame_id = "camera_link"
self.info_pub.publish(self.camera_info_msg)
# ... also publish Image with same stamp
# Calibrate the camera:
# ros2 run camera_calibration cameracalibrator \
# --size 8x6 --square 0.025 \
# image:=/camera/image_raw camera:=/cameraimage_proc and depth_image_proc packages read CameraInfo to undistort and rectify images. Always publish camera_info on the matching namespace: /camera/camera_info for /camera/image_raw.
CLI Tools — List Transports and Republish
Use command-line tools to inspect available transports and convert between transport types at runtime.
# List available image_transport plugins
ros2 run image_transport list_transports
# Republish as a different transport
# Useful to create a compressed topic from a camera that only publishes raw
ros2 run image_transport republish raw compressed --ros-args --remap in:=/camera/image_raw --remap out/compressed:=/camera/image_raw/compressed
# Set JPEG quality via parameter (1 = low quality, 95 = high quality)
ros2 param set /republish out.compressed.jpeg_quality 50
# Subscribe to a topic with a specific transport from CLI
ros2 run image_tools showimage --ros-args -p transport:=compressed --remap image:=/camera/image_raw
# View compressed image stats
ros2 topic hz /camera/image_raw/compressed
ros2 topic bw /camera/image_raw/compressed
# Image pipeline: undistort a calibrated camera
ros2 run image_proc rectify_node --ros-args --remap image:=/camera/image_raw --remap camera_info:=/camera/camera_infoQuick Reference
| API / Tool | Details |
|---|---|
| Install | ros-jazzy-image-transport + ros-jazzy-image-transport-plugins |
| C++ publisher | image_transport::ImageTransport it_(node); it_.advertise('topic', 1) |
| Compressed sub | subscribe CompressedImage on /base_topic/compressed |
| Convert to cv::Mat | cv_bridge::CvImage(..., 'bgr8', frame).toImageMsg() |
| Compressed → cv::Mat | bridge.compressed_imgmsg_to_cv2(msg, 'bgr8') |
| List transports | ros2 run image_transport list_transports |
| Republish | ros2 run image_transport republish raw compressed |
| JPEG quality | ros2 param set /node out.compressed.jpeg_quality 50 |
| Camera calibration | ros2 run camera_calibration cameracalibrator --size 8x6 --square 0.025 |
| camera_info topic | Always publish /camera/camera_info alongside /camera/image_raw |