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:
40  const std::string &topic_name,
41  int32_t buffer_size,
42  const std::string &frame_id,
43  const std::string &camera_name);
44 
52  void open(int32_t device_id);
53 
60  void open(const std::string &device_path);
61 
67  void loadCameraInfo();
68 
76  void open();
77 
81  void openFile(const std::string &file_path);
82 
89  bool capture();
90 
95  void publish();
96 
104  inline const sensor_msgs::CameraInfo &getInfo() const
105  {
106  return info_;
107  }
108 
116  inline const cv::Mat &getCvImage() const
117  {
118  return bridge_.image;
119  }
120 
128  inline const sensor_msgs::ImagePtr getImageMsgPtr() const
129  {
130  return bridge_.toImageMsg();
131  }
132 
137  inline bool setWidth(int32_t width)
138  {
139  return cap_.set(cv::CAP_PROP_FRAME_WIDTH, width);
140  }
141 
146  inline bool setHeight(int32_t height)
147  {
148  return cap_.set(cv::CAP_PROP_FRAME_HEIGHT, height);
149  }
150 
155  bool setPropertyFromParam(int property_id, const std::string &param_name);
156 
157 private:
161  void rescaleCameraInfo(int width, int height);
162 
167 
172 
176  std::string topic_name_;
177 
181  std::string frame_id_;
185  int32_t buffer_size_;
186 
191 
195  cv::VideoCapture cap_;
196 
201 
207  sensor_msgs::CameraInfo info_;
208 
213 
218 
223 };
224 
225 } // namespace cv_camera
226 
227 #endif // CV_CAMERA_CAPTURE_H
image_transport::ImageTransport it_
ROS image transport utility.
Definition: capture.h:171
bool setHeight(int32_t height)
try capture image height
Definition: capture.h:146
bool capture()
capture an image and store.
Definition: capture.cpp:131
const cv::Mat & getCvImage() const
accessor of cv::Mat
Definition: capture.h:116
void open()
Open default camera device.
Definition: capture.cpp:105
ros::NodeHandle node_
node handle for advertise.
Definition: capture.h:166
void publish()
Publish the image that is already captured by capture().
Definition: capture.cpp:171
image_transport::CameraPublisher pub_
image publisher created by image_transport::ImageTransport.
Definition: capture.h:190
void loadCameraInfo()
Load camera info from file.
Definition: capture.cpp:25
captures by cv::VideoCapture and publishes to ROS topic.
Definition: capture.h:27
int32_t buffer_size_
size of publisher buffer
Definition: capture.h:185
bool setWidth(int32_t width)
try capture image width
Definition: capture.h:137
camera_info_manager::CameraInfoManager info_manager_
camera info manager
Definition: capture.h:212
namespace of this package
Definition: capture.h:20
cv_bridge::CvImage bridge_
this stores last captured image.
Definition: capture.h:200
void openFile(const std::string &file_path)
open video file instead of capture device.
Definition: capture.cpp:110
std::string topic_name_
name of topic without namespace (usually "image_raw").
Definition: capture.h:176
cv::VideoCapture cap_
capture device.
Definition: capture.h:195
bool setPropertyFromParam(int property_id, const std::string &param_name)
set CV_PROP_*
Definition: capture.cpp:176
ros::Duration capture_delay_
capture_delay param value
Definition: capture.h:222
std::string frame_id_
header.frame_id for publishing images.
Definition: capture.h:181
void rescaleCameraInfo(int width, int height)
rescale camera calibration to another resolution
Definition: capture.cpp:60
Capture(ros::NodeHandle &node, const std::string &topic_name, int32_t buffer_size, const std::string &frame_id, const std::string &camera_name)
costruct with ros node and topic settings
Definition: capture.cpp:12
const sensor_msgs::CameraInfo & getInfo() const
accessor of CameraInfo.
Definition: capture.h:104
const sensor_msgs::ImagePtr getImageMsgPtr() const
accessor of ROS Image message.
Definition: capture.h:128
sensor_msgs::CameraInfo info_
this stores last captured image info.
Definition: capture.h:207
sensor_msgs::ImagePtr toImageMsg() const
bool rescale_camera_info_
rescale_camera_info param value
Definition: capture.h:217


cv_camera
Author(s): Takashi Ogura
autogenerated on Mon Jun 1 2020 03:55:59