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>

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... | |
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).
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.
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:
${NAME} resolved to the current camera name defined by the device driver.${ROS_HOME} resolved to the $ROS_HOME environment variable if defined, or ~/.ros if not.${FOCAL_LENGTH} resolved to the focal length of the camera. By default, the focal length is formatted by string %0.01fmm, but it can be changed by specifying another format string, e.g. ${FOCAL_LENGTH:%0.04f_mm}.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.
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.
|
strongprotected |
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.
|
explicit |
Constructor. It does not load the calibration file, that is done lazily when needed.
| [in] | cname | Name of the camera (used in URL). |
| [in] | url | The URL specifying path to the calibration file (substitution keywords can be used). |
|
explicit |
Constructor. It does not load the calibration file, that is done lazily when needed.
| [in] | log | Logger. |
| [in] | cname | Name of the camera (used in URL). |
| [in] | url | The URL specifying path to the calibration file (substitution keywords can be used). |
|
virtual |
| 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().
|
private |
Resolve the package:// part of URL with a local file.
| [in] | url | The package:// URL. |
| bool camera_info_manager_lib::CameraInfoManager::isCalibrated | ( | ) |
|
protectedvirtual |
Load calibration according to camera info URL.
| [in] | url | Camera info URL (can contain substitution keywords). |
| [in] | cname | Name of the camera. |
| [in] | focalLength | Focal length of the camera [mm]. |
|
protectedvirtual |
Load calibration from the given file.
| [in] | filename | Calibration file. |
| [in] | cname | Camera name. |
|
protectedvirtual |
Load calibration from camera flash (not supported, but subclasses can override).
| [in] | flashURL | Flash URL. |
| [in] | cname | Camera name. |
|
staticprotected |
Parse the type of the URL.
| [in] | url | The URL to parse. |
|
static |
Resolve substitution keywords in the given URL.
| [in] | log | Logger. |
| [in] | url | The URL to resolve. |
| [in] | cname | Camera name. |
| [in] | focalLength | Focal length [mm]. |
|
virtual |
Set or change the name of the camera that should currently be represented by this class.
| [in] | cname | New camera name. |
|
virtual |
Set or change the focal length of the camera that should currently be represented by this class.
| [in] | focalLength | New focal length [mm]. |
|
static |
Validate a camera info URL.
| [in] | url | The URL to validate. |
|
protected |
Camera name.
Definition at line 313 of file camera_info_manager.h.
|
protected |
Current CameraInfo.
Definition at line 316 of file camera_info_manager.h.
|
protected |
Current focal length.
Definition at line 314 of file camera_info_manager.h.
|
protected |
Whether camInfo load has been attempted.
Definition at line 317 of file camera_info_manager.h.
|
protected |
URL for calibration data.
Definition at line 315 of file camera_info_manager.h.