camera_info_manager::CameraInfoManager Class Reference

#include <camera_info_manager.h>

List of all members.

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.

Detailed Description

Definition at line 88 of file camera_info_manager.h.


Member Enumeration Documentation

Enumerator:
URL_empty 
URL_file 
URL_package 
URL_invalid 
URL_flash 

Definition at line 125 of file camera_info_manager.h.


Constructor & Destructor Documentation

camera_info_manager::CameraInfoManager::CameraInfoManager ( ros::NodeHandle  nh,
const std::string &  cname = "camera",
const std::string &  url = "" 
)

Member Function Documentation

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.

Warning:
The caller must fill in the CameraInfo message Header. The time stamp and frame_id should normally be the same as the corresponding Image message Header fields.

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  ) 

Member Data Documentation

sensor_msgs::CameraInfo camera_info_manager::CameraInfoManager::cam_info_ [private]

current CameraInfo

Definition at line 164 of file camera_info_manager.h.

camera name

Definition at line 162 of file camera_info_manager.h.

set_camera_info service

Definition at line 161 of file camera_info_manager.h.

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.

node handle for service

Definition at line 160 of file camera_info_manager.h.

URL for calibration data.

Definition at line 163 of file camera_info_manager.h.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Enumerations Enumerator


camera_info_manager
Author(s): Jack O'Quin
autogenerated on Fri Jan 11 10:03:44 2013