capture.cpp
Go to the documentation of this file.
1 // Copyright [2015] Takashi Ogura<t.ogura@gmail.com>
2 
3 #include "cv_camera/capture.h"
4 #include <sstream>
5 #include <string>
6 
7 namespace cv_camera
8 {
9 
11 
12 Capture::Capture(ros::NodeHandle &node, const std::string &topic_name,
13  int32_t buffer_size, const std::string &frame_id,
14  const std::string& camera_name)
15  : node_(node),
16  it_(node_),
17  topic_name_(topic_name),
18  buffer_size_(buffer_size),
19  frame_id_(frame_id),
20  info_manager_(node_, camera_name),
21  capture_delay_(ros::Duration(node_.param("capture_delay", 0.0)))
22 {
23 }
24 
26 {
27  std::string url;
28  if (node_.getParam("camera_info_url", url))
29  {
30  if (info_manager_.validateURL(url))
31  {
33  }
34  }
35 
36  rescale_camera_info_ = node_.param<bool>("rescale_camera_info", false);
37 
38  for (int i = 0;; ++i)
39  {
40  int code = 0;
41  double value = 0.0;
42  std::stringstream stream;
43  stream << "property_" << i << "_code";
44  const std::string param_for_code = stream.str();
45  stream.str("");
46  stream << "property_" << i << "_value";
47  const std::string param_for_value = stream.str();
48  if (!node_.getParam(param_for_code, code) || !node_.getParam(param_for_value, value))
49  {
50  break;
51  }
52  if (!cap_.set(code, value))
53  {
54  ROS_ERROR_STREAM("Setting with code " << code << " and value " << value << " failed"
55  << std::endl);
56  }
57  }
58 }
59 
60 void Capture::rescaleCameraInfo(int width, int height)
61 {
62  double width_coeff = static_cast<double>(width) / info_.width;
63  double height_coeff = static_cast<double>(height) / info_.height;
64  info_.width = width;
65  info_.height = height;
66 
67  // See http://docs.ros.org/api/sensor_msgs/html/msg/CameraInfo.html for clarification
68  info_.K[0] *= width_coeff;
69  info_.K[2] *= width_coeff;
70  info_.K[4] *= height_coeff;
71  info_.K[5] *= height_coeff;
72 
73  info_.P[0] *= width_coeff;
74  info_.P[2] *= width_coeff;
75  info_.P[5] *= height_coeff;
76  info_.P[6] *= height_coeff;
77 }
78 
79 void Capture::open(int32_t device_id)
80 {
81  cap_.open(device_id);
82  if (!cap_.isOpened())
83  {
84  std::stringstream stream;
85  stream << "device_id" << device_id << " cannot be opened";
86  throw DeviceError(stream.str());
87  }
89 
91 }
92 
93 void Capture::open(const std::string &device_path)
94 {
95  cap_.open(device_path, cv::CAP_V4L);
96  if (!cap_.isOpened())
97  {
98  throw DeviceError("device_path " + device_path + " cannot be opened");
99  }
101 
102  loadCameraInfo();
103 }
104 
106 {
107  open(0);
108 }
109 
110 void Capture::openFile(const std::string &file_path)
111 {
112  cap_.open(file_path);
113  if (!cap_.isOpened())
114  {
115  std::stringstream stream;
116  stream << "file " << file_path << " cannot be opened";
117  throw DeviceError(stream.str());
118  }
120 
121  std::string url;
122  if (node_.getParam("camera_info_url", url))
123  {
124  if (info_manager_.validateURL(url))
125  {
127  }
128  }
129 }
130 
132 {
133  if (cap_.read(bridge_.image))
134  {
136  bridge_.encoding = enc::BGR8;
137  bridge_.header.stamp = stamp;
138  bridge_.header.frame_id = frame_id_;
139 
141  if (info_.height == 0 && info_.width == 0)
142  {
143  info_.height = bridge_.image.rows;
144  info_.width = bridge_.image.cols;
145  }
146  else if (info_.height != bridge_.image.rows || info_.width != bridge_.image.cols)
147  {
149  {
150  int old_width = info_.width;
151  int old_height = info_.height;
153  ROS_INFO_ONCE("Camera calibration automatically rescaled from %dx%d to %dx%d",
154  old_width, old_height, bridge_.image.cols, bridge_.image.rows);
155  }
156  else
157  {
158  ROS_WARN_ONCE("Calibration resolution %dx%d does not match camera resolution %dx%d. "
159  "Use rescale_camera_info param for rescaling",
160  info_.width, info_.height, bridge_.image.cols, bridge_.image.rows);
161  }
162  }
163  info_.header.stamp = stamp;
164  info_.header.frame_id = frame_id_;
165 
166  return true;
167  }
168  return false;
169 }
170 
172 {
174 }
175 
176 bool Capture::setPropertyFromParam(int property_id, const std::string &param_name)
177 {
178  if (cap_.isOpened())
179  {
180  double value = 0.0;
181  if (node_.getParam(param_name, value))
182  {
183  ROS_INFO("setting property %s = %lf", param_name.c_str(), value);
184  return cap_.set(property_id, value);
185  }
186  }
187  return true;
188 }
189 
190 } // namespace cv_camera
image_transport::ImageTransport it_
ROS image transport utility.
Definition: capture.h:171
bool param(const std::string &param_name, T &param_val, const T &default_val)
void publish(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &info) const
bool capture()
capture an image and store.
Definition: capture.cpp:131
sensor_msgs::CameraInfo getCameraInfo(void)
#define ROS_INFO_ONCE(...)
bool loadCameraInfo(const std::string &url)
void open()
Open default camera device.
Definition: capture.cpp:105
ros::NodeHandle node_
node handle for advertise.
Definition: capture.h:166
ROS cv camera device exception.
Definition: exception.h:16
void publish()
Publish the image that is already captured by capture().
Definition: capture.cpp:171
std::string encoding
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
bool validateURL(const std::string &url)
int32_t buffer_size_
size of publisher buffer
Definition: capture.h:185
CameraPublisher advertiseCamera(const std::string &base_topic, uint32_t queue_size, bool latch=false)
#define ROS_WARN_ONCE(...)
#define ROS_INFO(...)
camera_info_manager::CameraInfoManager info_manager_
camera info manager
Definition: capture.h:212
bool param(const std::string &param_name, T &param_val, const T &default_val) const
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
bool getParam(const std::string &key, std::string &s) const
static Time now()
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
#define ROS_ERROR_STREAM(args)
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
std_msgs::Header header
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