capture.h
Go to the documentation of this file.
1 // Copyright [2015] Takashi Ogura<t.ogura@gmail.com>
2 
3 #ifndef CV_CAMERA_CAPTURE_H
4 #define CV_CAMERA_CAPTURE_H
5 
6 #include "cv_camera/exception.h"
7 #include <string>
8 
9 #include <ros/ros.h>
10 #include <cv_bridge/cv_bridge.h>
12 #include <sensor_msgs/CameraInfo.h>
14 #include <opencv2/highgui/highgui.hpp>
16 
20 namespace cv_camera
21 {
22 
27 class Capture
28 {
29 public:
39  const std::string &topic_name,
40  int32_t buffer_size,
41  const std::string &frame_id);
42 
50  void open(int32_t device_id);
51 
58  void open(const std::string &device_path);
59 
65  void loadCameraInfo();
66 
74  void open();
75 
79  void openFile(const std::string &file_path);
80 
87  bool capture();
88 
93  void publish();
94 
102  inline const sensor_msgs::CameraInfo &getInfo() const
103  {
104  return info_;
105  }
106 
114  inline const cv::Mat &getCvImage() const
115  {
116  return bridge_.image;
117  }
118 
126  inline const sensor_msgs::ImagePtr getImageMsgPtr() const
127  {
128  return bridge_.toImageMsg();
129  }
130 
135  inline bool setWidth(int32_t width)
136  {
137  return cap_.set(CV_CAP_PROP_FRAME_WIDTH, width);
138  }
139 
144  inline bool setHeight(int32_t height)
145  {
146  return cap_.set(CV_CAP_PROP_FRAME_HEIGHT, height);
147  }
148 
153  bool setPropertyFromParam(int property_id, const std::string &param_name);
154 
155 private:
159  void rescaleCameraInfo(int width, int height);
160 
165 
170 
174  std::string topic_name_;
175 
179  std::string frame_id_;
183  int32_t buffer_size_;
184 
189 
193  cv::VideoCapture cap_;
194 
199 
205  sensor_msgs::CameraInfo info_;
206 
211 
216 
221 };
222 
223 } // namespace cv_camera
224 
225 #endif // CV_CAMERA_CAPTURE_H
image_transport::ImageTransport it_
ROS image transport utility.
Definition: capture.h:169
bool setHeight(int32_t height)
try capture image height
Definition: capture.h:144
bool capture()
capture an image and store.
Definition: capture.cpp:130
Capture(ros::NodeHandle &node, const std::string &topic_name, int32_t buffer_size, const std::string &frame_id)
costruct with ros node and topic settings
Definition: capture.cpp:12
const cv::Mat & getCvImage() const
accessor of cv::Mat
Definition: capture.h:114
void open()
Open default camera device.
Definition: capture.cpp:104
ros::NodeHandle node_
node handle for advertise.
Definition: capture.h:164
void publish()
Publish the image that is already captured by capture().
Definition: capture.cpp:170
image_transport::CameraPublisher pub_
image publisher created by image_transport::ImageTransport.
Definition: capture.h:188
void loadCameraInfo()
Load camera info from file.
Definition: capture.cpp:24
captures by cv::VideoCapture and publishes to ROS topic.
Definition: capture.h:27
int32_t buffer_size_
size of publisher buffer
Definition: capture.h:183
bool setWidth(int32_t width)
try capture image width
Definition: capture.h:135
camera_info_manager::CameraInfoManager info_manager_
camera info manager
Definition: capture.h:210
namespace of this package
Definition: capture.h:20
cv_bridge::CvImage bridge_
this stores last captured image.
Definition: capture.h:198
void openFile(const std::string &file_path)
open video file instead of capture device.
Definition: capture.cpp:109
std::string topic_name_
name of topic without namespace (usually "image_raw").
Definition: capture.h:174
cv::VideoCapture cap_
capture device.
Definition: capture.h:193
bool setPropertyFromParam(int property_id, const std::string &param_name)
set CV_PROP_*
Definition: capture.cpp:175
ros::Duration capture_delay_
capture_delay param value
Definition: capture.h:220
std::string frame_id_
header.frame_id for publishing images.
Definition: capture.h:179
void rescaleCameraInfo(int width, int height)
rescale camera calibration to another resolution
Definition: capture.cpp:59
const sensor_msgs::CameraInfo & getInfo() const
accessor of CameraInfo.
Definition: capture.h:102
const sensor_msgs::ImagePtr getImageMsgPtr() const
accessor of ROS Image message.
Definition: capture.h:126
sensor_msgs::CameraInfo info_
this stores last captured image info.
Definition: capture.h:205
sensor_msgs::ImagePtr toImageMsg() const
bool rescale_camera_info_
rescale_camera_info param value
Definition: capture.h:215


cv_camera
Author(s): Takashi Ogura
autogenerated on Fri May 10 2019 02:14:17