Public Member Functions | Static Public Member Functions | Protected Types | Protected Member Functions | Static Protected Member Functions | Protected Attributes | Private Member Functions | List of all members
camera_info_manager_lib::CameraInfoManager Class Reference

Provides CameraInfo data for a calibrated camera. Different from camera_info_manager::CameraInfoManager, this class provides only the C++ API and not the ROS API (set_camera_info service). More...

#include <camera_info_manager.h>

Inheritance diagram for camera_info_manager_lib::CameraInfoManager:
Inheritance graph
[legend]

Public Member Functions

 CameraInfoManager (const cras::LogHelperPtr &log, const std::string &cname="camera", const std::string &url="")
 Constructor. It does not load the calibration file, that is done lazily when needed. More...
 
 CameraInfoManager (const std::string &cname="camera", const std::string &url="")
 Constructor. It does not load the calibration file, that is done lazily when needed. More...
 
sensor_msgs::CameraInfo getCameraInfo ()
 Load and return the camera info assigned to the camera specified in constructor or by calls to setCameraName() and setFocalLength(). More...
 
bool isCalibrated ()
 
virtual bool setCameraName (const std::string &cname)
 Set or change the name of the camera that should currently be represented by this class. More...
 
virtual bool setFocalLength (double focalLength)
 Set or change the focal length of the camera that should currently be represented by this class. More...
 
virtual ~CameraInfoManager ()
 
- Public Member Functions inherited from cras::HasLogger
::cras::LogHelperConstPtr getCrasLogger () const
 
 HasLogger (const ::cras::LogHelperPtr &log)
 
void setCrasLogger (const ::cras::LogHelperPtr &log)
 

Static Public Member Functions

static std::string resolveURL (const cras::LogHelperPtr &log, const std::string &url, const std::string &cname, const cras::optional< double > &focalLength)
 Resolve substitution keywords in the given URL. More...
 
static bool validateURL (const std::string &url)
 Validate a camera info URL. More...
 

Protected Types

enum  URL {
  URL::EMPTY = 0, URL::FILE, URL::PACKAGE, URL::INVALID,
  URL::FLASH
}
 recognized URL types More...
 

Protected Member Functions

virtual bool loadCalibration (const std::string &url, const std::string &cname, const cras::optional< double > &focalLength)
 Load calibration according to camera info URL. More...
 
virtual bool loadCalibrationFile (const std::string &filename, const std::string &cname)
 Load calibration from the given file. More...
 
virtual bool loadCalibrationFlash (const std::string &flashURL, const std::string &cname)
 Load calibration from camera flash (not supported, but subclasses can override). More...
 

Static Protected Member Functions

static URL parseURL (const std::string &url)
 Parse the type of the URL. More...
 

Protected Attributes

std::string cameraName
 Camera name. More...
 
sensor_msgs::CameraInfo camInfo {}
 Current CameraInfo. More...
 
cras::optional< double > focalLength
 Current focal length. More...
 
bool loadedCamInfo
 Whether camInfo load has been attempted. More...
 
std::string url
 URL for calibration data. More...
 
- Protected Attributes inherited from cras::HasLogger
::cras::LogHelperPtr log
 

Private Member Functions

std::string getPackageFileName (const std::string &url) const
 Resolve the package:// part of URL with a local file. More...
 

Detailed Description

Provides CameraInfo data for a calibrated camera. Different from camera_info_manager::CameraInfoManager, this class provides only the C++ API and not the ROS API (set_camera_info service).

Camera Name

The device driver sets a camera name via the CameraInfoManager() constructor or the setCameraName() method. This name is written when CameraInfo is saved, and checked when data are loaded, with a warning logged if the name read does not match.

Syntax: a camera name contains any combination of alphabetic, numeric and '_' characters. Case is significant.

Camera drivers may use any syntactically valid name they please. Where possible, it is best for the name to be unique to the device, such as a GUID, or the make, model and serial number. Any parameters that affect calibration, such as resolution, focus, zoom, etc., may also be included in the name, uniquely identifying each CameraInfo file.

The camera name can be resolved as part of the URL, allowing direct access to device-specific calibration information.

Uniform Resource Locator

The location for getting and saving calibration data is expressed by Uniform Resource Locator. The driver defines a URL via the CameraInfoManager() constructor or the loadCameraInfo() method. Many drivers provide a ~camera_info_url parameter so users may customize this URL, but that is handled outside this class.

Typically, cameras store calibration information in a file, which can be in any format supported by camera_calibration_parsers . Currently, that includes YAML and Videre INI files, identified by their .yaml or .ini extensions as shown in the examples. These file formats are described here:

Example URL syntax:

The file: URL specifies a full path name in the local system. The package: URL is handled the same as file:, except the path name is resolved relative to the location of the named ROS package, which must be reachable via $ROS_PACKAGE_PATH.

The URL may contain substitution variables delimited by ${...}, including:

Resolution is done in a single pass through the URL string. Variable values containing substitutable strings are not resolved recursively. Unrecognized variable names are treated literally with no substitution, but an error is logged.

Examples with variable substitution:

The default URL is:

If that file exists, its contents are used. Any new calibration will be stored there, missing parent directories being created if necessary and possible.

Loading Calibration Data

CameraInfoManager loads nothing until the &c loadCameraInfo(), &c isCalibrated() or &c getCameraInfo() method is called. That suppresses bogus error messages, but allows (valid) load errors to occur during the first getCameraInfo(), or isCalibrated(). To avoid that, do an explicit loadCameraInfo() first.

Definition at line 161 of file camera_info_manager.h.

Member Enumeration Documentation

◆ URL

recognized URL types

Enumerator
EMPTY 

empty string

FILE 

file:

PACKAGE 

package:

INVALID 

anything >= is invalid

