camera_info_manager

Python camera_info_manager interface, providing CameraInfo support for drivers written in Python. This is very similar to the C++ camera_info_manager package, but not identical.

exception camera_info_manager.CameraInfoError[source]

..exception: CameraInfoError

Base class for exceptions in this module.

exception camera_info_manager.CameraInfoMissingError[source]

..exception: CameraInfoMissingError

Exception raised when CameraInfo has not been loaded.

class camera_info_manager.CameraInfoManager(cname=u'camera', url=u'', namespace=u'')[source]

CameraInfoManager provides ROS CameraInfo support for Python camera drivers. It handles the sensor_msgs/SetCameraInfo service requests, saving and restoring sensor_msgs/CameraInfo data.

Parameters:
  • cname – camera name.
  • url – Uniform Resource Locator for camera calibration data.
  • namespace – Optional ROS namespace prefix for the service name. If a namespace is specified, the ‘/’ separator required between it and set_camera_info will be supplied automatically.
str(camera_info_manager_obj)
Returns:String representation of CameraInfoManager object.

ROS Service

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

The calling node must invoke rospy.spin() in some thread, so CameraInfoManager gets called to handle arriving service requests.

If a driver handles multiple cameras, it should use the namespace parameter to declare separate CameraInfoManager instances for each one, as in this stereo example:

left_ci = CameraInfoManager(cname='left_camera', namespace='left')
right_ci = CameraInfoManager(cname='right_camera', namespace='right')

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 setURL() method. Many drivers provide a ~camera_info_url parameter so users may customize this URL, but that is handled outside this class.

Camera calibration information is stored in YAML format.

Example URL syntax:

  • file:///full/path/to/local/file.yaml
  • package://camera_info_manager_py/tests/test_calibration.yaml
  • package://ros_package_name/calibrations/camera3.yaml

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:

  • ${NAME} resolved to the current camera name defined by the

    device driver.

  • ${ROS_HOME} resolved to the $ROS_HOME environment variable if

    defined, ~/.ros if not.

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:

  • package://my_cameras/calibrations/${NAME}.yaml
  • file://${ROS_HOME}/camera_info/left_front_camera.yaml

The default URL is:

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

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

Unlike the C++ camera_info_manager, this Python implementation loads nothing until the loadCameraInfo() method is called. It is an error to call getCameraInfo(), or isCalibrated() before that is done.

If the URL or camera name changes, loadCameraInfo() must be called again before the data are accessible.

getCameraInfo()[source]

Get the current camera calibration.

The loadCameraInfo() must have been called since the last time the camera name or URL changed.

Returns:sensor_msgs/CameraInfo message.
Raises:CameraInfoMissingError if camera info not up to date.
getCameraName()[source]

Get the current camera name.

Returns:camera name string
getURL()[source]

Get the current calibration URL.

Returns:URL string without variable expansion.
isCalibrated()[source]

Is the current CameraInfo calibrated?

The loadCameraInfo() must have been called since the last time the camera name or URL changed.

Returns:True if camera calibration exists; False for null calibration.
Raises:CameraInfoMissingError if camera info not up to date.
loadCameraInfo()[source]

Load currently configured calibration data (if any).

This method updates camera_info, if possible, based on the currently-configured URL and camera name. An empty or non-existent calibration is not considered an error; a null sensor_msgs/CameraInfo being provided in that case.

Raises:IOError if an existing calibration is unreadable.
setCameraInfo(req)[source]

Callback for SetCameraInfo request.

Parameters:req – SetCameraInfo request message.
Returns:SetCameraInfo response message, success is True if message handled.
Post:camera_info updated, can be used immediately without reloading.
setCameraName(cname)[source]

Set a new camera name.

Parameters:cname – camera name to use for saving calibration data
Returns:True if new name has valid syntax; valid names contain only alphabetic, numeric, or ‘_’ characters.
Post:camera name updated, if valid. A new name may affect the URL, so camera_info will have to be reloaded before being used again.
setURL(url)[source]

Set the calibration URL.

Parameters:cname – camera name to use for saving calibration data
Returns:True if new name has valid syntax.
Post:URL updated, if valid. A new value may change the camera_info, so it will have to be reloaded before being used again.
camera_info_manager.genCameraName(from_string)[source]

Generate a valid camera name.

Valid names contain only alphabetic, numeric, or ‘_’ characters. All invalid characters in from_string are replaced by an ‘_’.

Parameters:from_string – string from which to base camera name.
Returns:a valid camera name based on from_string.
camera_info_manager.getPackageFileName(url)[source]

Get file name corresponding to a package: URL.

param url fully-resolved Uniform Resource Locator returns file name if package found, “” otherwise

camera_info_manager.loadCalibrationFile(filename, cname)[source]

Load calibration data from a file.

This function returns a sensor_msgs/CameraInfo message, based on the filename parameter. An empty or non-existent file is not considered an error; a null CameraInfo being provided in that case.

Parameters:
  • filename – location of CameraInfo to read
  • cname – Camera name.
Returns:

sensor_msgs/CameraInfo message containing calibration, if file readable; null calibration message otherwise.

Raises:

IOError if an existing calibration file is unreadable.

camera_info_manager.parseURL(url)[source]

Parse calibration Uniform Resource Locator.

param url: string to parse returns URL type code

note: Unsupported URL types have codes >= URL_invalid.

camera_info_manager.resolveURL(url, cname)[source]

Resolve substitution strings in Uniform Resource Locator.

Parameters:
  • url – URL to resolve, which may include ${...} substitution variables.
  • cname – camera name for resolving ${NAME} variables.
Returns:

a copy of the URL with any variable information resolved.

camera_info_manager.saveCalibration(new_info, url, cname)[source]

Save calibration data.

This function writes new calibration information to the location defined by the url and cname parameters, if possible.

Parameters:
  • new_infosensor_msgs/CameraInfo to save.
  • url – Uniform Resource Locator for calibration data (if empty use file://${ROS_HOME}/camera_info/${NAME}.yaml).
  • cname – Camera name.
Returns:

True if able to save the data.

camera_info_manager.saveCalibrationFile(ci, filename, cname)[source]

Save calibration data to a YAML file.

This function writes the new calibration information to a YAML file, if possible.

Parameters:
Returns:

True if able to save the data.