Go to the documentation of this file.
52 #include <sensor_msgs/CameraInfo.h>
170 const std::string&
url,
const std::string& cname,
const cras::optional<double>&
focalLength);
220 const std::string&
url,
const std::string& cname,
const cras::optional<double>&
focalLength);
250 sensor_msgs::CameraInfo
camInfo {};
Provides CameraInfo data for a calibrated camera. Different from camera_info_manager::CameraInfoManag...
static URL parseURL(const std::string &url)
Parse the type of the URL.
std::string cameraName
Camera name.
virtual bool setCameraName(const std::string &cname)
Set or change the name of the camera that should currently be represented by this class.
virtual bool loadCalibration(const std::string &url, const std::string &cname, const cras::optional< double > &focalLength)
Load calibration according to camera info URL.
virtual bool loadCalibrationFlash(const std::string &flashURL, const std::string &cname)
Load calibration from camera flash (not supported, but subclasses can override).
bool loadedCamInfo
Whether camInfo load has been attempted.
virtual bool setFocalLength(double focalLength)
Set or change the focal length of the camera that should currently be represented by this class.
CameraInfoManager(const std::string &cname="camera", const std::string &url="")
Constructor. It does not load the calibration file, that is done lazily when needed.
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.
sensor_msgs::CameraInfo getCameraInfo()
Load and return the camera info assigned to the camera specified in constructor or by calls to setCam...
virtual ~CameraInfoManager()
::cras::LogHelper::Ptr LogHelperPtr
@ INVALID
anything >= is invalid
virtual bool loadCalibrationFile(const std::string &filename, const std::string &cname)
Load calibration from the given file.
sensor_msgs::CameraInfo camInfo
Current CameraInfo.
std::string url
URL for calibration data.
static bool validateURL(const std::string &url)
Validate a camera info URL.
std::string getPackageFileName(const std::string &url) const
Resolve the package:// part of URL with a local file.
cras::optional< double > focalLength
Current focal length.