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 #include <astra_camera/GetDeviceType.h>
43 #include <astra_camera/GetCameraInfo.h>
44 #include <cmath>
45 
46 #define libuvc_VERSION (libuvc_VERSION_MAJOR * 10000 \
47  + libuvc_VERSION_MINOR * 100 \
48  + libuvc_VERSION_PATCH)
49 
50 namespace libuvc_camera {
51 
53  : nh_(nh), priv_nh_(priv_nh),
54  state_(kInitial),
55  ctx_(NULL), dev_(NULL), devh_(NULL), rgb_frame_(NULL),
56  it_(nh_),
57  config_server_(mutex_, priv_nh_),
58  config_changed_(false),
59  cinfo_manager_(nh),
60  param_init_(false) {
61  cam_pub_ = it_.advertiseCamera("image_raw", 1, false);
63  device_type_client = nh_.serviceClient<astra_camera::GetDeviceType>(ns + "/get_device_type");
64  camera_info_client = nh_.serviceClient<astra_camera::GetCameraInfo>(ns + "/get_camera_info");
71  device_type_init_ = false;
72  camera_info_init_ = false;
73  uvc_flip_ = 0;
75  int slash_end;
76  for (slash_end = 0; slash_end < ns.length(); slash_end++)
77  {
78  if (ns[slash_end] != '/')
79  {
80  break;
81  }
82  }
83  ns_no_slash = ns.substr(slash_end);
84  camera_info_valid_ = false;
85 }
86 
88  if (rgb_frame_)
89  uvc_free_frame(rgb_frame_);
90 
91  if (ctx_)
92  uvc_exit(ctx_); // Destroys dev_, devh_, etc.
93 }
94 
95 bool CameraDriver::getUVCExposureCb(astra_camera::GetUVCExposureRequest& req, astra_camera::GetUVCExposureResponse& res)
96 {
97  uint32_t expo;
98  uvc_error_t err = uvc_get_exposure_abs(devh_, &expo, UVC_GET_CUR);
99  res.exposure = expo;
100  return (err == UVC_SUCCESS);
101 }
102 
103 bool CameraDriver::setUVCExposureCb(astra_camera::SetUVCExposureRequest& req, astra_camera::SetUVCExposureResponse& res)
104 {
105  if (req.exposure == 0)
106  {
107  uvc_set_ae_mode(devh_, 2);
108  return true;
109  }
110  uvc_set_ae_mode(devh_, 1); // mode 1: manual mode; 2: auto mode; 4: shutter priority mode; 8: aperture priority mode
111  if (req.exposure > 330)
112  {
113  ROS_ERROR("Please set exposure lower than 330");
114  return false;
115  }
116  uvc_error_t err = uvc_set_exposure_abs(devh_, req.exposure);
117  return (err == UVC_SUCCESS);
118 }
119 
120 bool CameraDriver::getUVCGainCb(astra_camera::GetUVCGainRequest& req, astra_camera::GetUVCGainResponse& res)
121 {
122  uint16_t gain;
123  uvc_error_t err = uvc_get_gain(devh_, &gain, UVC_GET_CUR);
124  res.gain = gain;
125  return (err == UVC_SUCCESS);
126 }
127 
128 bool CameraDriver::setUVCGainCb(astra_camera::SetUVCGainRequest& req, astra_camera::SetUVCGainResponse& res)
129 {
130  uvc_error_t err = uvc_set_gain(devh_, req.gain);
131  return (err == UVC_SUCCESS);
132 }
133 
134 bool CameraDriver::getUVCWhiteBalanceCb(astra_camera::GetUVCWhiteBalanceRequest& req, astra_camera::GetUVCWhiteBalanceResponse& res)
135 {
136  uint16_t white_balance;
137  uvc_error_t err = uvc_get_white_balance_temperature(devh_, &white_balance, UVC_GET_CUR);
138  res.white_balance = white_balance;
139  return (err == UVC_SUCCESS);
140 }
141 
142 bool CameraDriver::setUVCWhiteBalanceCb(astra_camera::SetUVCWhiteBalanceRequest& req, astra_camera::SetUVCWhiteBalanceResponse& res)
143 {
144  if (req.white_balance == 0)
145  {
146  uvc_set_white_balance_temperature_auto(devh_, 1);
147  return true;
148  }
149  uvc_set_white_balance_temperature_auto(devh_, 0); // 0: manual, 1: auto
150  uvc_error_t err = uvc_set_white_balance_temperature(devh_, req.white_balance);
151  return (err == UVC_SUCCESS);
152 }
153 
155  assert(state_ == kInitial);
156 
157  uvc_error_t err;
158 
159  err = uvc_init(&ctx_, NULL);
160 
161  if (err != UVC_SUCCESS) {
162  uvc_perror(err, "ERROR: uvc_init");
163  return false;
164  }
165 
166  state_ = kStopped;
167 
168  config_server_.setCallback(boost::bind(&CameraDriver::ReconfigureCallback, this, _1, _2));
169 
170  return state_ == kRunning;
171 }
172 
174  boost::recursive_mutex::scoped_lock(mutex_);
175 
176  assert(state_ != kInitial);
177 
178  if (state_ == kRunning)
179  CloseCamera();
180 
181  assert(state_ == kStopped);
182 
183  uvc_exit(ctx_);
184  ctx_ = NULL;
185 
186  state_ = kInitial;
187 }
188 
189 void CameraDriver::ReconfigureCallback(UVCCameraConfig &new_config, uint32_t level) {
190  boost::recursive_mutex::scoped_lock(mutex_);
191 
192  if ((level & kReconfigureClose) == kReconfigureClose) {
193  if (state_ == kRunning)
194  CloseCamera();
195  }
196 
197  if (state_ == kStopped) {
198  OpenCamera(new_config);
199  }
200 
201  if (new_config.camera_info_url != config_.camera_info_url)
202  cinfo_manager_.loadCameraInfo(new_config.camera_info_url);
203 
204  if (state_ == kRunning) {
205 #define PARAM_INT(name, fn, value) if (new_config.name != config_.name) { \
206  int val = (value); \
207  if (uvc_set_##fn(devh_, val)) { \
208  ROS_WARN("Unable to set " #name " to %d", val); \
209  new_config.name = config_.name; \
210  } \
211  }
212 
213  PARAM_INT(scanning_mode, scanning_mode, new_config.scanning_mode);
214  PARAM_INT(auto_exposure, ae_mode, 1 << new_config.auto_exposure);
215  PARAM_INT(auto_exposure_priority, ae_priority, new_config.auto_exposure_priority);
216  PARAM_INT(exposure_absolute, exposure_abs, new_config.exposure_absolute * 10000);
217  PARAM_INT(auto_focus, focus_auto, new_config.auto_focus ? 1 : 0);
218  PARAM_INT(focus_absolute, focus_abs, new_config.focus_absolute);
219 #if libuvc_VERSION > 00005 /* version > 0.0.5 */
220  PARAM_INT(gain, gain, new_config.gain);
221  PARAM_INT(iris_absolute, iris_abs, new_config.iris_absolute);
222  PARAM_INT(brightness, brightness, new_config.brightness);
223 #endif
224 
225 
226  if (new_config.pan_absolute != config_.pan_absolute || new_config.tilt_absolute != config_.tilt_absolute) {
227  if (uvc_set_pantilt_abs(devh_, new_config.pan_absolute, new_config.tilt_absolute)) {
228  ROS_WARN("Unable to set pantilt to %d, %d", new_config.pan_absolute, new_config.tilt_absolute);
229  new_config.pan_absolute = config_.pan_absolute;
230  new_config.tilt_absolute = config_.tilt_absolute;
231  }
232  }
233  // TODO: roll_absolute
234  // TODO: privacy
235  // TODO: backlight_compensation
236  // TODO: contrast
237  // TODO: power_line_frequency
238  // TODO: auto_hue
239  // TODO: saturation
240  // TODO: sharpness
241  // TODO: gamma
242  // TODO: auto_white_balance
243  // TODO: white_balance_temperature
244  // TODO: white_balance_BU
245  // TODO: white_balance_RV
246  }
247 
248  config_ = new_config;
249 }
250 
251 void CameraDriver::ImageCallback(uvc_frame_t *frame) {
252  ros::Time timestamp = ros::Time(frame->capture_time.tv_sec, frame->capture_time.tv_usec);
253  if ( timestamp == ros::Time(0) ) {
254  timestamp = ros::Time::now();
255  }
256 
257  boost::recursive_mutex::scoped_lock(mutex_);
258 
259  assert(state_ == kRunning);
260  assert(rgb_frame_);
261 
262  sensor_msgs::Image::Ptr image(new sensor_msgs::Image());
263  image->width = config_.width;
264  image->height = config_.height;
265  image->step = image->width * 3;
266  image->data.resize(image->step * image->height);
267 
268  if (frame->frame_format == UVC_FRAME_FORMAT_BGR){
269  image->encoding = "bgr8";
270  memcpy(&(image->data[0]), frame->data, frame->data_bytes);
271  } else if (frame->frame_format == UVC_FRAME_FORMAT_RGB){
272  image->encoding = "rgb8";
273  memcpy(&(image->data[0]), frame->data, frame->data_bytes);
274  } else if (frame->frame_format == UVC_FRAME_FORMAT_UYVY) {
275  image->encoding = "yuv422";
276  memcpy(&(image->data[0]), frame->data, frame->data_bytes);
277  } else if (frame->frame_format == UVC_FRAME_FORMAT_YUYV) {
278  // FIXME: uvc_any2bgr does not work on "yuyv" format, so use uvc_yuyv2bgr directly.
279  uvc_error_t conv_ret = uvc_yuyv2bgr(frame, rgb_frame_);
280  if (conv_ret != UVC_SUCCESS) {
281  uvc_perror(conv_ret, "Couldn't convert frame to RGB");
282  return;
283  }
284  image->encoding = "bgr8";
285  memcpy(&(image->data[0]), rgb_frame_->data, rgb_frame_->data_bytes);
286 #if libuvc_VERSION > 00005 /* version > 0.0.5 */
287  } else if (frame->frame_format == UVC_FRAME_FORMAT_MJPEG) {
288  // Enable mjpeg support despite uvs_any2bgr shortcoming
289  // https://github.com/ros-drivers/libuvc_ros/commit/7508a09f
290  uvc_error_t conv_ret = uvc_mjpeg2rgb(frame, rgb_frame_);
291  if (conv_ret != UVC_SUCCESS) {
292  uvc_perror(conv_ret, "Couldn't convert frame to RGB");
293  return;
294  }
295  image->encoding = "rgb8";
296  memcpy(&(image->data[0]), rgb_frame_->data, rgb_frame_->data_bytes);
297 #endif
298  } else {
299  uvc_error_t conv_ret = uvc_any2bgr(frame, rgb_frame_);
300  if (conv_ret != UVC_SUCCESS) {
301  uvc_perror(conv_ret, "Couldn't convert frame to RGB");
302  return;
303  }
304  image->encoding = "bgr8";
305  memcpy(&(image->data[0]), rgb_frame_->data, rgb_frame_->data_bytes);
306  }
307 
308  astra_camera::GetDeviceType device_type_srv;
309  astra_camera::GetCameraInfo camera_info_srv;
310 
311  if (device_type_init_ == false)
312  {
313  if (device_type_client.call(device_type_srv))
314  {
315  device_type_ = device_type_srv.response.device_type;
316  if (strcmp(device_type_.c_str(), OB_STEREO_S) == 0)
317  {
319  }
320  else if (strcmp(device_type_.c_str(), OB_EMBEDDED_S) == 0)
321  {
323  uvc_flip_ = 1;
324  }
325  else if (strcmp(device_type_.c_str(), OB_ASTRA_PRO) == 0)
326  {
328  }
329  else if (strcmp(device_type_.c_str(), OB_STEREO_S_U3) == 0)
330  {
332  }
333  else
334  {
336  }
337  device_type_init_ = true;
338  }
339  }
340 
341  if (camera_info_init_ == false)
342  {
343  if (camera_info_client.call(camera_info_srv))
344  {
345  camera_info_ = camera_info_srv.response.info;
346  camera_info_init_ = true;
347  camera_info_valid_ = true;
348  if (std::isnan(camera_info_.K[0]) || std::isnan(camera_info_.K[2]) || std::isnan(camera_info_.K[4]) || std::isnan(camera_info_.K[5]))
349  {
350  camera_info_valid_ = false;
351  }
352  }
353  }
354 
355  sensor_msgs::CameraInfo::Ptr cinfo(new sensor_msgs::CameraInfo(cinfo_manager_.getCameraInfo()));
357  {
358  // update cinfo
359  if (camera_info_init_ == true && camera_info_valid_ == true)
360  {
361  cinfo->height = image->height;
362  cinfo->width = image->width;
363  cinfo->distortion_model = camera_info_.distortion_model;
364  cinfo->D.resize(5, 0.0);
365  cinfo->D[4] = 0.0000000001;
366  // for (int i = 0; i < 5; i++)
367  // {
368  // cinfo->D[i] = camera_info_.D[i];
369  // }
370  for (int i = 0; i < 9; i++)
371  {
372  cinfo->K[i] = camera_info_.K[i];
373  cinfo->R[i] = camera_info_.R[i];
374  }
375  cinfo->K[0] = (1 - uvc_flip_)*(camera_info_.K[0]) + (uvc_flip_)*(-camera_info_.K[0]);
376  cinfo->K[2] = (1 - uvc_flip_)*(camera_info_.K[2]) + (uvc_flip_)*(image->width - camera_info_.K[2]);
377  for (int i = 0; i < 12; i++)
378  {
379  cinfo->P[i] = camera_info_.P[i];
380  }
381  }
382  image->header.frame_id = ns_no_slash + "_rgb_optical_frame";
383  cinfo->header.frame_id = ns_no_slash + "_rgb_optical_frame";
384  }
385  else
386  {
387  image->header.frame_id = config_.frame_id;
388  cinfo->header.frame_id = config_.frame_id;
389  }
390  image->header.stamp = timestamp;
391  cinfo->header.stamp = timestamp;
392 
393  cam_pub_.publish(image, cinfo);
394 
395  if (config_changed_)
396  {
397  config_server_.updateConfig(config_);
398  config_changed_ = false;
399  }
400 }
401 
402 /* static */ void CameraDriver::ImageCallbackAdapter(uvc_frame_t *frame, void *ptr) {
403  CameraDriver *driver = static_cast<CameraDriver*>(ptr);
404 
405  driver->ImageCallback(frame);
406 }
407 
409  enum uvc_status_class status_class,
410  int event,
411  int selector,
412  enum uvc_status_attribute status_attribute,
413  void *data, size_t data_len) {
414  boost::recursive_mutex::scoped_lock(mutex_);
415 
416  printf("Controls callback. class: %d, event: %d, selector: %d, attr: %d, data_len: %zu\n",
417  status_class, event, selector, status_attribute, data_len);
418 
419  if (status_attribute == UVC_STATUS_ATTRIBUTE_VALUE_CHANGE) {
420  switch (status_class) {
421  case UVC_STATUS_CLASS_CONTROL_CAMERA: {
422  switch (selector) {
423  case UVC_CT_EXPOSURE_TIME_ABSOLUTE_CONTROL:
424  uint8_t *data_char = (uint8_t*) data;
425  uint32_t exposure_int = ((data_char[0]) | (data_char[1] << 8) |
426  (data_char[2] << 16) | (data_char[3] << 24));
427  config_.exposure_absolute = exposure_int * 0.0001;
428  config_changed_ = true;
429  break;
430  }
431  break;
432  }
433  case UVC_STATUS_CLASS_CONTROL_PROCESSING: {
434  switch (selector) {
435  case UVC_PU_WHITE_BALANCE_TEMPERATURE_CONTROL:
436  uint8_t *data_char = (uint8_t*) data;
437  config_.white_balance_temperature =
438  data_char[0] | (data_char[1] << 8);
439  config_changed_ = true;
440  break;
441  }
442  break;
443  }
444  }
445 
446  // config_server_.updateConfig(config_);
447  }
448 }
449 
451  enum uvc_status_class status_class,
452  int event,
453  int selector,
454  enum uvc_status_attribute status_attribute,
455  void *data, size_t data_len,
456  void *ptr) {
457  CameraDriver *driver = static_cast<CameraDriver*>(ptr);
458 
459  driver->AutoControlsCallback(status_class, event, selector,
460  status_attribute, data, data_len);
461 }
462 
463 enum uvc_frame_format CameraDriver::GetVideoMode(std::string vmode){
464  if(vmode == "uncompressed") {
465  return UVC_COLOR_FORMAT_UNCOMPRESSED;
466  } else if (vmode == "compressed") {
467  return UVC_COLOR_FORMAT_COMPRESSED;
468  } else if (vmode == "yuyv") {
469  return UVC_COLOR_FORMAT_YUYV;
470  } else if (vmode == "uyvy") {
471  return UVC_COLOR_FORMAT_UYVY;
472  } else if (vmode == "rgb") {
473  return UVC_COLOR_FORMAT_RGB;
474  } else if (vmode == "bgr") {
475  return UVC_COLOR_FORMAT_BGR;
476  } else if (vmode == "mjpeg") {
477  return UVC_COLOR_FORMAT_MJPEG;
478  } else if (vmode == "gray8") {
479  return UVC_COLOR_FORMAT_GRAY8;
480  } else {
481  ROS_ERROR_STREAM("Invalid Video Mode: " << vmode);
482  ROS_WARN_STREAM("Continue using video mode: uncompressed");
483  return UVC_COLOR_FORMAT_UNCOMPRESSED;
484  }
485 };
486 
487 void CameraDriver::OpenCamera(UVCCameraConfig &new_config) {
488  assert(state_ == kStopped);
489 
490  int vendor_id = strtol(new_config.vendor.c_str(), NULL, 0);
491  int product_id = strtol(new_config.product.c_str(), NULL, 0);
492 
493  ROS_INFO("Opening camera with vendor=0x%x, product=0x%x, serial=\"%s\", index=%d",
494  vendor_id, product_id, new_config.serial.c_str(), new_config.index);
495 
496  uvc_device_t **devs;
497 
498  // Implement missing index select behavior
499  // https://github.com/ros-drivers/libuvc_ros/commit/4f30e9a0
500 #if libuvc_VERSION > 00005 /* version > 0.0.5 */
501  uvc_error_t find_err = uvc_find_devices(
502  ctx_, &devs,
503  vendor_id,
504  product_id,
505  new_config.serial.empty() ? NULL : new_config.serial.c_str());
506 
507  if (find_err != UVC_SUCCESS) {
508  uvc_perror(find_err, "uvc_find_device");
509  return;
510  }
511 
512  // select device by index
513  dev_ = NULL;
514  int dev_idx = 0;
515  while (devs[dev_idx] != NULL) {
516  if(dev_idx == new_config.index) {
517  dev_ = devs[dev_idx];
518  }
519  else {
520  uvc_unref_device(devs[dev_idx]);
521  }
522 
523  dev_idx++;
524  }
525 
526  if(dev_ == NULL) {
527  ROS_ERROR("Unable to find device at index %d", new_config.index);
528  return;
529  }
530 #else
531  uvc_error_t find_err = uvc_find_device(
532  ctx_, &dev_,
533  vendor_id,
534  product_id,
535  new_config.serial.empty() ? NULL : new_config.serial.c_str());
536 
537  if (find_err != UVC_SUCCESS) {
538  uvc_perror(find_err, "uvc_find_device");
539  return;
540  }
541 
542 #endif
543  uvc_error_t open_err = uvc_open(dev_, &devh_);
544 
545  if (open_err != UVC_SUCCESS) {
546  switch (open_err) {
547  case UVC_ERROR_ACCESS:
548 #ifdef __linux__
549  ROS_ERROR("Permission denied opening /dev/bus/usb/%03d/%03d",
550  uvc_get_bus_number(dev_), uvc_get_device_address(dev_));
551 #else
552  ROS_ERROR("Permission denied opening device %d on bus %d",
553  uvc_get_device_address(dev_), uvc_get_bus_number(dev_));
554 #endif
555  break;
556  default:
557 #ifdef __linux__
558  ROS_ERROR("Can't open /dev/bus/usb/%03d/%03d: %s (%d)",
559  uvc_get_bus_number(dev_), uvc_get_device_address(dev_),
560  uvc_strerror(open_err), open_err);
561 #else
562  ROS_ERROR("Can't open device %d on bus %d: %s (%d)",
563  uvc_get_device_address(dev_), uvc_get_bus_number(dev_),
564  uvc_strerror(open_err), open_err);
565 #endif
566  break;
567  }
568 
569  uvc_unref_device(dev_);
570  return;
571  }
572 
573  uvc_set_status_callback(devh_, &CameraDriver::AutoControlsCallbackAdapter, this);
574 
575  uvc_stream_ctrl_t ctrl;
576  uvc_error_t mode_err = uvc_get_stream_ctrl_format_size(
577  devh_, &ctrl,
578  GetVideoMode(new_config.video_mode),
579  new_config.width, new_config.height,
580  new_config.frame_rate);
581 
582  if (mode_err != UVC_SUCCESS) {
583  uvc_perror(mode_err, "uvc_get_stream_ctrl_format_size");
584  uvc_close(devh_);
585  uvc_unref_device(dev_);
586  ROS_ERROR("check video_mode/width/height/frame_rate are available");
587  uvc_print_diag(devh_, NULL);
588  return;
589  }
590 
591  uvc_error_t stream_err = uvc_start_streaming(devh_, &ctrl, &CameraDriver::ImageCallbackAdapter, this, 0);
592 
593  if (stream_err != UVC_SUCCESS) {
594  uvc_perror(stream_err, "uvc_start_streaming");
595  uvc_close(devh_);
596  uvc_unref_device(dev_);
597  return;
598  }
599 
600  if (rgb_frame_)
601  uvc_free_frame(rgb_frame_);
602 
603  rgb_frame_ = uvc_allocate_frame(new_config.width * new_config.height * 3);
604  assert(rgb_frame_);
605 
606  state_ = kRunning;
607 }
608 
610  assert(state_ == kRunning);
611 
612  uvc_close(devh_);
613  devh_ = NULL;
614 
615  uvc_unref_device(dev_);
616  dev_ = NULL;
617 
618  state_ = kStopped;
619 }
620 
621 };
libuvc_camera::CameraDriver::dev_
uvc_device_t * dev_
Definition: camera_driver.h:79
libuvc_camera::CameraDriver::device_type_client
ros::ServiceClient device_type_client
Definition: camera_driver.h:102
libuvc_camera::CameraDriver::config_server_
dynamic_reconfigure::Server< UVCCameraConfig > config_server_
Definition: camera_driver.h:86
ros::this_node::getNamespace
const ROSCPP_DECL std::string & getNamespace()
libuvc_camera::CameraDriver::getUVCExposureCb
bool getUVCExposureCb(astra_camera::GetUVCExposureRequest &req, astra_camera::GetUVCExposureResponse &res)
Definition: camera_driver.cpp:95
camera_info_manager::CameraInfoManager::getCameraInfo
sensor_msgs::CameraInfo getCameraInfo(void)
libuvc_camera
Definition: camera_driver.h:23
libuvc_camera::CameraDriver::CloseCamera
void CloseCamera()
Definition: camera_driver.cpp:609
OB_STEREO_S_NO
@ OB_STEREO_S_NO
Definition: astra_device_type.h:12
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
libuvc_camera::CameraDriver::ImageCallbackAdapter
static void ImageCallbackAdapter(uvc_frame_t *frame, void *ptr)
Definition: camera_driver.cpp:402
libuvc_camera::CameraDriver::cam_pub_
image_transport::CameraPublisher cam_pub_
Definition: camera_driver.h:84
ros.h
libuvc_camera::CameraDriver::device_type_init_
bool device_type_init_
Definition: camera_driver.h:105
libuvc_camera::CameraDriver::ns
std::string ns
Definition: camera_driver.h:92
ros::NodeHandle::serviceClient
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
libuvc_camera::CameraDriver::kInitial
@ kInitial
Definition: camera_driver.h:35
libuvc_camera::CameraDriver::nh_
ros::NodeHandle nh_
Definition: camera_driver.h:73
camera_info_manager::CameraInfoManager::loadCameraInfo
bool loadCameraInfo(const std::string &url)
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
image_transport::CameraPublisher::publish
void publish(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &info) const
libuvc_camera::CameraDriver::rgb_frame_
uvc_frame_t * rgb_frame_
Definition: camera_driver.h:81
libuvc_camera::CameraDriver::ns_no_slash
std::string ns_no_slash
Definition: camera_driver.h:93
libuvc_camera::CameraDriver::get_uvc_exposure_server
ros::ServiceServer get_uvc_exposure_server
Definition: camera_driver.h:95
libuvc_camera::CameraDriver::ReconfigureCallback
void ReconfigureCallback(UVCCameraConfig &config, uint32_t level)
Definition: camera_driver.cpp:189
image_transport::ImageTransport::advertiseCamera
CameraPublisher advertiseCamera(const std::string &base_topic, uint32_t queue_size, bool latch=false)
libuvc_camera::CameraDriver::getUVCWhiteBalanceCb
bool getUVCWhiteBalanceCb(astra_camera::GetUVCWhiteBalanceRequest &req, astra_camera::GetUVCWhiteBalanceResponse &res)
Definition: camera_driver.cpp:134
libuvc_camera::CameraDriver::camera_info_init_
bool camera_info_init_
Definition: camera_driver.h:106
libuvc_camera::CameraDriver::it_
image_transport::ImageTransport it_
Definition: camera_driver.h:83
OB_EMBEDDED_S_NO
@ OB_EMBEDDED_S_NO
Definition: astra_device_type.h:13
libuvc_camera::CameraDriver::OpenCamera
void OpenCamera(UVCCameraConfig &new_config)
Definition: camera_driver.cpp:487
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
libuvc_camera::CameraDriver::get_uvc_gain_server
ros::ServiceServer get_uvc_gain_server
Definition: camera_driver.h:97
libuvc_camera::CameraDriver::set_uvc_gain_server
ros::ServiceServer set_uvc_gain_server
Definition: camera_driver.h:98
astraWithUVC
bool astraWithUVC(OB_DEVICE_NO id)
Definition: astra_device_type.cpp:3
libuvc_camera::CameraDriver::setUVCExposureCb
bool setUVCExposureCb(astra_camera::SetUVCExposureRequest &req, astra_camera::SetUVCExposureResponse &res)
Definition: camera_driver.cpp:103
libuvc_camera::CameraDriver::state_
State state_
Definition: camera_driver.h:75
uint8_t
unsigned char uint8_t
Definition: OniPlatformWin32.h:65
OB_ASTRA_PRO_NO
@ OB_ASTRA_PRO_NO
Definition: astra_device_type.h:15
OB_EMBEDDED_S
#define OB_EMBEDDED_S
Definition: astra_device_type.h:5
libuvc_camera::CameraDriver::setUVCWhiteBalanceCb
bool setUVCWhiteBalanceCb(astra_camera::SetUVCWhiteBalanceRequest &req, astra_camera::SetUVCWhiteBalanceResponse &res)
Definition: camera_driver.cpp:142
libuvc_camera::CameraDriver::config_
UVCCameraConfig config_
Definition: camera_driver.h:87
uint16_t
unsigned short uint16_t
Definition: OniPlatformWin32.h:66
libuvc_camera::CameraDriver::camera_info_
sensor_msgs::CameraInfo camera_info_
Definition: camera_driver.h:108
libuvc_camera::CameraDriver::AutoControlsCallbackAdapter
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)
Definition: camera_driver.cpp:450
libuvc_camera::CameraDriver::~CameraDriver
~CameraDriver()
Definition: camera_driver.cpp:87
libuvc_camera::CameraDriver::ImageCallback
void ImageCallback(uvc_frame_t *frame)
Definition: camera_driver.cpp:251
libuvc_camera::CameraDriver::kRunning
@ kRunning
Definition: camera_driver.h:37
ROS_WARN
#define ROS_WARN(...)
PARAM_INT
#define PARAM_INT(name, fn, value)
libuvc_camera::CameraDriver::uvc_flip_
int uvc_flip_
Definition: camera_driver.h:109
libuvc_camera::CameraDriver::cinfo_manager_
camera_info_manager::CameraInfoManager cinfo_manager_
Definition: camera_driver.h:90
camera_driver.h
libuvc_camera::CameraDriver::camera_info_client
ros::ServiceClient camera_info_client
Definition: camera_driver.h:103
libuvc_camera::CameraDriver::set_uvc_white_balance_server
ros::ServiceServer set_uvc_white_balance_server
Definition: camera_driver.h:100
OB_STEREO_S
#define OB_STEREO_S
Definition: astra_device_type.h:4
libuvc_camera::CameraDriver::setUVCGainCb
bool setUVCGainCb(astra_camera::SetUVCGainRequest &req, astra_camera::SetUVCGainResponse &res)
Definition: camera_driver.cpp:128
libuvc_camera::CameraDriver::AutoControlsCallback
void AutoControlsCallback(enum uvc_status_class status_class, int event, int selector, enum uvc_status_attribute status_attribute, void *data, size_t data_len)
Definition: camera_driver.cpp:408
OB_ASTRA_NO
@ OB_ASTRA_NO
Definition: astra_device_type.h:11
OB_STEREO_S_U3
#define OB_STEREO_S_U3
Definition: astra_device_type.h:6
libuvc_camera::CameraDriver::set_uvc_exposure_server
ros::ServiceServer set_uvc_exposure_server
Definition: camera_driver.h:96
libuvc_camera::CameraDriver::getUVCGainCb
bool getUVCGainCb(astra_camera::GetUVCGainRequest &req, astra_camera::GetUVCGainResponse &res)
Definition: camera_driver.cpp:120
ros::Time
OB_STEREO_S_U3_NO
@ OB_STEREO_S_U3_NO
Definition: astra_device_type.h:14
libuvc_camera::CameraDriver::Stop
void Stop()
Definition: camera_driver.cpp:173
OB_ASTRA_PRO
#define OB_ASTRA_PRO
Definition: astra_device_type.h:7
libuvc_camera::CameraDriver::ctx_
uvc_context_t * ctx_
Definition: camera_driver.h:78
ROS_ERROR
#define ROS_ERROR(...)
libuvc_camera::CameraDriver::mutex_
boost::recursive_mutex mutex_
Definition: camera_driver.h:76
ros::ServiceClient::call
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
libuvc_camera::CameraDriver::config_changed_
bool config_changed_
Definition: camera_driver.h:88
libuvc_camera::CameraDriver::kReconfigureClose
static const int kReconfigureClose
Definition: camera_driver.h:41
libuvc_camera::CameraDriver::kStopped
@ kStopped
Definition: camera_driver.h:36
uint32_t
unsigned int uint32_t
Definition: OniPlatformWin32.h:67
libuvc_camera::CameraDriver::Start
bool Start()
Definition: camera_driver.cpp:154
libuvc_camera::CameraDriver
Definition: camera_driver.h:25
ROS_INFO
#define ROS_INFO(...)
libuvc_camera::CameraDriver::device_type_
std::string device_type_
Definition: camera_driver.h:107
libuvc_camera::CameraDriver::device_type_no_
OB_DEVICE_NO device_type_no_
Definition: camera_driver.h:110
libuvc_camera::CameraDriver::devh_
uvc_device_handle_t * devh_
Definition: camera_driver.h:80
libuvc_camera::CameraDriver::GetVideoMode
enum uvc_frame_format GetVideoMode(std::string vmode)
Definition: camera_driver.cpp:463
ros::NodeHandle
camera_publisher.h
libuvc_camera::CameraDriver::get_uvc_white_balance_server
ros::ServiceServer get_uvc_white_balance_server
Definition: camera_driver.h:99
libuvc_camera::CameraDriver::CameraDriver
CameraDriver(ros::NodeHandle nh, ros::NodeHandle priv_nh)
Definition: camera_driver.cpp:52
ros::Time::now
static Time now()
libuvc_camera::CameraDriver::camera_info_valid_
bool camera_info_valid_
Definition: camera_driver.h:111


ros_astra_camera
Author(s): Tim Liu
autogenerated on Wed Mar 2 2022 00:52:57