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
85 changes: 85 additions & 0 deletions image_transport/doc/camera_api.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,85 @@
Camera API
==========

Camera drivers typically publish both an ``Image`` and a ``CameraInfo`` topic.
``image_transport`` provides helper classes that publish and subscribe to these
two topics together, keeping them synchronised.

CameraPublisher
---------------

:cpp:class:`image_transport::CameraPublisher` publishes ``Image`` and
``CameraInfo`` on a pair of synchronised topics derived from a single base
topic name.

See the full :ref:`exhale_class_classimage__transport_1_1CameraPublisher` API reference.

CameraSubscriber
----------------

:cpp:class:`image_transport::CameraSubscriber` subscribes to both the
``Image`` and ``CameraInfo`` topics and delivers them via a single callback.

See the full :ref:`exhale_class_classimage__transport_1_1CameraSubscriber` API reference.

Topic Naming Convention
-----------------------

Given a base topic name (e.g. ``/camera/image_raw``), ``CameraPublisher``
automatically creates the matching camera info topic by appending
``/../camera_info``:

.. code-block:: text

/camera/image_raw ← image topic
/camera/camera_info ← camera info topic (sibling)

The sibling topic name is computed by
:cpp:func:`image_transport::getCameraInfoTopic`.

Usage Example
-------------

**Publisher side (camera driver)**

.. code-block:: cpp

#include <rclcpp/rclcpp.hpp>
#include <image_transport/image_transport.hpp>
#include <sensor_msgs/msg/camera_info.hpp>

class CameraDriver : public rclcpp::Node
{
public:
CameraDriver() : Node("camera_driver")
{
it_ = std::make_shared<image_transport::ImageTransport>(
shared_from_this());
cam_pub_ = it_->advertiseCamera("camera/image_raw", 1);
}

void publishFrame(
sensor_msgs::msg::Image::SharedPtr image,
sensor_msgs::msg::CameraInfo::SharedPtr info)
{
cam_pub_.publish(image, info);
}

private:
std::shared_ptr<image_transport::ImageTransport> it_;
image_transport::CameraPublisher cam_pub_;
};

**Subscriber side**

.. code-block:: cpp

it_ = std::make_shared<image_transport::ImageTransport>(shared_from_this());
cam_sub_ = it_->subscribeCamera(
"camera/image_raw", 1,
[this](
const sensor_msgs::msg::Image::ConstSharedPtr & img,
const sensor_msgs::msg::CameraInfo::ConstSharedPtr & info)
{
RCLCPP_INFO(get_logger(), "fx = %f", info->k[0]);
});
43 changes: 43 additions & 0 deletions image_transport/doc/conf.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
import os
import sys

# Allow Sphinx extensions to find local modules
sys.path.insert(0, os.path.abspath('.'))

# -- Project information (overridden by rosdoc2 from package.xml) ----------
project = 'image_transport'
copyright = '2024, Open Robotics'
author = 'Alejandro Hernandez Cordero, Geoffrey Biggs'

# -- General configuration -------------------------------------------------
extensions = [
'sphinx.ext.autodoc',
'sphinx.ext.intersphinx',
'breathe',
'myst_parser',
]

# breathe_projects and breathe_default_project are overridden by rosdoc2 at build time.
breathe_default_project = 'image_transport Doxygen Project'
breathe_default_members = ('members', 'undoc-members')

# myst_parser — allow .md files in toctrees
source_suffix = {
'.rst': 'restructuredtext',
'.md': 'markdown',
}

templates_path = ['_templates']
# Exclude root-level copies of user docs (rosdoc2 copies them to user_docs/ too,
# where they are included via the user_docs.rst glob toctree).
exclude_patterns = [
'_build',
'camera_api.rst',
'filter_api.rst',
'overview.rst',
'plugin_api.rst',
'user_api.rst',
]

# -- HTML output options ---------------------------------------------------
html_theme = 'sphinx_rtd_theme'
63 changes: 63 additions & 0 deletions image_transport/doc/filter_api.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,63 @@
Message Filter Integration
==========================

``image_transport`` provides :cpp:class:`image_transport::SubscriberFilter`, a
drop-in replacement for ``message_filters::Subscriber`` that works with the
full suite of ``message_filters`` synchronisation policies (e.g.
``TimeSynchronizer``, ``ApproximateTime``).

SubscriberFilter
----------------

:cpp:class:`image_transport::SubscriberFilter` is a
``message_filters``-compatible subscriber that decodes compressed image streams
before delivering them to the filter chain.

See the full :ref:`exhale_class_classimage__transport_1_1SubscriberFilter` API reference.

