capture.h
Go to the documentation of this file.
00001 // Copyright [2015] Takashi Ogura<t.ogura@gmail.com>
00002 
00003 #ifndef CV_CAMERA_CAPTURE_H
00004 #define CV_CAMERA_CAPTURE_H
00005 
00006 #include "cv_camera/exception.h"
00007 #include <string>
00008 
00009 #include <ros/ros.h>
00010 #include <cv_bridge/cv_bridge.h>
00011 #include <image_transport/image_transport.h>
00012 #include <sensor_msgs/CameraInfo.h>
00013 #include <sensor_msgs/image_encodings.h>
00014 #include <opencv2/highgui/highgui.hpp>
00015 #include <camera_info_manager/camera_info_manager.h>
00016 
00020 namespace cv_camera
00021 {
00022 
00027 class Capture
00028 {
00029 public:
00038   Capture(ros::NodeHandle &node,
00039           const std::string &topic_name,
00040           int32_t buffer_size,
00041           const std::string &frame_id);
00042 
00050   void open(int32_t device_id);
00051 
00058   void open(const std::string &device_path);
00059 
00065   void loadCameraInfo();
00066 
00074   void open();
00075 
00079   void openFile(const std::string &file_path);
00080 
00087   bool capture();
00088 
00093   void publish();
00094 
00102   inline const sensor_msgs::CameraInfo &getInfo() const
00103   {
00104     return info_;
00105   }
00106 
00114   inline const cv::Mat &getCvImage() const
00115   {
00116     return bridge_.image;
00117   }
00118 
00126   inline const sensor_msgs::ImagePtr getImageMsgPtr() const
00127   {
00128     return bridge_.toImageMsg();
00129   }
00130 
00135   inline bool setWidth(int32_t width)
00136   {
00137     return cap_.set(CV_CAP_PROP_FRAME_WIDTH, width);
00138   }
00139 
00144   inline bool setHeight(int32_t height)
00145   {
00146     return cap_.set(CV_CAP_PROP_FRAME_HEIGHT, height);
00147   }
00148 
00153   bool setPropertyFromParam(int property_id, const std::string &param_name);
00154 
00155 private:
00159   void rescaleCameraInfo(int width, int height);
00160 
00164   ros::NodeHandle node_;
00165 
00169   image_transport::ImageTransport it_;
00170 
00174   std::string topic_name_;
00175 
00179   std::string frame_id_;
00183   int32_t buffer_size_;
00184 
00188   image_transport::CameraPublisher pub_;
00189 
00193   cv::VideoCapture cap_;
00194 
00198   cv_bridge::CvImage bridge_;
00199 
00205   sensor_msgs::CameraInfo info_;
00206 
00210   camera_info_manager::CameraInfoManager info_manager_;
00211 
00215   bool rescale_camera_info_;
00216 
00220   ros::Duration capture_delay_;
00221 };
00222 
00223 } // namespace cv_camera
00224 
00225 #endif // CV_CAMERA_CAPTURE_H


cv_camera
Author(s): Takashi Ogura
autogenerated on Thu May 9 2019 02:53:02