driver.cpp
Go to the documentation of this file.
1 // Copyright [2015] Takashi Ogura<t.ogura@gmail.com>
2 
3 #include "cv_camera/driver.h"
4 #include <string>
5 
6 namespace
7 {
8 const double DEFAULT_RATE = 30.0;
9 const int32_t PUBLISHER_BUFFER_SIZE = 1;
10 }
11 
12 namespace cv_camera
13 {
14 
15 Driver::Driver(ros::NodeHandle &private_node, ros::NodeHandle &camera_node)
16  : private_node_(private_node),
17  camera_node_(camera_node)
18 {
19 }
20 
22 {
23  double hz(DEFAULT_RATE);
24  int32_t device_id(0);
25  std::string device_path("");
26  std::string frame_id("camera");
27  std::string file_path("");
28  std::string camera_name("");
29 
30  private_node_.getParam("device_id", device_id);
31  private_node_.getParam("frame_id", frame_id);
32  private_node_.getParam("rate", hz);
33  if (!private_node_.getParam("camera_name", camera_name))
34  {
35  camera_name = frame_id;
36  }
37 
38  int32_t image_width(640);
39  int32_t image_height(480);
40 
41  camera_.reset(new Capture(camera_node_,
42  "image_raw",
43  PUBLISHER_BUFFER_SIZE,
44  frame_id,
45  camera_name));
46 
47  if (private_node_.getParam("file", file_path) && file_path != "")
48  {
49  camera_->openFile(file_path);
50  }
51  else if (private_node_.getParam("device_path", device_path) && device_path != "")
52  {
53  camera_->open(device_path);
54  }
55  else
56  {
57  camera_->open(device_id);
58  }
59  if (private_node_.getParam("image_width", image_width))
60  {
61  if (!camera_->setWidth(image_width))
62  {
63  ROS_WARN("fail to set image_width");
64  }
65  }
66  if (private_node_.getParam("image_height", image_height))
67  {
68  if (!camera_->setHeight(image_height))
69  {
70  ROS_WARN("fail to set image_height");
71  }
72  }
73 
74  camera_->setPropertyFromParam(cv::CAP_PROP_POS_MSEC, "cv_cap_prop_pos_msec");
75  camera_->setPropertyFromParam(cv::CAP_PROP_POS_AVI_RATIO, "cv_cap_prop_pos_avi_ratio");
76  camera_->setPropertyFromParam(cv::CAP_PROP_FRAME_WIDTH, "cv_cap_prop_frame_width");
77  camera_->setPropertyFromParam(cv::CAP_PROP_FRAME_HEIGHT, "cv_cap_prop_frame_height");
78  camera_->setPropertyFromParam(cv::CAP_PROP_FPS, "cv_cap_prop_fps");
79  camera_->setPropertyFromParam(cv::CAP_PROP_FOURCC, "cv_cap_prop_fourcc");
80  camera_->setPropertyFromParam(cv::CAP_PROP_FRAME_COUNT, "cv_cap_prop_frame_count");
81  camera_->setPropertyFromParam(cv::CAP_PROP_FORMAT, "cv_cap_prop_format");
82  camera_->setPropertyFromParam(cv::CAP_PROP_MODE, "cv_cap_prop_mode");
83  camera_->setPropertyFromParam(cv::CAP_PROP_BRIGHTNESS, "cv_cap_prop_brightness");
84  camera_->setPropertyFromParam(cv::CAP_PROP_CONTRAST, "cv_cap_prop_contrast");
85  camera_->setPropertyFromParam(cv::CAP_PROP_SATURATION, "cv_cap_prop_saturation");
86  camera_->setPropertyFromParam(cv::CAP_PROP_HUE, "cv_cap_prop_hue");
87  camera_->setPropertyFromParam(cv::CAP_PROP_GAIN, "cv_cap_prop_gain");
88  camera_->setPropertyFromParam(cv::CAP_PROP_EXPOSURE, "cv_cap_prop_exposure");
89  camera_->setPropertyFromParam(cv::CAP_PROP_CONVERT_RGB, "cv_cap_prop_convert_rgb");
90 
91  camera_->setPropertyFromParam(cv::CAP_PROP_RECTIFICATION, "cv_cap_prop_rectification");
92  camera_->setPropertyFromParam(cv::CAP_PROP_ISO_SPEED, "cv_cap_prop_iso_speed");
93  camera_->setPropertyFromParam(cv::CAP_PROP_WHITE_BALANCE_BLUE_U, "cv_cap_prop_white_balance_u");
94  camera_->setPropertyFromParam(cv::CAP_PROP_WHITE_BALANCE_RED_V, "cv_cap_prop_white_balance_v");
95  camera_->setPropertyFromParam(cv::CAP_PROP_BUFFERSIZE, "cv_cap_prop_buffersize");
96 
97  rate_.reset(new ros::Rate(hz));
98 }
99 
101 {
102  if (camera_->capture())
103  {
104  camera_->publish();
105  }
106  rate_->sleep();
107 }
108 
110 {
111 }
112 
113 } // namespace cv_camera
boost::shared_ptr< ros::Rate > rate_
publishing rate.
Definition: driver.h:59
ros::NodeHandle camera_node_
ROS private node for publishing images.
Definition: driver.h:50
ros::NodeHandle private_node_
ROS private node for getting ROS parameters.
Definition: driver.h:46
#define ROS_WARN(...)
captures by cv::VideoCapture and publishes to ROS topic.
Definition: capture.h:27
Driver(ros::NodeHandle &private_node, ros::NodeHandle &camera_node)
construct with ROS node handles.
Definition: driver.cpp:15
namespace of this package
Definition: capture.h:20
void proceed()
Capture, publish and sleep.
Definition: driver.cpp:100
boost::shared_ptr< Capture > camera_
wrapper of cv::VideoCapture.
Definition: driver.h:54
bool getParam(const std::string &key, std::string &s) const
void setup()
Setup camera device and ROS parameters.
Definition: driver.cpp:21


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