#include <camera_info_manager.h>
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) |
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_ |
ros::NodeHandle | nh_ |
node handle for service | |
std::string | url_ |
URL for calibration data. |
Definition at line 88 of file camera_info_manager.h.
enum camera_info_manager::CameraInfoManager::url_type_t [private] |
Definition at line 125 of file camera_info_manager.h.
camera_info_manager::CameraInfoManager::CameraInfoManager | ( | ros::NodeHandle | nh, | |
const std::string & | cname = "camera" , |
|||
const std::string & | url = "" | |||
) |
sensor_msgs::CameraInfo camera_info_manager::CameraInfoManager::getCameraInfo | ( | void | ) | [inline] |
Returns the current CameraInfo data.
The matrices are all zeros if no calibration was available. The image pipeline handles that as uncalibrated data.
Definition at line 105 of file camera_info_manager.h.
std::string camera_info_manager::CameraInfoManager::getPackageFileName | ( | const std::string & | url | ) | [private] |
bool camera_info_manager::CameraInfoManager::isCalibrated | ( | void | ) | [inline] |
Returns true if the current CameraInfo is calibrated.
Definition at line 112 of file camera_info_manager.h.
bool camera_info_manager::CameraInfoManager::loadCalibration | ( | const std::string & | url, | |
const std::string & | cname | |||
) | [private] |
bool camera_info_manager::CameraInfoManager::loadCalibrationFile | ( | const std::string & | filename, | |
const std::string & | cname | |||
) | [private] |
bool camera_info_manager::CameraInfoManager::loadCameraInfo | ( | const std::string & | url | ) |
url_type_t camera_info_manager::CameraInfoManager::parseURL | ( | const std::string & | url | ) | [private] |
bool camera_info_manager::CameraInfoManager::saveCalibration | ( | const sensor_msgs::CameraInfo & | new_info, | |
const std::string & | url, | |||
const std::string & | cname | |||
) | [private] |
bool camera_info_manager::CameraInfoManager::saveCalibrationFile | ( | const sensor_msgs::CameraInfo & | new_info, | |
const std::string & | filename, | |||
const std::string & | cname | |||
) | [private] |
bool camera_info_manager::CameraInfoManager::setCameraInfo | ( | sensor_msgs::SetCameraInfo::Request & | req, | |
sensor_msgs::SetCameraInfo::Response & | rsp | |||
) | [private] |
bool camera_info_manager::CameraInfoManager::setCameraName | ( | const std::string & | cname | ) |
bool camera_info_manager::CameraInfoManager::validateURL | ( | const std::string & | url | ) |
sensor_msgs::CameraInfo camera_info_manager::CameraInfoManager::cam_info_ [private] |
current CameraInfo
Definition at line 164 of file camera_info_manager.h.
std::string camera_info_manager::CameraInfoManager::camera_name_ [private] |
camera name
Definition at line 162 of file camera_info_manager.h.
ros::ServiceServer camera_info_manager::CameraInfoManager::info_service_ [private] |
set_camera_info service
Definition at line 161 of file camera_info_manager.h.
boost::mutex camera_info_manager::CameraInfoManager::mutex_ [private] |
This non-recursive mutex is only held for a short time while accessing or changing private class variables. To avoid deadlocks, it is never held during I/O or while invoking a callback.
Definition at line 157 of file camera_info_manager.h.
ros::NodeHandle camera_info_manager::CameraInfoManager::nh_ [private] |
node handle for service
Definition at line 160 of file camera_info_manager.h.
std::string camera_info_manager::CameraInfoManager::url_ [private] |
URL for calibration data.
Definition at line 163 of file camera_info_manager.h.