camera_info_manager::CameraInfoManager Class Reference

CameraInfo Manager class. More...

#include <camera_info_manager.h>

List of all members.

Public Member Functions

 CameraInfoManager (ros::NodeHandle nh, const std::string &cname="camera", const std::string &url="")
sensor_msgs::CameraInfo getCameraInfo (void)
bool isCalibrated (void)
bool loadCameraInfo (const std::string &url)
std::string resolveURL (const std::string &url, const std::string &cname)
bool setCameraName (const std::string &cname)
bool validateURL (const std::string &url)

Private Types

enum  url_type_t {
  URL_empty = 0, URL_file, URL_package, URL_invalid,
  URL_flash
}

Private Member Functions

std::string getPackageFileName (const std::string &url)
bool loadCalibration (const std::string &url, const std::string &cname)
bool loadCalibrationFile (const std::string &filename, const std::string &cname)
url_type_t parseURL (const std::string &url)
bool saveCalibration (const sensor_msgs::CameraInfo &new_info, const std::string &url, const std::string &cname)
bool saveCalibrationFile (const sensor_msgs::CameraInfo &new_info, const std::string &filename, const std::string &cname)
bool setCameraInfo (sensor_msgs::SetCameraInfo::Request &req, sensor_msgs::SetCameraInfo::Response &rsp)

Private Attributes

sensor_msgs::CameraInfo cam_info_
 current CameraInfo
std::string camera_name_
 camera name
ros::ServiceServer info_service_
 set_camera_info service
boost::mutex mutex_
 mutual exclusion lock for private data
ros::NodeHandle nh_
 node handle for service
std::string url_
 URL for calibration data.

Detailed Description

CameraInfo Manager class.

Provides CameraInfo, handles the sensor_msgs/SetCameraInfo service requests, saves and restores sensor_msgs/CameraInfo data.

ROS Service

Typically, these service requests are made by a calibration package, such as:

The calling node must invoke ros::spin() or ros::spinOnce() in some thread, so CameraInfoManager can handle arriving service requests.

Camera Name

The device driver sets a camera name via the CameraInfoManager::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.

Beginning with Electric Emys, 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::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.

Beginning with Electric Emys, 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:

In C-turtle and Diamondback, if the URL was empty, no calibration data were loaded, and any data provided via `set_camera_info` would be stored in:

Beginning in Electric, the default URL changed to:

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

Definition at line 160 of file camera_info_manager.h.


Member Enumeration Documentation

Enumerator:
URL_empty 
URL_file 
URL_package 
URL_invalid 
URL_flash 

Definition at line 200 of file camera_info_manager.h.


Constructor & Destructor Documentation

camera_info_manager::CameraInfoManager::CameraInfoManager ( ros::NodeHandle  nh,
const std::string &  cname = "camera",
const std::string &  url = "" 
)

Constructor

Parameters:
nh node handle, normally for the driver's streaming name space ("camera"). The service name is relative to this handle. Nodes supporting multiple cameras may use subordinate names, like "left/camera" and "right/camera".
cname default camera name
url default Uniform Resource Locator for loading and saving data.

Definition at line 78 of file camera_info_manager.cpp.


Member Function Documentation

sensor_msgs::CameraInfo camera_info_manager::CameraInfoManager::getCameraInfo ( void   )  [inline]

Get the current CameraInfo data.

The matrices are all zeros if no calibration was available. The image pipeline handles that as uncalibrated data.

Warning:
The caller must fill in the message Header of the CameraInfo returned. The time stamp and frame_id should normally be the same as the corresponding Image message Header fields.

Definition at line 178 of file camera_info_manager.h.

std::string camera_info_manager::CameraInfoManager::getPackageFileName ( const std::string &  url  )  [private]

Get file name corresponding to a package: URL.

Parameters:
url a copy of the Uniform Resource Locator
Returns:
file name if package found, "" otherwise

Definition at line 97 of file camera_info_manager.cpp.

bool camera_info_manager::CameraInfoManager::isCalibrated ( void   )  [inline]

Return true if the current CameraInfo is calibrated.

Definition at line 185 of file camera_info_manager.h.

bool camera_info_manager::CameraInfoManager::loadCalibration ( const std::string &  url,
const std::string &  cname 
) [private]

Load CameraInfo calibration data (if any).

Precondition:
mutex_ unlocked
Parameters:
url a copy of the Uniform Resource Locator
cname is a copy of the camera_name_
Returns:
true if URL contains calibration data.

sets cam_info_, if successful

Definition at line 131 of file camera_info_manager.cpp.

