38 #ifndef _CAMERA_INFO_MANAGER_H_ 39 #define _CAMERA_INFO_MANAGER_H_ 42 #include <boost/thread/mutex.hpp> 43 #include <sensor_msgs/CameraInfo.h> 44 #include <sensor_msgs/SetCameraInfo.h> 50 #ifdef ROS_BUILD_SHARED_LIBS // ros is being built around shared libraries 51 #ifdef camera_info_manager_EXPORTS // we are building a shared lib/dll 52 #define CAMERA_INFO_MANAGER_DECL ROS_HELPER_EXPORT 53 #else // we are using shared lib/dll 54 #define CAMERA_INFO_MANAGER_DECL ROS_HELPER_IMPORT 56 #else // ros is being built around static libraries 57 #define CAMERA_INFO_MANAGER_DECL 193 const std::string &cname=
"camera",
194 const std::string &url=
"");
196 sensor_msgs::CameraInfo getCameraInfo(
void);
197 bool isCalibrated(
void);
198 bool loadCameraInfo(
const std::string &url);
199 std::string resolveURL(
const std::string &url,
200 const std::string &cname);
201 bool setCameraName(
const std::string &cname);
202 bool setCameraInfo(
const sensor_msgs::CameraInfo &camera_info);
203 bool validateURL(
const std::string &url);
220 std::string getPackageFileName(
const std::string &url);
221 bool loadCalibration(
const std::string &url,
222 const std::string &cname);
223 bool loadCalibrationFile(
const std::string &filename,
224 const std::string &cname);
225 url_type_t parseURL(
const std::string &url);
226 bool saveCalibration(
const sensor_msgs::CameraInfo &new_info,
227 const std::string &url,
228 const std::string &cname);
229 bool saveCalibrationFile(
const sensor_msgs::CameraInfo &new_info,
230 const std::string &filename,
231 const std::string &cname);
232 bool setCameraInfoService(sensor_msgs::SetCameraInfo::Request &req,
233 sensor_msgs::SetCameraInfo::Response &rsp);
257 #endif // _CAMERA_INFO_MANAGER_H_
bool loaded_cam_info_
cam_info_ load attempted
std::string url_
URL for calibration data.
ros::ServiceServer info_service_
set_camera_info service
sensor_msgs::CameraInfo cam_info_
current CameraInfo
boost::mutex mutex_
mutual exclusion lock for private data
ros::NodeHandle nh_
node handle for service
#define CAMERA_INFO_MANAGER_DECL
CameraInfo Manager class.
std::string camera_name_
camera name