video_stream.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (Modified BSD License)
3  *
4  * Copyright (c) 2016, PAL Robotics, S.L.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of PAL Robotics, S.L. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *
34  * @author Sammy Pfeiffer
35  */
36 
37 #include <ros/ros.h>
38 #include <nodelet/nodelet.h>
39 #include <dynamic_reconfigure/server.h>
42 #include <opencv2/highgui/highgui.hpp>
43 #include <opencv2/imgproc/imgproc.hpp>
44 #include <cv_bridge/cv_bridge.h>
45 #include <sstream>
46 #include <stdexcept>
47 #include <boost/filesystem.hpp>
48 #include <boost/assign/list_of.hpp>
49 #include <boost/thread/thread.hpp>
50 #include <queue>
51 #include <mutex>
52 #include <video_stream_opencv/VideoStreamConfig.h>
53 
54 namespace fs = boost::filesystem;
55 
57 
59 protected:
63 VideoStreamConfig config;
65 std::queue<cv::Mat> framesQueue;
66 cv::Mat frame;
72 boost::thread capture_thread;
74 sensor_msgs::CameraInfo cam_info_msg;
75 
76 // Based on the ros tutorial on transforming opencv images to Image messages
77 
78 virtual sensor_msgs::CameraInfo get_default_camera_info_from_image(sensor_msgs::ImagePtr img){
79  sensor_msgs::CameraInfo cam_info_msg;
80  cam_info_msg.header.frame_id = img->header.frame_id;
81  // Fill image size
82  cam_info_msg.height = img->height;
83  cam_info_msg.width = img->width;
84  NODELET_INFO_STREAM("The image width is: " << img->width);
85  NODELET_INFO_STREAM("The image height is: " << img->height);
86  // Add the most common distortion model as sensor_msgs/CameraInfo says
87  cam_info_msg.distortion_model = "plumb_bob";
88  // Don't let distorsion matrix be empty
89  cam_info_msg.D.resize(5, 0.0);
90  // Give a reasonable default intrinsic camera matrix
91  cam_info_msg.K = boost::assign::list_of(img->width/2.0) (0.0) (img->width/2.0)
92  (0.0) (img->height/2.0) (img->height/2.0)
93  (0.0) (0.0) (1.0);
94  // Give a reasonable default rectification matrix
95  cam_info_msg.R = boost::assign::list_of (1.0) (0.0) (0.0)
96  (0.0) (1.0) (0.0)
97  (0.0) (0.0) (1.0);
98  // Give a reasonable default projection matrix
99  cam_info_msg.P = boost::assign::list_of (img->width/2.0) (0.0) (img->width/2.0) (0.0)
100  (0.0) (img->height/2.0) (img->height/2.0) (0.0)
101  (0.0) (0.0) (1.0) (0.0);
102  return cam_info_msg;
103 }
104 
105 
106 virtual void do_capture() {
107  NODELET_DEBUG("Capture thread started");
108  cv::Mat frame;
109  VideoStreamConfig latest_config = config;
110  ros::Rate camera_fps_rate(latest_config.set_camera_fps);
111 
112  int frame_counter = 0;
113  // Read frames as fast as possible
114  capture_thread_running = true;
115  while (nh->ok() && capture_thread_running && subscriber_num > 0) {
116  {
117  std::lock_guard<std::mutex> lock(c_mutex);
118  latest_config = config;
119  }
120  if (!cap->isOpened()) {
121  NODELET_WARN("Waiting for device...");
122  cv::waitKey(100);
123  continue;
124  }
125  if (!cap->read(frame)) {
126  NODELET_ERROR_STREAM_THROTTLE(1.0, "Could not capture frame (frame_counter: " << frame_counter << ")");
127  if (latest_config.reopen_on_read_failure) {
128  NODELET_WARN_STREAM_THROTTLE(1.0, "trying to reopen the device");
129  unsubscribe();
130  subscribe();
131  }
132  }
133 
134  frame_counter++;
135  if (video_stream_provider_type == "videofile")
136  {
137  camera_fps_rate.sleep();
138  }
139  NODELET_DEBUG_STREAM("Current frame_counter: " << frame_counter << " latest_config.stop_frame - latest_config.start_frame: " << latest_config.stop_frame - latest_config.start_frame);
140  if (video_stream_provider_type == "videofile" &&
141  frame_counter >= latest_config.stop_frame - latest_config.start_frame)
142  {
143  if (latest_config.loop_videofile)
144  {
145  cap->open(video_stream_provider);
146  cap->set(cv::CAP_PROP_POS_FRAMES, latest_config.start_frame);
147  frame_counter = 0;
148  NODELET_DEBUG("Reached end of frames, looping.");
149  }
150  else {
151  NODELET_INFO("Reached the end of frames");
152  break;
153  }
154  }
155 
156  if(!frame.empty()) {
157  std::lock_guard<std::mutex> g(q_mutex);
158  // accumulate only until max_queue_size
159  while (framesQueue.size() >= latest_config.buffer_queue_size) {
160  framesQueue.pop();
161  }
162  framesQueue.push(frame.clone());
163  }
164  }
165  NODELET_DEBUG("Capture thread finished");
166 }
167 
168 virtual void do_publish(const ros::TimerEvent& event) {
169  bool is_new_image = false;
170  sensor_msgs::ImagePtr msg;
171  std_msgs::Header header;
172  VideoStreamConfig latest_config;
173 
174  {
175  std::lock_guard<std::mutex> lock(p_mutex);
176  latest_config = config;
177  }
178 
179  header.frame_id = latest_config.frame_id;
180  {
181  std::lock_guard<std::mutex> g(q_mutex);
182  if (!framesQueue.empty()){
183  frame = framesQueue.front();
184  framesQueue.pop();
185  is_new_image = true;
186  }
187  }
188 
189  // Check if grabbed frame is actually filled with some content
190  if(!frame.empty() && is_new_image) {
191  // From http://docs.opencv.org/modules/core/doc/operations_on_arrays.html#void flip(InputArray src, OutputArray dst, int flipCode)
192  // FLIP_HORIZONTAL == 1, FLIP_VERTICAL == 0 or FLIP_BOTH == -1
193  // Flip the image if necessary
194  if (latest_config.flip_horizontal && latest_config.flip_vertical)
195  cv::flip(frame, frame, -1);
196  else if (latest_config.flip_horizontal)
197  cv::flip(frame, frame, 1);
198  else if (latest_config.flip_vertical)
199  cv::flip(frame, frame, 0);
200  cv_bridge::CvImagePtr cv_image =
201  boost::make_shared<cv_bridge::CvImage>(header, "bgr8", frame);
202  if (latest_config.output_encoding != "bgr8")
203  {
204  try {
205  // https://github.com/ros-perception/vision_opencv/blob/melodic/cv_bridge/include/cv_bridge/cv_bridge.h#L247
206  cv_image = cv_bridge::cvtColor(cv_image, latest_config.output_encoding);
207  } catch (std::runtime_error &ex) {
208  NODELET_ERROR_STREAM("cannot change encoding to " << latest_config.output_encoding
209  << ": " << ex.what());
210  }
211  }
212  msg = cv_image->toImageMsg();
213  // Create a default camera info if we didn't get a stored one on initialization
214  if (cam_info_msg.distortion_model == ""){
215  NODELET_WARN_STREAM("No calibration file given, publishing a reasonable default camera info.");
216  cam_info_msg = get_default_camera_info_from_image(msg);
217  }
218  // The timestamps are in sync thanks to this publisher
219  pub.publish(*msg, cam_info_msg, ros::Time::now());
220  }
221 }
222 
223 virtual void subscribe() {
224  ROS_DEBUG("Subscribe");
225  VideoStreamConfig& latest_config = config;
226  // initialize camera info publisher
228  *nh, latest_config.camera_name, latest_config.camera_info_url);
229  // Get the saved camera info if any
230  cam_info_msg = cam_info_manager.getCameraInfo();
231  cam_info_msg.header.frame_id = latest_config.frame_id;
232 
233  // initialize camera
234  cap.reset(new cv::VideoCapture);
235  try {
236  int device_num = std::stoi(video_stream_provider);
237  NODELET_INFO_STREAM("Opening VideoCapture with provider: /dev/video" << device_num);
238  cap->open(device_num);
239  } catch (std::invalid_argument &ex) {
240  NODELET_INFO_STREAM("Opening VideoCapture with provider: " << video_stream_provider);
241  cap->open(video_stream_provider);
242  if(video_stream_provider_type == "videofile" )
243  {
244  // We can only check the number of frames when we actually open the video file
245  NODELET_INFO_STREAM("Video number of frames: " << cap->get(cv::CAP_PROP_FRAME_COUNT));
246  if(latest_config.stop_frame == -1)
247  {
248  NODELET_WARN_STREAM("'stop_frame' set to -1, setting internally (won't be shown in dynamic_reconfigure) to last frame: " << cap->get(cv::CAP_PROP_FRAME_COUNT));
249  latest_config.stop_frame = cap->get(cv::CAP_PROP_FRAME_COUNT);
250  }
251  if(latest_config.stop_frame > cap->get(cv::CAP_PROP_FRAME_COUNT))
252  {
253  NODELET_ERROR_STREAM("Invalid 'stop_frame' " << latest_config.stop_frame << " for video which has " << cap->get(cv::CAP_PROP_FRAME_COUNT) << " frames. Setting internally (won't be shown in dynamic_reconfigure) 'stop_frame' to " << cap->get(cv::CAP_PROP_FRAME_COUNT));
254  latest_config.stop_frame = cap->get(cv::CAP_PROP_FRAME_COUNT);
255  }
256 
257  if(latest_config.start_frame >= latest_config.stop_frame)
258  {
259  NODELET_ERROR_STREAM("Invalid 'start_frame' " << latest_config.start_frame << ", which exceeds 'stop_frame' " << latest_config.stop_frame << ". Setting internally (won't be shown in dynamic_reconfigure) 'start_frame' to 0.");
260  latest_config.start_frame = 0;
261  }
262 
263  cap->set(cv::CAP_PROP_POS_FRAMES, latest_config.start_frame);
264  }
265  if (!cap->isOpened()) {
266  NODELET_FATAL_STREAM("Invalid 'video_stream_provider': " << video_stream_provider);
267  return;
268  }
269  }
270  NODELET_INFO_STREAM("Video stream provider type detected: " << video_stream_provider_type);
271 
272  double reported_camera_fps;
273  // OpenCV 2.4 returns -1 (instead of a 0 as the spec says) and prompts an error
274  // HIGHGUI ERROR: V4L2: Unable to get property <unknown property string>(5) - Invalid argument
275  reported_camera_fps = cap->get(cv::CAP_PROP_FPS);
276  if (reported_camera_fps > 0.0)
277  NODELET_INFO_STREAM("Camera reports FPS: " << reported_camera_fps);
278  else
279  NODELET_INFO_STREAM("Backend can't provide camera FPS information");
280 
281  cap->set(cv::CAP_PROP_FPS, latest_config.set_camera_fps);
282  if(!cap->isOpened()){
283  NODELET_ERROR_STREAM("Could not open the stream.");
284  return;
285  }
286  if (latest_config.width != 0 && latest_config.height != 0){
287  cap->set(cv::CAP_PROP_FRAME_WIDTH, latest_config.width);
288  cap->set(cv::CAP_PROP_FRAME_HEIGHT, latest_config.height);
289  }
290 
291  cap->set(cv::CAP_PROP_BRIGHTNESS, latest_config.brightness);
292  cap->set(cv::CAP_PROP_CONTRAST, latest_config.contrast);
293  cap->set(cv::CAP_PROP_HUE, latest_config.hue);
294  cap->set(cv::CAP_PROP_SATURATION, latest_config.saturation);
295 
296  if (latest_config.auto_exposure) {
297  cap->set(cv::CAP_PROP_AUTO_EXPOSURE, 0.75);
298  latest_config.exposure = 0.5;
299  } else {
300  cap->set(cv::CAP_PROP_AUTO_EXPOSURE, 0.25);
301  cap->set(cv::CAP_PROP_EXPOSURE, latest_config.exposure);
302  }
303 
304  try {
305  capture_thread = boost::thread(
306  boost::bind(&VideoStreamNodelet::do_capture, this));
307  publish_timer = nh->createTimer(
308  ros::Duration(1.0 / latest_config.fps), &VideoStreamNodelet::do_publish, this);
309  } catch (std::exception& e) {
310  NODELET_ERROR_STREAM("Failed to start capture thread: " << e.what());
311  }
312 }
313 
314 virtual void unsubscribe() {
315  ROS_DEBUG("Unsubscribe");
316  publish_timer.stop();
317  capture_thread_running = false;
318  capture_thread.join();
319  cap.reset();
320 }
321 
322 virtual void connectionCallbackImpl() {
323  std::lock_guard<std::mutex> lock(s_mutex);
324  subscriber_num++;
325  if (subscriber_num == 1) {
326  subscribe();
327  }
328 }
329 
331  std::lock_guard<std::mutex> lock(s_mutex);
332  bool always_subscribe = false;
333  pnh->getParamCached("always_subscribe", always_subscribe);
334  if (video_stream_provider == "videofile" || always_subscribe) {
335  return;
336  }
337 
338  subscriber_num--;
339  if (subscriber_num == 0) {
340  unsubscribe();
341  }
342 }
343 
346 }
347 
350 }
351 
354 }
355 
358 }
359 
360 virtual void configCallback(VideoStreamConfig& new_config, uint32_t level) {
361  NODELET_DEBUG("configCallback");
362 
363  if (new_config.fps > new_config.set_camera_fps) {
365  "Asked to publish at 'fps' (" << new_config.fps
366  << ") which is higher than the 'set_camera_fps' (" << new_config.set_camera_fps <<
367  "), we can't publish faster than the camera provides images.");
368  new_config.fps = new_config.set_camera_fps;
369  }
370 
371  {
372  std::lock_guard<std::mutex> c_lock(c_mutex);
373  std::lock_guard<std::mutex> p_lock(p_mutex);
374  config = new_config;
375  }
376 
377  // show current configuration
378  NODELET_INFO_STREAM("Camera name: " << new_config.camera_name);
379  NODELET_INFO_STREAM("Provided camera_info_url: '" << new_config.camera_info_url << "'");
380  NODELET_INFO_STREAM("Publishing with frame_id: " << new_config.frame_id);
381  NODELET_INFO_STREAM("Setting camera FPS to: " << new_config.set_camera_fps);
382  NODELET_INFO_STREAM("Throttling to fps: " << new_config.fps);
383  NODELET_INFO_STREAM("Setting buffer size for capturing frames to: " << new_config.buffer_queue_size);
384  NODELET_INFO_STREAM("Flip horizontal image is: " << ((new_config.flip_horizontal)?"true":"false"));
385  NODELET_INFO_STREAM("Flip vertical image is: " << ((new_config.flip_vertical)?"true":"false"));
386  NODELET_INFO_STREAM("Video start frame is: " << new_config.start_frame);
387  NODELET_INFO_STREAM("Video stop frame is: " << new_config.stop_frame);
388 
389  if (new_config.width != 0 && new_config.height != 0)
390  {
391  NODELET_INFO_STREAM("Forced image width is: " << new_config.width);
392  NODELET_INFO_STREAM("Forced image height is: " << new_config.height);
393  }
394 
395  NODELET_DEBUG_STREAM("subscriber_num: " << subscriber_num << " and level: " << level);
396  if (subscriber_num > 0 && (level & 0x1))
397  {
398  NODELET_DEBUG("New dynamic_reconfigure config received on a parameter with configure level 1, unsubscribing and subscribing");
399  unsubscribe();
400  subscribe();
401  }
402 }
403 
404 virtual void onInit() {
405  nh.reset(new ros::NodeHandle(getNodeHandle()));
406  pnh.reset(new ros::NodeHandle(getPrivateNodeHandle()));
407  subscriber_num = 0;
408 
409  // provider can be an url (e.g.: rtsp://10.0.0.1:554) or a number of device, (e.g.: 0 would be /dev/video0)
410  pnh->param<std::string>("video_stream_provider", video_stream_provider, "0");
411  // check file type
412  try {
413  int device_num = std::stoi(video_stream_provider);
414  video_stream_provider_type ="videodevice";
415  } catch (std::invalid_argument &ex) {
416  if (video_stream_provider.find("http://") != std::string::npos ||
417  video_stream_provider.find("https://") != std::string::npos){
418  video_stream_provider_type = "http_stream";
419  }
420  else if(video_stream_provider.find("rtsp://") != std::string::npos){
421  video_stream_provider_type = "rtsp_stream";
422  }
423  else{
424  fs::file_type file_type = fs::status(fs::canonical(fs::path(video_stream_provider))).type();
425  if(fs::path(video_stream_provider) != fs::canonical(fs::path(video_stream_provider)))
426  NODELET_WARN_STREAM("Video stream provider path converted from: '" << fs::path(video_stream_provider) <<
427  "' to its canonical path: '" << fs::canonical(fs::path(video_stream_provider)) << "'" );
428  switch (file_type) {
429  case fs::file_type::character_file:
430  case fs::file_type::block_file:
431  video_stream_provider_type = "videodevice";
432  break;
433  case fs::file_type::regular_file:
434  video_stream_provider_type = "videofile";
435  break;
436  default:
437  video_stream_provider_type = "unknown";
438  }
439  }
440  }
441 
442  // set parameters from dynamic reconfigure server
443  dyn_srv = boost::make_shared<dynamic_reconfigure::Server<VideoStreamConfig> >(*pnh);
444  auto f = boost::bind(&VideoStreamNodelet::configCallback, this, _1, _2);
445  dyn_srv->setCallback(f);
446 
447  subscriber_num = 0;
449  boost::bind(&VideoStreamNodelet::connectionCallback, this, _1);
450  ros::SubscriberStatusCallback info_connect_cb =
451  boost::bind(&VideoStreamNodelet::infoConnectionCallback, this, _1);
453  boost::bind(&VideoStreamNodelet::disconnectionCallback, this, _1);
454  ros::SubscriberStatusCallback info_disconnect_cb =
455  boost::bind(&VideoStreamNodelet::infoDisconnectionCallback, this, _1);
457  "image_raw", 1,
458  connect_cb, disconnect_cb,
459  info_connect_cb, info_disconnect_cb,
460  ros::VoidPtr(), false);
461 }
462 
464  if (subscriber_num > 0)
465  subscriber_num = 0;
466  unsubscribe();
467 }
468 };
469 } // namespace
470 
#define NODELET_ERROR_STREAM_THROTTLE(rate,...)
#define NODELET_INFO_STREAM(...)
virtual void disconnectionCallback(const image_transport::SingleSubscriberPublisher &)
void publish(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &info) const
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
#define NODELET_WARN_STREAM_THROTTLE(rate,...)
sensor_msgs::CameraInfo getCameraInfo(void)
#define NODELET_WARN(...)
f
void stop()
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
#define NODELET_WARN_STREAM(...)
image_transport::CameraPublisher pub
virtual void configCallback(VideoStreamConfig &new_config, uint32_t level)
ros::NodeHandle & getPrivateNodeHandle() const
#define NODELET_ERROR_STREAM(...)
boost::shared_ptr< ros::NodeHandle > nh
CameraPublisher advertiseCamera(const std::string &base_topic, uint32_t queue_size, bool latch=false)
CvImagePtr cvtColor(const CvImageConstPtr &source, const std::string &encoding)
boost::shared_ptr< dynamic_reconfigure::Server< VideoStreamConfig > > dyn_srv
virtual sensor_msgs::CameraInfo get_default_camera_info_from_image(sensor_msgs::ImagePtr img)
boost::shared_ptr< cv::VideoCapture > cap
ros::NodeHandle & getNodeHandle() const
#define NODELET_DEBUG_STREAM(...)
virtual void do_publish(const ros::TimerEvent &event)
virtual void infoDisconnectionCallback(const ros::SingleSubscriberPublisher &)
bool sleep()
virtual void connectionCallback(const image_transport::SingleSubscriberPublisher &)
#define NODELET_INFO(...)
sensor_msgs::CameraInfo cam_info_msg
#define NODELET_FATAL_STREAM(...)
static Time now()
boost::shared_ptr< ros::NodeHandle > pnh
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
virtual void infoConnectionCallback(const ros::SingleSubscriberPublisher &)
#define NODELET_DEBUG(...)
#define ROS_DEBUG(...)


video_stream_opencv
Author(s): Sammy Pfeiffer
autogenerated on Wed Apr 14 2021 02:45:12