Usage Example
-------------

The following example synchronises an image with a ``PointCloud2`` message
using ``message_filters::TimeSynchronizer``.

.. code-block:: cpp

#include <rclcpp/rclcpp.hpp>
#include <image_transport/subscriber_filter.hpp>
#include <message_filters/subscriber.h>
#include <message_filters/time_synchronizer.h>
#include <sensor_msgs/msg/point_cloud2.hpp>

class SyncNode : public rclcpp::Node
{
public:
SyncNode() : Node("sync_node")
{
image_sub_.subscribe(shared_from_this(), "camera/image_raw");
cloud_sub_.subscribe(shared_from_this(), "points");

sync_ = std::make_shared<
message_filters::TimeSynchronizer<
sensor_msgs::msg::Image,
sensor_msgs::msg::PointCloud2>>(image_sub_, cloud_sub_, 10);
sync_->registerCallback(
std::bind(&SyncNode::callback, this,
std::placeholders::_1, std::placeholders::_2));
}

private:
void callback(
const sensor_msgs::msg::Image::ConstSharedPtr & img,
const sensor_msgs::msg::PointCloud2::ConstSharedPtr & cloud)
{
RCLCPP_INFO(get_logger(), "Synced frame at %u ns",
img->header.stamp.nanosec);
}

image_transport::SubscriberFilter image_sub_;
message_filters::Subscriber<sensor_msgs::msg::PointCloud2> cloud_sub_;
std::shared_ptr<message_filters::TimeSynchronizer<
sensor_msgs::msg::Image,
sensor_msgs::msg::PointCloud2>> sync_;
};
106 changes: 106 additions & 0 deletions image_transport/doc/overview.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,106 @@
Overview
========

``image_transport`` is a ROS 2 library that provides a plugin-based framework
for publishing and subscribing to images. It acts as a transparent layer on
top of standard ROS 2 publishers and subscribers, allowing image data to be
transported in raw or compressed form without any changes to the application
code.

Motivation
----------

Raw images are large. A single 1080p colour frame is roughly 6 MB. Sending
these frames over a network at 30 Hz consumes nearly 1.5 Gbit/s of bandwidth.
``image_transport`` solves this by:

* Advertising a *family* of topics for every base image topic (e.g.
``/camera/image_raw``, ``/camera/image_raw/compressed``,
``/camera/image_raw/theora``, …).
* Letting subscribers pick the transport that best suits their network
conditions by setting the ``image_transport`` ROS parameter.
* Keeping the API identical to standard ``rclcpp`` publishers and subscribers
so that existing code requires minimal changes.

Architecture
------------

.. code-block:: text

Camera driver
image_transport::Publisher
├─ raw topic ──► raw subscriber
├─ compressed topic ──► compressed subscriber
└─ theora topic ──► theora subscriber

The publisher side creates one sub-publisher per installed transport plugin.
The subscriber side picks exactly one transport based on the
``image_transport`` parameter (default: ``raw``).

Plugin system
^^^^^^^^^^^^^

Transport plugins are discovered at runtime via ``pluginlib``. Each plugin
implements either :cpp:class:`image_transport::PublisherPlugin` or
:cpp:class:`image_transport::SubscriberPlugin`. The built-in ``raw`` transport
is provided by :cpp:class:`image_transport::RawPublisher` and
:cpp:class:`image_transport::RawSubscriber`.

A list of all currently loaded transport plugins can be obtained with:

.. code-block:: bash

ros2 run image_transport list_transports

Dependencies
------------

* ``rclcpp`` — ROS 2 C++ client library
* ``sensor_msgs`` — ``Image`` and ``CameraInfo`` message types
* ``message_filters`` — for :cpp:class:`image_transport::SubscriberFilter`
* ``pluginlib`` — runtime plugin loading
* ``rclcpp_components`` — composable node support (``republish``)

ROS Parameters
--------------

.. list-table::
:header-rows: 1

* - Parameter
- Type
- Default
- Description
* - ``image_transport``
- string
- ``"raw"``
- Transport to use when subscribing. Set per-subscriber via
:cpp:class:`image_transport::TransportHints`.

Nodes
-----

republish
^^^^^^^^^

Converts an image stream from one transport to another.

.. code-block:: bash

ros2 run image_transport republish \
--ros-args \
-p in_transport:=raw \
-p out_transport:=compressed \
--remap in:=/camera/image_raw \
--remap out:=/camera/image_raw

list_transports
^^^^^^^^^^^^^^^

Prints all transport plugins available in the current environment.

.. code-block:: bash

ros2 run image_transport list_transports
Loading