camera_driver.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (C) 2012 Ken Tossell
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 the author nor other contributors may be
18 * used to endorse or promote products derived from this software
19 * 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 *********************************************************************/
35 
36 #include <ros/ros.h>
37 #include <sensor_msgs/Image.h>
38 #include <std_msgs/Header.h>
40 #include <dynamic_reconfigure/server.h>
41 #include <libuvc/libuvc.h>
42 #define libuvc_VERSION (libuvc_VERSION_MAJOR * 10000 \
43  + libuvc_VERSION_MINOR * 100 \
44  + libuvc_VERSION_PATCH)
45 
46 namespace libuvc_camera {
47 
49  : nh_(nh), priv_nh_(priv_nh),
50  state_(kInitial),
51  ctx_(NULL), dev_(NULL), devh_(NULL), rgb_frame_(NULL),
52  it_(nh_),
53  config_server_(mutex_, priv_nh_),
54  config_changed_(false),
55  cinfo_manager_(nh) {
56  cam_pub_ = it_.advertiseCamera("image_raw", 1, false);
57 }
58 
60  if (rgb_frame_)
61  uvc_free_frame(rgb_frame_);
62 
63  if (ctx_)
64  uvc_exit(ctx_); // Destroys dev_, devh_, etc.
65 }
66 
68  assert(state_ == kInitial);
69 
70  uvc_error_t err;
71 
72  err = uvc_init(&ctx_, NULL);
73 
74  if (err != UVC_SUCCESS) {
75  uvc_perror(err, "ERROR: uvc_init");
76  return false;
77  }
78 
79  state_ = kStopped;
80 
81  config_server_.setCallback(boost::bind(&CameraDriver::ReconfigureCallback, this, _1, _2));
82 
83  return state_ == kRunning;
84 }
85 
87  boost::recursive_mutex::scoped_lock lock(mutex_);
88 
89  assert(state_ != kInitial);
90 
91  if (state_ == kRunning)
92  CloseCamera();
93 
94  assert(state_ == kStopped);
95 
96  uvc_exit(ctx_);
97  ctx_ = NULL;
98 
99  state_ = kInitial;
100 }
101 
102 void CameraDriver::ReconfigureCallback(UVCCameraConfig &new_config, uint32_t level) {
103  boost::recursive_mutex::scoped_lock lock(mutex_);
104 
105  if ((level & kReconfigureClose) == kReconfigureClose) {
106  if (state_ == kRunning)
107  CloseCamera();
108  }
109 
110  if (state_ == kStopped) {
111  OpenCamera(new_config);
112  }
113 
114  if (new_config.camera_info_url != config_.camera_info_url)
115  cinfo_manager_.loadCameraInfo(new_config.camera_info_url);
116 
117  if (state_ == kRunning) {
118 #define PARAM_INT(name, fn, value) if (new_config.name != config_.name) { \
119  int val = (value); \
120  if (uvc_set_##fn(devh_, val)) { \
121  ROS_WARN("Unable to set " #name " to %d", val); \
122  new_config.name = config_.name; \
123  } \
124  }
125 
126  PARAM_INT(scanning_mode, scanning_mode, new_config.scanning_mode);
127  PARAM_INT(auto_exposure, ae_mode, 1 << new_config.auto_exposure);
128  PARAM_INT(auto_exposure_priority, ae_priority, new_config.auto_exposure_priority);
129  PARAM_INT(exposure_absolute, exposure_abs, new_config.exposure_absolute * 10000);
130  PARAM_INT(auto_focus, focus_auto, new_config.auto_focus ? 1 : 0);
131  PARAM_INT(focus_absolute, focus_abs, new_config.focus_absolute);
132 #if libuvc_VERSION > 00005 /* version > 0.0.5 */
133  PARAM_INT(gain, gain, new_config.gain);
134  PARAM_INT(iris_absolute, iris_abs, new_config.iris_absolute);
135  PARAM_INT(brightness, brightness, new_config.brightness);
136 #endif
137 
138 
139  if (new_config.pan_absolute != config_.pan_absolute || new_config.tilt_absolute != config_.tilt_absolute) {
140  if (uvc_set_pantilt_abs(devh_, new_config.pan_absolute, new_config.tilt_absolute)) {
141  ROS_WARN("Unable to set pantilt to %d, %d", new_config.pan_absolute, new_config.tilt_absolute);
142  new_config.pan_absolute = config_.pan_absolute;
143  new_config.tilt_absolute = config_.tilt_absolute;
144  }
145  }
146  // TODO: roll_absolute
147  // TODO: privacy
148  // TODO: backlight_compensation
149  // TODO: contrast
150  // TODO: power_line_frequency
151  // TODO: auto_hue
152  // TODO: saturation
153  // TODO: sharpness
154  // TODO: gamma
155  // TODO: auto_white_balance
156  // TODO: white_balance_temperature
157  // TODO: white_balance_BU
158  // TODO: white_balance_RV
159  }
160 
161  config_ = new_config;
162 }
163 
164 void CameraDriver::ImageCallback(uvc_frame_t *frame) {
165  ros::Time timestamp = ros::Time(frame->capture_time.tv_sec, frame->capture_time.tv_usec * 1000);
166  if ( timestamp == ros::Time(0) ) {
167  timestamp = ros::Time::now();
168  }
169 
170  boost::recursive_mutex::scoped_lock lock(mutex_);
171 
172  assert(state_ == kRunning);
173  assert(rgb_frame_);
174 
175  sensor_msgs::Image::Ptr image(new sensor_msgs::Image());
176  image->width = config_.width;
177  image->height = config_.height;
178  image->step = image->width * 3;
179  image->data.resize(image->step * image->height);
180 
181  if (frame->frame_format == UVC_FRAME_FORMAT_BGR){
182  image->encoding = "bgr8";
183  memcpy(&(image->data[0]), frame->data, frame->data_bytes);
184  } else if (frame->frame_format == UVC_FRAME_FORMAT_RGB){
185  image->encoding = "rgb8";
186  memcpy(&(image->data[0]), frame->data, frame->data_bytes);
187  } else if (frame->frame_format == UVC_FRAME_FORMAT_UYVY) {
188  uvc_error_t conv_ret = uvc_uyvy2bgr(frame, rgb_frame_);
189  if (conv_ret != UVC_SUCCESS) {
190  uvc_perror(conv_ret, "Couldn't convert frame to RGB");
191  return;
192  }
193  image->encoding = "bgr8";
194  memcpy(&(image->data[0]), rgb_frame_->data, rgb_frame_->data_bytes);
195  } else if (frame->frame_format == UVC_FRAME_FORMAT_YUYV) {
196  // FIXME: uvc_any2bgr does not work on "yuyv" format, so use uvc_yuyv2bgr directly.
197  uvc_error_t conv_ret = uvc_yuyv2bgr(frame, rgb_frame_);
198  if (conv_ret != UVC_SUCCESS) {
199  uvc_perror(conv_ret, "Couldn't convert frame to RGB");
200  return;
201  }
202  image->encoding = "bgr8";
203  memcpy(&(image->data[0]), rgb_frame_->data, rgb_frame_->data_bytes);
204 #if libuvc_VERSION > 00005 /* version > 0.0.5 */
205  } else if (frame->frame_format == UVC_FRAME_FORMAT_MJPEG) {
206  // Enable mjpeg support despite uvs_any2bgr shortcoming
207  // https://github.com/ros-drivers/libuvc_ros/commit/7508a09f
208  uvc_error_t conv_ret = uvc_mjpeg2rgb(frame, rgb_frame_);
209  if (conv_ret != UVC_SUCCESS) {
210  uvc_perror(conv_ret, "Couldn't convert frame to RGB");
211  return;
212  }
213  image->encoding = "rgb8";
214  memcpy(&(image->data[0]), rgb_frame_->data, rgb_frame_->data_bytes);
215 #endif
216  } else {
217  uvc_error_t conv_ret = uvc_any2bgr(frame, rgb_frame_);
218  if (conv_ret != UVC_SUCCESS) {
219  uvc_perror(conv_ret, "Couldn't convert frame to RGB");
220  return;
221  }
222  image->encoding = "bgr8";
223  memcpy(&(image->data[0]), rgb_frame_->data, rgb_frame_->data_bytes);
224  }
225 
226 
227  sensor_msgs::CameraInfo::Ptr cinfo(
228  new sensor_msgs::CameraInfo(cinfo_manager_.getCameraInfo()));
229 
230  image->header.frame_id = config_.frame_id;
231  image->header.stamp = timestamp;
232  cinfo->header.frame_id = config_.frame_id;
233  cinfo->header.stamp = timestamp;
234 
235  cam_pub_.publish(image, cinfo);
236 
237  if (config_changed_) {
238  config_server_.updateConfig(config_);
239  config_changed_ = false;
240  }
241 }
242 
243 /* static */ void CameraDriver::ImageCallbackAdapter(uvc_frame_t *frame, void *ptr) {
244  CameraDriver *driver = static_cast<CameraDriver*>(ptr);
245 
246  driver->ImageCallback(frame);
247 }
248 
250  enum uvc_status_class status_class,
251  int event,
252  int selector,
253  enum uvc_status_attribute status_attribute,
254  void *data, size_t data_len) {
255  boost::recursive_mutex::scoped_lock lock(mutex_);
256 
257  printf("Controls callback. class: %d, event: %d, selector: %d, attr: %d, data_len: %zu\n",
258  status_class, event, selector, status_attribute, data_len);
259 
260  if (status_attribute == UVC_STATUS_ATTRIBUTE_VALUE_CHANGE) {
261  switch (status_class) {
262  case UVC_STATUS_CLASS_CONTROL_CAMERA: {
263  switch (selector) {
264  case UVC_CT_EXPOSURE_TIME_ABSOLUTE_CONTROL:
265  uint8_t *data_char = (uint8_t*) data;
266  uint32_t exposure_int = ((data_char[0]) | (data_char[1] << 8) |
267  (data_char[2] << 16) | (data_char[3] << 24));
268  config_.exposure_absolute = exposure_int * 0.0001;
269  config_changed_ = true;
270  break;
271  }
272  break;
273  }
274  case UVC_STATUS_CLASS_CONTROL_PROCESSING: {
275  switch (selector) {
276  case UVC_PU_WHITE_BALANCE_TEMPERATURE_CONTROL:
277  uint8_t *data_char = (uint8_t*) data;
278  config_.white_balance_temperature =
279  data_char[0] | (data_char[1] << 8);
280  config_changed_ = true;
281  break;
282  }
283  break;
284  }
285  }
286 
287  // config_server_.updateConfig(config_);
288  }
289 }
290 
292  enum uvc_status_class status_class,
293  int event,
294  int selector,
295  enum uvc_status_attribute status_attribute,
296  void *data, size_t data_len,
297  void *ptr) {
298  CameraDriver *driver = static_cast<CameraDriver*>(ptr);
299 
300  driver->AutoControlsCallback(status_class, event, selector,
301  status_attribute, data, data_len);
302 }
303 
304 enum uvc_frame_format CameraDriver::GetVideoMode(std::string vmode){
305  if(vmode == "uncompressed") {
306  return UVC_COLOR_FORMAT_UNCOMPRESSED;
307  } else if (vmode == "compressed") {
308  return UVC_COLOR_FORMAT_COMPRESSED;
309  } else if (vmode == "yuyv") {
310  return UVC_COLOR_FORMAT_YUYV;
311  } else if (vmode == "uyvy") {
312  return UVC_COLOR_FORMAT_UYVY;
313  } else if (vmode == "rgb") {
314  return UVC_COLOR_FORMAT_RGB;
315  } else if (vmode == "bgr") {
316  return UVC_COLOR_FORMAT_BGR;
317  } else if (vmode == "mjpeg") {
318  return UVC_COLOR_FORMAT_MJPEG;
319  } else if (vmode == "gray8") {
320  return UVC_COLOR_FORMAT_GRAY8;
321  } else {
322  ROS_ERROR_STREAM("Invalid Video Mode: " << vmode);
323  ROS_WARN_STREAM("Continue using video mode: uncompressed");
324  return UVC_COLOR_FORMAT_UNCOMPRESSED;
325  }
326 };
327 
328 void CameraDriver::OpenCamera(UVCCameraConfig &new_config) {
329  assert(state_ == kStopped);
330 
331  int vendor_id = strtol(new_config.vendor.c_str(), NULL, 0);
332  int product_id = strtol(new_config.product.c_str(), NULL, 0);
333 
334  ROS_INFO("Opening camera with vendor=0x%x, product=0x%x, serial=\"%s\", index=%d",
335  vendor_id, product_id, new_config.serial.c_str(), new_config.index);
336 
337  uvc_device_t **devs;
338 
339  // Implement missing index select behavior
340  // https://github.com/ros-drivers/libuvc_ros/commit/4f30e9a0
341 #if libuvc_VERSION > 00005 /* version > 0.0.5 */
342  uvc_error_t find_err = uvc_find_devices(
343  ctx_, &devs,
344  vendor_id,
345  product_id,
346  new_config.serial.empty() ? NULL : new_config.serial.c_str());
347 
348  if (find_err != UVC_SUCCESS) {
349  uvc_perror(find_err, "uvc_find_device");
350  return;
351  }
352 
353  // select device by index
354  dev_ = NULL;
355  int dev_idx = 0;
356  while (devs[dev_idx] != NULL) {
357  if(dev_idx == new_config.index) {
358  dev_ = devs[dev_idx];
359  }
360  else {
361  uvc_unref_device(devs[dev_idx]);
362  }
363 
364  dev_idx++;
365  }
366 
367  if(dev_ == NULL) {
368  ROS_ERROR("Unable to find device at index %d", new_config.index);
369  return;
370  }
371 #else
372  uvc_error_t find_err = uvc_find_device(
373  ctx_, &dev_,
374  vendor_id,
375  product_id,
376  new_config.serial.empty() ? NULL : new_config.serial.c_str());
377 
378  if (find_err != UVC_SUCCESS) {
379  uvc_perror(find_err, "uvc_find_device");
380  return;
381  }
382 
383 #endif
384  uvc_error_t open_err = uvc_open(dev_, &devh_);
385 
386  if (open_err != UVC_SUCCESS) {
387  switch (open_err) {
388  case UVC_ERROR_ACCESS:
389 #ifdef __linux__
390  ROS_ERROR("Permission denied opening /dev/bus/usb/%03d/%03d",
391  uvc_get_bus_number(dev_), uvc_get_device_address(dev_));
392 #else
393  ROS_ERROR("Permission denied opening device %d on bus %d",
394  uvc_get_device_address(dev_), uvc_get_bus_number(dev_));
395 #endif
396  break;
397  default:
398 #ifdef __linux__
399  ROS_ERROR("Can't open /dev/bus/usb/%03d/%03d: %s (%d)",
400  uvc_get_bus_number(dev_), uvc_get_device_address(dev_),
401  uvc_strerror(open_err), open_err);
402 #else
403  ROS_ERROR("Can't open device %d on bus %d: %s (%d)",
404  uvc_get_device_address(dev_), uvc_get_bus_number(dev_),
405  uvc_strerror(open_err), open_err);
406 #endif
407  break;
408  }
409 
410  uvc_unref_device(dev_);
411  return;
412  }
413 
414  uvc_set_status_callback(devh_, &CameraDriver::AutoControlsCallbackAdapter, this);
415 
416  uvc_stream_ctrl_t ctrl;
417  uvc_error_t mode_err = uvc_get_stream_ctrl_format_size(
418  devh_, &ctrl,
419  GetVideoMode(new_config.video_mode),
420  new_config.width, new_config.height,
421  new_config.frame_rate);
422 
423  if (mode_err != UVC_SUCCESS) {
424  uvc_perror(mode_err, "uvc_get_stream_ctrl_format_size");
425  uvc_close(devh_);
426  uvc_unref_device(dev_);
427  ROS_ERROR("check video_mode/width/height/frame_rate are available");
428  uvc_print_diag(devh_, NULL);
429  return;
430  }
431 
432  uvc_error_t stream_err = uvc_start_streaming(devh_, &ctrl, &CameraDriver::ImageCallbackAdapter, this, 0);
433 
434  if (stream_err != UVC_SUCCESS) {
435  uvc_perror(stream_err, "uvc_start_streaming");
436  uvc_close(devh_);
437  uvc_unref_device(dev_);
438  return;
439  }
440 
441  if (rgb_frame_)
442  uvc_free_frame(rgb_frame_);
443 
444  rgb_frame_ = uvc_allocate_frame(new_config.width * new_config.height * 3);
445  assert(rgb_frame_);
446 
447  state_ = kRunning;
448 }
449 
451  assert(state_ == kRunning);
452 
453  uvc_close(devh_);
454  devh_ = NULL;
455 
456  uvc_unref_device(dev_);
457  dev_ = NULL;
458 
459  state_ = kStopped;
460 }
461 
462 };
boost::recursive_mutex mutex_
Definition: camera_driver.h:61
static void ImageCallbackAdapter(uvc_frame_t *frame, void *ptr)
enum uvc_frame_format GetVideoMode(std::string vmode)
void publish(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &info) const
sensor_msgs::CameraInfo getCameraInfo(void)
bool loadCameraInfo(const std::string &url)
static void AutoControlsCallbackAdapter(enum uvc_status_class status_class, int event, int selector, enum uvc_status_attribute status_attribute, void *data, size_t data_len, void *ptr)
image_transport::ImageTransport it_
Definition: camera_driver.h:68
#define ROS_WARN(...)
dynamic_reconfigure::Server< UVCCameraConfig > config_server_
Definition: camera_driver.h:71
void ReconfigureCallback(UVCCameraConfig &config, uint32_t level)
CameraPublisher advertiseCamera(const std::string &base_topic, uint32_t queue_size, bool latch=false)
void ImageCallback(uvc_frame_t *frame)
#define ROS_INFO(...)
#define PARAM_INT(name, fn, value)
#define ROS_WARN_STREAM(args)
void OpenCamera(UVCCameraConfig &new_config)
image_transport::CameraPublisher cam_pub_
Definition: camera_driver.h:69
camera_info_manager::CameraInfoManager cinfo_manager_
Definition: camera_driver.h:75
void AutoControlsCallback(enum uvc_status_class status_class, int event, int selector, enum uvc_status_attribute status_attribute, void *data, size_t data_len)
static Time now()
static const int kReconfigureClose
Definition: camera_driver.h:32
CameraDriver(ros::NodeHandle nh, ros::NodeHandle priv_nh)
#define ROS_ERROR_STREAM(args)
#define ROS_ERROR(...)
uvc_device_handle_t * devh_
Definition: camera_driver.h:65


libuvc_camera
Author(s):
autogenerated on Mon Jul 8 2019 03:45:03