bool camera_info_manager::CameraInfoManager::loadCalibrationFile ( const std::string &  filename,
const std::string &  cname 
) [private]

Load CameraInfo calibration data from a file.

Precondition:
mutex_ unlocked
Parameters:
filename containing CameraInfo to read
cname is a copy of the camera_name_
Returns:
true if URL contains calibration data.

Sets cam_info_, if successful

Definition at line 189 of file camera_info_manager.cpp.

bool camera_info_manager::CameraInfoManager::loadCameraInfo ( const std::string &  url  ) 

Set a new URL and load its calibration data (if any).

Parameters:
url new Uniform Resource Locator for CameraInfo.
Returns:
true if new URL contains calibration data.

cam_info_ updated, if successful.

Definition at line 227 of file camera_info_manager.cpp.

CameraInfoManager::url_type_t camera_info_manager::CameraInfoManager::parseURL ( const std::string &  url  )  [private]

Parse calibration Uniform Resource Locator.

Parameters:
url string to parse
Returns:
URL type
Note:
Recognized but unsupported URL types have enum values >= URL_invalid.

Definition at line 323 of file camera_info_manager.cpp.

std::string camera_info_manager::CameraInfoManager::resolveURL ( const std::string &  url,
const std::string &  cname 
)

Resolve Uniform Resource Locator string.

Parameters:
url a copy of the Uniform Resource Locator, which may include ${...} substitution variables.
cname is a copy of the camera_name_
Returns:
a copy of the URL with any variable information resolved.

Definition at line 249 of file camera_info_manager.cpp.

bool camera_info_manager::CameraInfoManager::saveCalibration ( const sensor_msgs::CameraInfo &  new_info,
const std::string &  url,
const std::string &  cname 
) [private]

Save CameraInfo calibration data.

Precondition:
mutex_ unlocked
Parameters:
new_info contains CameraInfo to save
url is a copy of the URL storage location (if empty, use file://${ROS_HOME}/camera_info/${NAME}.yaml)
cname is a copy of the camera_name_
Returns:
true, if successful

Definition at line 359 of file camera_info_manager.cpp.

bool camera_info_manager::CameraInfoManager::saveCalibrationFile ( const sensor_msgs::CameraInfo &  new_info,
const std::string &  filename,
const std::string &  cname 
) [private]

Save CameraInfo calibration data to a file.

Precondition:
mutex_ unlocked
Parameters:
new_info contains CameraInfo to save
filename is local file to store data
cname is a copy of the camera_name_
Returns:
true, if successful

Definition at line 409 of file camera_info_manager.cpp.

bool camera_info_manager::CameraInfoManager::setCameraInfo ( sensor_msgs::SetCameraInfo::Request &  req,
sensor_msgs::SetCameraInfo::Response &  rsp 
) [private]

Callback for SetCameraInfo request.

Always updates cam_info_ class variable, even if save fails.

Parameters:
req SetCameraInfo request message
rsp SetCameraInfo response message
Returns:
true if message handled

Definition at line 474 of file camera_info_manager.cpp.

bool camera_info_manager::CameraInfoManager::setCameraName ( const std::string &  cname  ) 

Set a new camera name.

Parameters:
cname new camera name to use for saving calibration data
Returns:
true if new name has valid syntax

cam_name_ updated, if valid.

Valid names contain only alphabetic, numeric, or '_' characters.

Definition at line 511 of file camera_info_manager.cpp.

bool camera_info_manager::CameraInfoManager::validateURL ( const std::string &  url  ) 

Validate URL syntax.

Parameters:
url Uniform Resource Locator to check
Returns:
true if URL syntax is supported by CameraInfoManager (although the resource need not actually exist)

Definition at line 546 of file camera_info_manager.cpp.


Member Data Documentation

sensor_msgs::CameraInfo camera_info_manager::CameraInfoManager::cam_info_ [private]

current CameraInfo

Definition at line 242 of file camera_info_manager.h.

camera name

Definition at line 240 of file camera_info_manager.h.

set_camera_info service

Definition at line 239 of file camera_info_manager.h.

mutual exclusion lock for private data

This non-recursive mutex is only held for a short time while accessing or changing private class variables. To avoid deadlocks and contention, it is never held during I/O or while invoking a callback. Most private methods operate on copies of class variables, keeping the mutex hold time short.

Definition at line 235 of file camera_info_manager.h.

node handle for service

Definition at line 238 of file camera_info_manager.h.

URL for calibration data.

Definition at line 241 of file camera_info_manager.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator


camera_info_manager
Author(s): Jack O'Quin
autogenerated on Fri Jan 11 12:08:34 2013