Class CameraInfoManager

Class Documentation

class CameraInfoManager

CameraInfo Manager class.

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

  • set_camera_info (sensor_msgs/SetCameraInfo) stores calibration information

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.

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.

Camera Name

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.

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.

Uniform Resource Locator

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 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:

  • ${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:

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.

Prior to Fuerte, calibration information was loaded in the constructor, and again each time the URL or camera name was updated. This frequently caused logging of confusing and misleading error messages.

Loading Calibration Data

Beginning in Fuerte, camera_info_manager loads nothing until the loadCameraInfo(), isCalibrated() or 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.

Public Functions

CAMERA_INFO_MANAGER_PUBLIC CameraInfoManager(rclcpp::Node *node, const std::string &cname = "camera", const std::string &url = "")
CAMERA_INFO_MANAGER_PUBLIC CameraInfoManager(rclcpp_lifecycle::LifecycleNode *node, const std::string &cname = "camera", const std::string &url = "")
CAMERA_INFO_MANAGER_PUBLIC CameraInfoManager(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface, rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface, rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logger_interface, const std::string &cname = "camera", const std::string &url = "", rmw_qos_profile_t custom_qos = rmw_qos_profile_default)
CAMERA_INFO_MANAGER_PUBLIC CameraInfo getCameraInfo (void)
CAMERA_INFO_MANAGER_PUBLIC bool isCalibrated (void)
CAMERA_INFO_MANAGER_PUBLIC bool loadCameraInfo (const std::string &url)
CAMERA_INFO_MANAGER_PUBLIC std::string resolveURL (const std::string &url, const std::string &cname)
CAMERA_INFO_MANAGER_PUBLIC bool setCameraName (const std::string &cname)
CAMERA_INFO_MANAGER_PUBLIC bool setCameraInfo (const CameraInfo &camera_info)
CAMERA_INFO_MANAGER_PUBLIC bool validateURL (const std::string &url)