00001 #ifndef CV_CAMERA_CAPTURE_H 00002 #define CV_CAMERA_CAPTURE_H 00003 00004 #include "cv_camera/exception.h" 00005 00006 #include <ros/ros.h> 00007 #include <cv_bridge/cv_bridge.h> 00008 #include <image_transport/image_transport.h> 00009 #include <sensor_msgs/CameraInfo.h> 00010 #include <sensor_msgs/image_encodings.h> 00011 #include <opencv2/highgui/highgui.hpp> 00012 #include <camera_info_manager/camera_info_manager.h> 00013 00017 namespace cv_camera { 00018 00023 class Capture { 00024 public: 00033 Capture(ros::NodeHandle& node, 00034 const std::string& topic_name, 00035 int32_t buffer_size, 00036 const std::string& frame_id); 00037 00045 void open(int32_t device_id); 00046 00054 void open(); 00055 00059 void openFile(const std::string& file_path); 00060 00067 bool capture(); 00068 00073 void publish(); 00074 00082 const sensor_msgs::CameraInfo& getInfo() const 00083 { 00084 return info_; 00085 } 00086 00094 const cv::Mat& getCvImage() const 00095 { 00096 return bridge_.image; 00097 } 00098 00106 const sensor_msgs::ImagePtr getImageMsgPtr() const 00107 { 00108 return bridge_.toImageMsg(); 00109 } 00110 00115 bool setWidth(int32_t width) { 00116 return cap_.set(CV_CAP_PROP_FRAME_WIDTH, width); 00117 } 00118 00123 bool setHeight(int32_t height) { 00124 return cap_.set(CV_CAP_PROP_FRAME_HEIGHT, height); 00125 } 00126 00127 private: 00128 00132 ros::NodeHandle node_; 00133 00137 image_transport::ImageTransport it_; 00138 00142 std::string topic_name_; 00143 00147 std::string frame_id_; 00151 int32_t buffer_size_; 00152 00156 image_transport::CameraPublisher pub_; 00157 00161 cv::VideoCapture cap_; 00162 00166 cv_bridge::CvImage bridge_; 00167 00173 sensor_msgs::CameraInfo info_; 00174 00178 camera_info_manager::CameraInfoManager info_manager_; 00179 }; 00180 00181 } // end namespace 00182 00183 #endif // end CV_CAMERA_CAPTURE_H