FLASH 

flash:

Definition at line 261 of file camera_info_manager.h.

Constructor & Destructor Documentation

◆ CameraInfoManager() [1/2]

camera_info_manager_lib::CameraInfoManager::CameraInfoManager ( const std::string &  cname = "camera",
const std::string &  url = "" 
)
explicit

Constructor. It does not load the calibration file, that is done lazily when needed.

Parameters
[in]cnameName of the camera (used in URL).
[in]urlThe URL specifying path to the calibration file (substitution keywords can be used).

◆ CameraInfoManager() [2/2]

camera_info_manager_lib::CameraInfoManager::CameraInfoManager ( const cras::LogHelperPtr log,
const std::string &  cname = "camera",
const std::string &  url = "" 
)
explicit

Constructor. It does not load the calibration file, that is done lazily when needed.

Parameters
[in]logLogger.
[in]cnameName of the camera (used in URL).
[in]urlThe URL specifying path to the calibration file (substitution keywords can be used).

◆ ~CameraInfoManager()

virtual camera_info_manager_lib::CameraInfoManager::~CameraInfoManager ( )
virtual

Member Function Documentation

◆ getCameraInfo()

sensor_msgs::CameraInfo camera_info_manager_lib::CameraInfoManager::getCameraInfo ( )

Load and return the camera info assigned to the camera specified in constructor or by calls to setCameraName() and setFocalLength().

Returns
The camera info.

◆ getPackageFileName()

std::string camera_info_manager_lib::CameraInfoManager::getPackageFileName ( const std::string &  url) const
private

Resolve the package:// part of URL with a local file.

Parameters
[in]urlThe package:// URL.
Returns
The URL resolved to a local file.

◆ isCalibrated()

bool camera_info_manager_lib::CameraInfoManager::isCalibrated ( )
Returns
Whether camera info is available and nonzero for the specified camera.

◆ loadCalibration()

virtual bool camera_info_manager_lib::CameraInfoManager::loadCalibration ( const std::string &  url,
const std::string &  cname,
const cras::optional< double > &  focalLength 
)
protectedvirtual

Load calibration according to camera info URL.

Parameters
[in]urlCamera info URL (can contain substitution keywords).
[in]cnameName of the camera.
[in]focalLengthFocal length of the camera [mm].
Returns
Whether the calibration has been found and loaded.

◆ loadCalibrationFile()

virtual bool camera_info_manager_lib::CameraInfoManager::loadCalibrationFile ( const std::string &  filename,
const std::string &  cname 
)
protectedvirtual

Load calibration from the given file.

Parameters
[in]filenameCalibration file.
[in]cnameCamera name.
Returns
Whether the calibration has been found and loaded.

◆ loadCalibrationFlash()

virtual bool camera_info_manager_lib::CameraInfoManager::loadCalibrationFlash ( const std::string &  flashURL,
const std::string &  cname 
)
protectedvirtual

Load calibration from camera flash (not supported, but subclasses can override).

Parameters
[in]flashURLFlash URL.
[in]cnameCamera name.
Returns
Whether the calibration has been found and loaded.

◆ parseURL()

static URL camera_info_manager_lib::CameraInfoManager::parseURL ( const std::string &  url)
staticprotected

Parse the type of the URL.

Parameters
[in]urlThe URL to parse.
Returns
The URL type.

◆ resolveURL()

static std::string camera_info_manager_lib::CameraInfoManager::resolveURL ( const cras::LogHelperPtr log,
const std::string &  url,
const std::string &  cname,
const cras::optional< double > &  focalLength 
)
static

Resolve substitution keywords in the given URL.

Parameters
[in]logLogger.
[in]urlThe URL to resolve.
[in]cnameCamera name.
[in]focalLengthFocal length [mm].
Returns
The resolved URL.

◆ setCameraName()

virtual bool camera_info_manager_lib::CameraInfoManager::setCameraName ( const std::string &  cname)
virtual

Set or change the name of the camera that should currently be represented by this class.

Parameters
[in]cnameNew camera name.
Returns
Whether the new name is valid and was used.

◆ setFocalLength()

virtual bool camera_info_manager_lib::CameraInfoManager::setFocalLength ( double  focalLength)
virtual

Set or change the focal length of the camera that should currently be represented by this class.

Parameters
[in]focalLengthNew focal length [mm].
Returns
Whether the focal length is valid and was used (negative values are invalid).

◆ validateURL()

static bool camera_info_manager_lib::CameraInfoManager::validateURL ( const std::string &  url)
static

Validate a camera info URL.

Parameters
[in]urlThe URL to validate.
Returns
True if URL syntax is supported by CameraInfoManager (although the resource need not actually exist).

Member Data Documentation

◆ cameraName

std::string camera_info_manager_lib::CameraInfoManager::cameraName
protected

Camera name.

Definition at line 313 of file camera_info_manager.h.

◆ camInfo

sensor_msgs::CameraInfo camera_info_manager_lib::CameraInfoManager::camInfo {}
protected

Current CameraInfo.

Definition at line 316 of file camera_info_manager.h.

◆ focalLength

cras::optional<double> camera_info_manager_lib::CameraInfoManager::focalLength
protected

Current focal length.

Definition at line 314 of file camera_info_manager.h.

◆ loadedCamInfo

bool camera_info_manager_lib::CameraInfoManager::loadedCamInfo
protected

Whether camInfo load has been attempted.

Definition at line 317 of file camera_info_manager.h.

◆ url

std::string camera_info_manager_lib::CameraInfoManager::url
protected

URL for calibration data.

Definition at line 315 of file camera_info_manager.h.


The documentation for this class was generated from the following file:


camera_info_manager_lib
Author(s): Martin Pecka
autogenerated on Wed May 28 2025 02:07:20