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
93 changes: 93 additions & 0 deletions camera_info_manager/doc/api.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,93 @@
API Reference
=============

CameraInfoManager
-----------------

:cpp:class:`camera_info_manager::CameraInfoManager` is the main class.
Camera drivers create one instance per camera and use it to serve calibration
data.

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

Type Aliases
------------

The following type aliases are defined in the ``camera_info_manager`` namespace:

- ``CameraInfo`` — alias for ``sensor_msgs::msg::CameraInfo``.
- ``SetCameraInfo`` — alias for ``sensor_msgs::srv::SetCameraInfo``.

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

**Minimal camera driver**

.. code-block:: cpp

#include <rclcpp/rclcpp.hpp>
#include <camera_info_manager/camera_info_manager.hpp>
#include <image_transport/image_transport.hpp>

class MyCameraDriver : public rclcpp::Node
{
public:
MyCameraDriver()
: Node("my_camera")
{
cim_ = std::make_shared<camera_info_manager::CameraInfoManager>(
get_node_base_interface(),
get_node_services_interface(),
get_node_logging_interface(),
"my_camera", // camera name
"package://my_driver/config/cam.yaml" // calibration URL
);

// Eagerly load calibration so errors surface before streaming starts.
if (!cim_->loadCameraInfo("")) {
RCLCPP_WARN(get_logger(), "No calibration loaded");
}

auto it = image_transport::ImageTransport(shared_from_this());
cam_pub_ = it.advertiseCamera("image_raw", 1);

timer_ = create_wall_timer(
std::chrono::milliseconds(33),
std::bind(&MyCameraDriver::publishFrame, this));
}

private:
void publishFrame()
{
auto image = std::make_shared<sensor_msgs::msg::Image>();
// ... fill image from hardware ...

auto ci = std::make_shared<sensor_msgs::msg::CameraInfo>(
cim_->getCameraInfo());
ci->header = image->header;
cam_pub_.publish(image, ci);
}

std::shared_ptr<camera_info_manager::CameraInfoManager> cim_;
image_transport::CameraPublisher cam_pub_;
rclcpp::TimerBase::SharedPtr timer_;
};

**Changing the calibration URL at runtime**

.. code-block:: cpp

// Reload from a different file without restarting the node:
cim_->loadCameraInfo("file:///tmp/new_calibration.yaml");

**Checking calibration status**

.. code-block:: cpp

if (cim_->isCalibrated()) {
auto ci = cim_->getCameraInfo();
RCLCPP_INFO(get_logger(), "fx = %f", ci.k[0]);
} else {
RCLCPP_WARN(get_logger(), "Camera not calibrated");
}
35 changes: 35 additions & 0 deletions camera_info_manager/doc/conf.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
import os
import sys

sys.path.insert(0, os.path.abspath('.'))

project = 'camera_info_manager'
copyright = '2024, Open Robotics'
author = 'Alejandro Hernandez Cordero, Geoffrey Biggs, Jack O\'Quin, Michael Carroll'

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 = 'camera_info_manager Doxygen Project'
breathe_default_members = ('members', 'undoc-members')

source_suffix = {
'.rst': 'restructuredtext',
'.md': 'markdown',
}

templates_path = ['_templates']
# Exclude root-level copies of user docs (rosdoc2 also copies them to user_docs/
# where they are covered by the user_docs.rst glob toctree).
exclude_patterns = [
'_build',
'overview.rst',
'api.rst',
]

html_theme = 'sphinx_rtd_theme'
120 changes: 120 additions & 0 deletions camera_info_manager/doc/overview.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,120 @@
Overview
========

``camera_info_manager`` provides a C++ class that manages
``sensor_msgs/msg/CameraInfo`` for camera drivers. It handles:

- **Loading** calibration data from a file or ``package://`` URL on first
access (lazy loading).
- **Saving** calibration data to a file in response to a
``sensor_msgs/srv/SetCameraInfo`` service call.
- **Advertising** the ``set_camera_info`` service so calibration tools can
push new calibration data to a running camera driver.

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

A camera driver creates a ``CameraInfoManager`` at startup, passing node
interfaces and a calibration URL. The manager advertises the
``set_camera_info`` service and lazy-loads calibration data the first time
``getCameraInfo()`` or ``isCalibrated()`` is called.

.. code-block:: none

Camera Driver Node
├── CameraInfoManager
│ ├── Reads calibration URL → loads CameraInfo from file/package
│ ├── Serves ~/set_camera_info → saves new calibration to file
│ └── Returns CameraInfo via getCameraInfo()
└── Publishes Image + CameraInfo on every frame

Calibration URL Schemes
-----------------------

``camera_info_manager`` supports two URL schemes for locating calibration
files:

``file://``
Absolute path on the local filesystem.

.. code-block:: none

file:///home/user/calibrations/camera.yaml

``package://``
Path relative to the install prefix of a ROS 2 package.

.. code-block:: none

package://my_camera_driver/config/calibration.yaml

URL Variable Substitution
~~~~~~~~~~~~~~~~~~~~~~~~~

URLs may contain the following variables (resolved in a single pass):

- ``${NAME}`` — replaced with the camera name set at construction time or
via ``setCameraName()``.
- ``${ROS_HOME}`` — replaced with the value of the ``$ROS_HOME`` environment
variable, or ``~/.ros`` if unset.

Default URL (when none is provided):

.. code-block:: none

file://${ROS_HOME}/camera_info/${NAME}.yaml

Camera Name
-----------

The camera name is used for two purposes:

1. Substituted for ``${NAME}`` in the calibration URL.
2. Compared against the camera name stored inside the calibration file — a
warning is logged if they differ.

A valid camera name consists of alphanumeric characters and underscores.
For uniqueness, consider encoding a GUID or make/model/serial combination.

Lazy Loading
------------

No I/O is performed in the constructor. Calibration data are read on the
first call to ``getCameraInfo()``, ``isCalibrated()``, or an explicit
``loadCameraInfo()``. Call ``loadCameraInfo()`` early in the driver's
``on_activate()`` or equivalent lifecycle callback to surface load errors
before streaming begins.

ROS 2 Service
-------------

The manager advertises ``~/set_camera_info`` (relative to the node namespace
unless overridden). Calibration tools such as
``camera_calibration`` send new calibration data via this service; the manager
saves the data to the configured URL and updates the in-memory CameraInfo.

Lifecycle Node Support
----------------------

Pass a ``rclcpp_lifecycle::LifecycleNode *`` to the deprecated constructor, or
extract node interfaces from the lifecycle node and use the preferred
interface-based constructor.

.. code-block:: cpp

auto cim = std::make_shared<camera_info_manager::CameraInfoManager>(
node->get_node_base_interface(),
node->get_node_services_interface(),
node->get_node_logging_interface(),
"my_camera",
"package://my_driver/config/camera.yaml");

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

- ``rclcpp`` — node interfaces and service server.
- ``rclcpp_lifecycle`` — lifecycle node support (deprecated constructor path).
- ``sensor_msgs`` — ``CameraInfo`` and ``SetCameraInfo`` types.
- ``camera_calibration_parsers`` — YAML / INI calibration file I/O.
- ``ament_index_cpp`` — resolves ``package://`` URLs to filesystem paths.
- ``rcpputils`` — utility helpers.
Loading