00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 #ifndef _CAMERA_INFO_MANAGER_H_
00039 #define _CAMERA_INFO_MANAGER_H_
00040
00041 #include <ros/ros.h>
00042 #include <boost/thread/mutex.hpp>
00043 #include <sensor_msgs/CameraInfo.h>
00044 #include <sensor_msgs/SetCameraInfo.h>
00045
00053 namespace camera_info_manager
00054 {
00055
00160 class CameraInfoManager
00161 {
00162 public:
00163
00164 CameraInfoManager(ros::NodeHandle nh,
00165 const std::string &cname="camera",
00166 const std::string &url="");
00167
00178 sensor_msgs::CameraInfo getCameraInfo(void)
00179 {
00180 boost::mutex::scoped_lock lock_(mutex_);
00181 return cam_info_;
00182 }
00183
00185 bool isCalibrated(void)
00186 {
00187 boost::mutex::scoped_lock lock_(mutex_);
00188 return (cam_info_.K[0] != 0.0);
00189 }
00190
00191 bool loadCameraInfo(const std::string &url);
00192 std::string resolveURL(const std::string &url,
00193 const std::string &cname);
00194 bool setCameraName(const std::string &cname);
00195 bool validateURL(const std::string &url);
00196
00197 private:
00198
00199
00200 typedef enum
00201 {
00202
00203 URL_empty = 0,
00204 URL_file,
00205 URL_package,
00206
00207 URL_invalid,
00208 URL_flash,
00209 } url_type_t;
00210
00211
00212 std::string getPackageFileName(const std::string &url);
00213 bool loadCalibration(const std::string &url,
00214 const std::string &cname);
00215 bool loadCalibrationFile(const std::string &filename,
00216 const std::string &cname);
00217 url_type_t parseURL(const std::string &url);
00218 bool saveCalibration(const sensor_msgs::CameraInfo &new_info,
00219 const std::string &url,
00220 const std::string &cname);
00221 bool saveCalibrationFile(const sensor_msgs::CameraInfo &new_info,
00222 const std::string &filename,
00223 const std::string &cname);
00224 bool setCameraInfo(sensor_msgs::SetCameraInfo::Request &req,
00225 sensor_msgs::SetCameraInfo::Response &rsp);
00226
00235 boost::mutex mutex_;
00236
00237
00238 ros::NodeHandle nh_;
00239 ros::ServiceServer info_service_;
00240 std::string camera_name_;
00241 std::string url_;
00242 sensor_msgs::CameraInfo cam_info_;
00243
00244 };
00245
00246 };
00247
00248
00249 typedef camera_info_manager::CameraInfoManager __attribute__((deprecated)) CameraInfoManager;
00250
00251 #endif // _CAMERA_INFO_MANAGER_H_