camera_driver.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (C) 2012 Ken Tossell
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the author nor other contributors may be
00018 *     used to endorse or promote products derived from this software
00019 *     without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 #include "libuvc_camera/camera_driver.h"
00035 
00036 #include <ros/ros.h>
00037 #include <sensor_msgs/Image.h>
00038 #include <std_msgs/Header.h>
00039 #include <image_transport/camera_publisher.h>
00040 #include <dynamic_reconfigure/server.h>
00041 #include <libuvc/libuvc.h>
00042 #include <astra_camera/GetDeviceType.h>
00043 #include <astra_camera/GetCameraInfo.h>
00044 #include <astra_camera/astra_device_type.h>
00045 
00046 #define libuvc_VERSION (libuvc_VERSION_MAJOR * 10000 \
00047                       + libuvc_VERSION_MINOR * 100 \
00048                       + libuvc_VERSION_PATCH)
00049 
00050 namespace libuvc_camera {
00051 
00052 CameraDriver::CameraDriver(ros::NodeHandle nh, ros::NodeHandle priv_nh)
00053   : nh_(nh), priv_nh_(priv_nh),
00054     state_(kInitial),
00055     ctx_(NULL), dev_(NULL), devh_(NULL), rgb_frame_(NULL),
00056     it_(nh_),
00057     config_server_(mutex_, priv_nh_),
00058     config_changed_(false),
00059     cinfo_manager_(nh),
00060     param_init_(false) {
00061   cam_pub_ = it_.advertiseCamera("image_raw", 1, false);
00062   ns = ros::this_node::getNamespace();
00063   device_type_client = nh_.serviceClient<astra_camera::GetDeviceType>(ns + "/get_device_type");
00064   camera_info_client = nh_.serviceClient<astra_camera::GetCameraInfo>(ns + "/get_camera_info");
00065   get_uvc_exposure_server = nh_.advertiseService("get_uvc_exposure", &CameraDriver::getUVCExposureCb, this);
00066   set_uvc_exposure_server = nh_.advertiseService("set_uvc_exposure", &CameraDriver::setUVCExposureCb, this);
00067   get_uvc_gain_server = nh_.advertiseService("get_uvc_gain", &CameraDriver::getUVCGainCb, this);
00068   set_uvc_gain_server = nh_.advertiseService("set_uvc_gain", &CameraDriver::setUVCGainCb, this);
00069   get_uvc_white_balance_server = nh_.advertiseService("get_uvc_white_balance", &CameraDriver::getUVCWhiteBalanceCb, this);
00070   set_uvc_white_balance_server = nh_.advertiseService("set_uvc_white_balance", &CameraDriver::setUVCWhiteBalanceCb, this);
00071   device_type_init_ = false;
00072   camera_info_init_ = false;
00073   uvc_flip_ = 0;
00074   device_type_no_ = OB_ASTRA_NO;
00075   if (ns.length() > 1)
00076   {
00077     ns_no_slash = ns.substr(1);
00078   }
00079 }
00080 
00081 CameraDriver::~CameraDriver() {
00082   if (rgb_frame_)
00083     uvc_free_frame(rgb_frame_);
00084 
00085   if (ctx_)
00086     uvc_exit(ctx_);  // Destroys dev_, devh_, etc.
00087 }
00088 
00089 bool CameraDriver::getUVCExposureCb(astra_camera::GetUVCExposureRequest& req, astra_camera::GetUVCExposureResponse& res)
00090 {
00091   uint32_t expo;
00092   uvc_error_t err = uvc_get_exposure_abs(devh_, &expo, UVC_GET_CUR);
00093   res.exposure = expo;
00094   return (err == UVC_SUCCESS);
00095 }
00096 
00097 bool CameraDriver::setUVCExposureCb(astra_camera::SetUVCExposureRequest& req, astra_camera::SetUVCExposureResponse& res)
00098 {
00099   if (req.exposure == 0)
00100   {
00101     uvc_set_ae_mode(devh_, 2);
00102     return true;
00103   }
00104   uvc_set_ae_mode(devh_, 1); // mode 1: manual mode; 2: auto mode; 4: shutter priority mode; 8: aperture priority mode
00105   if (req.exposure > 330)
00106   {
00107     ROS_ERROR("Please set exposure lower than 330");
00108     return false;
00109   }
00110   uvc_error_t err = uvc_set_exposure_abs(devh_, req.exposure);
00111   return (err == UVC_SUCCESS);
00112 }
00113 
00114 bool CameraDriver::getUVCGainCb(astra_camera::GetUVCGainRequest& req, astra_camera::GetUVCGainResponse& res)
00115 {
00116   uint16_t gain;
00117   uvc_error_t err = uvc_get_gain(devh_, &gain, UVC_GET_CUR);
00118   res.gain = gain;
00119   return (err == UVC_SUCCESS); 
00120 }
00121 
00122 bool CameraDriver::setUVCGainCb(astra_camera::SetUVCGainRequest& req, astra_camera::SetUVCGainResponse& res)
00123 {
00124   uvc_error_t err = uvc_set_gain(devh_, req.gain);
00125   return (err == UVC_SUCCESS);
00126 }
00127 
00128 bool CameraDriver::getUVCWhiteBalanceCb(astra_camera::GetUVCWhiteBalanceRequest& req, astra_camera::GetUVCWhiteBalanceResponse& res)
00129 {
00130   uint16_t white_balance;
00131   uvc_error_t err = uvc_get_white_balance_temperature(devh_, &white_balance, UVC_GET_CUR);
00132   res.white_balance = white_balance;
00133   return (err == UVC_SUCCESS);
00134 }
00135 
00136 bool CameraDriver::setUVCWhiteBalanceCb(astra_camera::SetUVCWhiteBalanceRequest& req, astra_camera::SetUVCWhiteBalanceResponse& res)
00137 {
00138   if (req.white_balance == 0)
00139   {
00140     uvc_set_white_balance_temperature_auto(devh_, 1);
00141     return true;
00142   }
00143   uvc_set_white_balance_temperature_auto(devh_, 0); // 0: manual, 1: auto
00144   uvc_error_t err = uvc_set_white_balance_temperature(devh_, req.white_balance);
00145   return (err == UVC_SUCCESS);
00146 }
00147 
00148 bool CameraDriver::Start() {
00149   assert(state_ == kInitial);
00150 
00151   uvc_error_t err;
00152 
00153   err = uvc_init(&ctx_, NULL);
00154 
00155   if (err != UVC_SUCCESS) {
00156     uvc_perror(err, "ERROR: uvc_init");
00157     return false;
00158   }
00159 
00160   state_ = kStopped;
00161 
00162   config_server_.setCallback(boost::bind(&CameraDriver::ReconfigureCallback, this, _1, _2));
00163 
00164   return state_ == kRunning;
00165 }
00166 
00167 void CameraDriver::Stop() {
00168   boost::recursive_mutex::scoped_lock(mutex_);
00169 
00170   assert(state_ != kInitial);
00171 
00172   if (state_ == kRunning)
00173     CloseCamera();
00174 
00175   assert(state_ == kStopped);
00176 
00177   uvc_exit(ctx_);
00178   ctx_ = NULL;
00179 
00180   state_ = kInitial;
00181 }
00182 
00183 void CameraDriver::ReconfigureCallback(UVCCameraConfig &new_config, uint32_t level) {
00184   boost::recursive_mutex::scoped_lock(mutex_);
00185 
00186   if ((level & kReconfigureClose) == kReconfigureClose) {
00187     if (state_ == kRunning)
00188       CloseCamera();
00189   }
00190 
00191   if (state_ == kStopped) {
00192     OpenCamera(new_config);
00193   }
00194 
00195   if (new_config.camera_info_url != config_.camera_info_url)
00196     cinfo_manager_.loadCameraInfo(new_config.camera_info_url);
00197 
00198   if (state_ == kRunning) {
00199 #define PARAM_INT(name, fn, value) if (new_config.name != config_.name) { \
00200       int val = (value);                                                \
00201       if (uvc_set_##fn(devh_, val)) {                                   \
00202         ROS_WARN("Unable to set " #name " to %d", val);                 \
00203         new_config.name = config_.name;                                 \
00204       }                                                                 \
00205     }
00206 
00207     PARAM_INT(scanning_mode, scanning_mode, new_config.scanning_mode);
00208     PARAM_INT(auto_exposure, ae_mode, 1 << new_config.auto_exposure);
00209     PARAM_INT(auto_exposure_priority, ae_priority, new_config.auto_exposure_priority);
00210     PARAM_INT(exposure_absolute, exposure_abs, new_config.exposure_absolute * 10000);
00211     PARAM_INT(auto_focus, focus_auto, new_config.auto_focus ? 1 : 0);
00212     PARAM_INT(focus_absolute, focus_abs, new_config.focus_absolute);
00213 #if libuvc_VERSION     > 00005 /* version > 0.0.5 */
00214     PARAM_INT(gain, gain, new_config.gain);
00215     PARAM_INT(iris_absolute, iris_abs, new_config.iris_absolute);
00216     PARAM_INT(brightness, brightness, new_config.brightness);
00217 #endif
00218     
00219 
00220     if (new_config.pan_absolute != config_.pan_absolute || new_config.tilt_absolute != config_.tilt_absolute) {
00221       if (uvc_set_pantilt_abs(devh_, new_config.pan_absolute, new_config.tilt_absolute)) {
00222         ROS_WARN("Unable to set pantilt to %d, %d", new_config.pan_absolute, new_config.tilt_absolute);
00223         new_config.pan_absolute = config_.pan_absolute;
00224         new_config.tilt_absolute = config_.tilt_absolute;
00225       }
00226     }
00227     // TODO: roll_absolute
00228     // TODO: privacy
00229     // TODO: backlight_compensation
00230     // TODO: contrast
00231     // TODO: power_line_frequency
00232     // TODO: auto_hue
00233     // TODO: saturation
00234     // TODO: sharpness
00235     // TODO: gamma
00236     // TODO: auto_white_balance
00237     // TODO: white_balance_temperature
00238     // TODO: white_balance_BU
00239     // TODO: white_balance_RV
00240   }
00241 
00242   config_ = new_config;
00243 }
00244 
00245 void CameraDriver::ImageCallback(uvc_frame_t *frame) {
00246   ros::Time timestamp = ros::Time(frame->capture_time.tv_sec, frame->capture_time.tv_usec);
00247   if ( timestamp == ros::Time(0) ) {
00248     timestamp = ros::Time::now();
00249   }
00250 
00251   boost::recursive_mutex::scoped_lock(mutex_);
00252 
00253   assert(state_ == kRunning);
00254   assert(rgb_frame_);
00255 
00256   sensor_msgs::Image::Ptr image(new sensor_msgs::Image());
00257   image->width = config_.width;
00258   image->height = config_.height;
00259   image->step = image->width * 3;
00260   image->data.resize(image->step * image->height);
00261 
00262   if (frame->frame_format == UVC_FRAME_FORMAT_BGR){
00263     image->encoding = "bgr8";
00264     memcpy(&(image->data[0]), frame->data, frame->data_bytes);
00265   } else if (frame->frame_format == UVC_FRAME_FORMAT_RGB){
00266     image->encoding = "rgb8";
00267     memcpy(&(image->data[0]), frame->data, frame->data_bytes);
00268   } else if (frame->frame_format == UVC_FRAME_FORMAT_UYVY) {
00269     image->encoding = "yuv422";
00270     memcpy(&(image->data[0]), frame->data, frame->data_bytes);
00271   } else if (frame->frame_format == UVC_FRAME_FORMAT_YUYV) {
00272     // FIXME: uvc_any2bgr does not work on "yuyv" format, so use uvc_yuyv2bgr directly.
00273     uvc_error_t conv_ret = uvc_yuyv2bgr(frame, rgb_frame_);
00274     if (conv_ret != UVC_SUCCESS) {
00275       uvc_perror(conv_ret, "Couldn't convert frame to RGB");
00276       return;
00277     }
00278     image->encoding = "bgr8";
00279     memcpy(&(image->data[0]), rgb_frame_->data, rgb_frame_->data_bytes);
00280 #if libuvc_VERSION     > 00005 /* version > 0.0.5 */
00281   } else if (frame->frame_format == UVC_FRAME_FORMAT_MJPEG) {
00282     // Enable mjpeg support despite uvs_any2bgr shortcoming
00283     //  https://github.com/ros-drivers/libuvc_ros/commit/7508a09f
00284     uvc_error_t conv_ret = uvc_mjpeg2rgb(frame, rgb_frame_);
00285     if (conv_ret != UVC_SUCCESS) {
00286       uvc_perror(conv_ret, "Couldn't convert frame to RGB");
00287       return;
00288     }
00289     image->encoding = "rgb8";
00290     memcpy(&(image->data[0]), rgb_frame_->data, rgb_frame_->data_bytes);
00291 #endif
00292   } else {
00293     uvc_error_t conv_ret = uvc_any2bgr(frame, rgb_frame_);
00294     if (conv_ret != UVC_SUCCESS) {
00295       uvc_perror(conv_ret, "Couldn't convert frame to RGB");
00296       return;
00297     }
00298     image->encoding = "bgr8";
00299     memcpy(&(image->data[0]), rgb_frame_->data, rgb_frame_->data_bytes);
00300   }
00301 
00302   astra_camera::GetDeviceType device_type_srv;
00303   astra_camera::GetCameraInfo camera_info_srv;
00304 
00305   if (device_type_init_ == false)
00306   {
00307     if (device_type_client.call(device_type_srv))
00308     {
00309       device_type_ = device_type_srv.response.device_type;
00310       if (strcmp(device_type_.c_str(), OB_STEREO_S) == 0)
00311       {
00312         device_type_no_ = OB_STEREO_S_NO;
00313       }
00314       else if (strcmp(device_type_.c_str(), OB_EMBEDDED_S) == 0)
00315       {
00316         device_type_no_ = OB_EMBEDDED_S_NO;
00317         uvc_flip_ = 1;
00318       }
00319       else if (strcmp(device_type_.c_str(), OB_ASTRA_PRO) == 0)
00320       {
00321         device_type_no_ = OB_ASTRA_PRO_NO;
00322       }
00323       else
00324       {
00325         device_type_no_ = OB_ASTRA_NO;
00326       }
00327       device_type_init_ = true;
00328     }
00329   }
00330 
00331   if (camera_info_init_ == false)
00332   {
00333     if (camera_info_client.call(camera_info_srv))
00334     {
00335       camera_info_ = camera_info_srv.response.info;
00336       camera_info_init_ = true;
00337     }
00338   }
00339 
00340   sensor_msgs::CameraInfo::Ptr cinfo(new sensor_msgs::CameraInfo(cinfo_manager_.getCameraInfo()));
00341   if (device_type_init_ == true &&
00342       (device_type_no_ == OB_STEREO_S_NO || device_type_no_ == OB_EMBEDDED_S_NO ||
00343        device_type_no_ == OB_ASTRA_PRO_NO))
00344   {
00345     // update cinfo
00346     if (camera_info_init_ == true)
00347     {
00348       cinfo->height = image->height;
00349       cinfo->width = image->width;
00350       cinfo->distortion_model = camera_info_.distortion_model;
00351       cinfo->D.resize(5, 0.0);
00352       for (int i = 0; i < 5; i++)
00353       {
00354         cinfo->D[i] = camera_info_.D[i];
00355       }
00356       for (int i = 0; i < 9; i++)
00357       {
00358         cinfo->K[i] = camera_info_.K[i];
00359         cinfo->R[i] = camera_info_.R[i];
00360       }
00361       cinfo->K[0] = (1 - uvc_flip_)*(camera_info_.K[0]) + (uvc_flip_)*(-camera_info_.K[0]);
00362       cinfo->K[2] = (1 - uvc_flip_)*(camera_info_.K[2]) + (uvc_flip_)*(image->width - camera_info_.K[2]);
00363       for (int i = 0; i < 12; i++)
00364       {
00365         cinfo->P[i] = camera_info_.P[i];
00366       }
00367     }
00368     image->header.frame_id = ns_no_slash + "_rgb_optical_frame";
00369     cinfo->header.frame_id = ns_no_slash + "_rgb_optical_frame";
00370   }
00371   else
00372   {
00373     image->header.frame_id = config_.frame_id;
00374     cinfo->header.frame_id = config_.frame_id;
00375   }
00376   image->header.stamp = timestamp;
00377   cinfo->header.stamp = timestamp;
00378 
00379   cam_pub_.publish(image, cinfo);
00380 
00381   if (config_changed_)
00382   {
00383     config_server_.updateConfig(config_);
00384     config_changed_ = false;
00385   }
00386 }
00387 
00388 /* static */ void CameraDriver::ImageCallbackAdapter(uvc_frame_t *frame, void *ptr) {
00389   CameraDriver *driver = static_cast<CameraDriver*>(ptr);
00390 
00391   driver->ImageCallback(frame);
00392 }
00393 
00394 void CameraDriver::AutoControlsCallback(
00395   enum uvc_status_class status_class,
00396   int event,
00397   int selector,
00398   enum uvc_status_attribute status_attribute,
00399   void *data, size_t data_len) {
00400   boost::recursive_mutex::scoped_lock(mutex_);
00401 
00402   printf("Controls callback. class: %d, event: %d, selector: %d, attr: %d, data_len: %zu\n",
00403          status_class, event, selector, status_attribute, data_len);
00404 
00405   if (status_attribute == UVC_STATUS_ATTRIBUTE_VALUE_CHANGE) {
00406     switch (status_class) {
00407     case UVC_STATUS_CLASS_CONTROL_CAMERA: {
00408       switch (selector) {
00409       case UVC_CT_EXPOSURE_TIME_ABSOLUTE_CONTROL:
00410         uint8_t *data_char = (uint8_t*) data;
00411         uint32_t exposure_int = ((data_char[0]) | (data_char[1] << 8) |
00412                                  (data_char[2] << 16) | (data_char[3] << 24));
00413         config_.exposure_absolute = exposure_int * 0.0001;
00414         config_changed_ = true;
00415         break;
00416       }
00417       break;
00418     }
00419     case UVC_STATUS_CLASS_CONTROL_PROCESSING: {
00420       switch (selector) {
00421       case UVC_PU_WHITE_BALANCE_TEMPERATURE_CONTROL:
00422         uint8_t *data_char = (uint8_t*) data;
00423         config_.white_balance_temperature = 
00424           data_char[0] | (data_char[1] << 8);
00425         config_changed_ = true;
00426         break;
00427       }
00428       break;
00429     }
00430     }
00431 
00432     // config_server_.updateConfig(config_);
00433   }
00434 }
00435 
00436 /* static */ void CameraDriver::AutoControlsCallbackAdapter(
00437   enum uvc_status_class status_class,
00438   int event,
00439   int selector,
00440   enum uvc_status_attribute status_attribute,
00441   void *data, size_t data_len,
00442   void *ptr) {
00443   CameraDriver *driver = static_cast<CameraDriver*>(ptr);
00444 
00445   driver->AutoControlsCallback(status_class, event, selector,
00446                                status_attribute, data, data_len);
00447 }
00448 
00449 enum uvc_frame_format CameraDriver::GetVideoMode(std::string vmode){
00450   if(vmode == "uncompressed") {
00451     return UVC_COLOR_FORMAT_UNCOMPRESSED;
00452   } else if (vmode == "compressed") {
00453     return UVC_COLOR_FORMAT_COMPRESSED;
00454   } else if (vmode == "yuyv") {
00455     return UVC_COLOR_FORMAT_YUYV;
00456   } else if (vmode == "uyvy") {
00457     return UVC_COLOR_FORMAT_UYVY;
00458   } else if (vmode == "rgb") {
00459     return UVC_COLOR_FORMAT_RGB;
00460   } else if (vmode == "bgr") {
00461     return UVC_COLOR_FORMAT_BGR;
00462   } else if (vmode == "mjpeg") {
00463     return UVC_COLOR_FORMAT_MJPEG;
00464   } else if (vmode == "gray8") {
00465     return UVC_COLOR_FORMAT_GRAY8;
00466   } else {
00467     ROS_ERROR_STREAM("Invalid Video Mode: " << vmode);
00468     ROS_WARN_STREAM("Continue using video mode: uncompressed");
00469     return UVC_COLOR_FORMAT_UNCOMPRESSED;
00470   }
00471 };
00472 
00473 void CameraDriver::OpenCamera(UVCCameraConfig &new_config) {
00474   assert(state_ == kStopped);
00475 
00476   int vendor_id = strtol(new_config.vendor.c_str(), NULL, 0);
00477   int product_id = strtol(new_config.product.c_str(), NULL, 0);
00478 
00479   ROS_INFO("Opening camera with vendor=0x%x, product=0x%x, serial=\"%s\", index=%d",
00480            vendor_id, product_id, new_config.serial.c_str(), new_config.index);
00481 
00482   uvc_device_t **devs;
00483 
00484   // Implement missing index select behavior
00485   // https://github.com/ros-drivers/libuvc_ros/commit/4f30e9a0
00486 #if libuvc_VERSION     > 00005 /* version > 0.0.5 */
00487   uvc_error_t find_err = uvc_find_devices(
00488     ctx_, &devs,
00489     vendor_id,
00490     product_id,
00491     new_config.serial.empty() ? NULL : new_config.serial.c_str());
00492 
00493   if (find_err != UVC_SUCCESS) {
00494     uvc_perror(find_err, "uvc_find_device");
00495     return;
00496   }
00497 
00498   // select device by index
00499   dev_ = NULL;
00500   int dev_idx = 0;
00501   while (devs[dev_idx] != NULL) {
00502     if(dev_idx == new_config.index) {
00503       dev_ = devs[dev_idx];
00504     }
00505     else {
00506       uvc_unref_device(devs[dev_idx]);
00507     }
00508 
00509     dev_idx++;
00510   }
00511 
00512   if(dev_ == NULL) {
00513     ROS_ERROR("Unable to find device at index %d", new_config.index);
00514     return;
00515   }
00516 #else
00517   uvc_error_t find_err = uvc_find_device(
00518     ctx_, &dev_,
00519     vendor_id,
00520     product_id,
00521     new_config.serial.empty() ? NULL : new_config.serial.c_str());
00522 
00523   if (find_err != UVC_SUCCESS) {
00524     uvc_perror(find_err, "uvc_find_device");
00525     return;
00526   }
00527 
00528 #endif
00529   uvc_error_t open_err = uvc_open(dev_, &devh_);
00530 
00531   if (open_err != UVC_SUCCESS) {
00532     switch (open_err) {
00533     case UVC_ERROR_ACCESS:
00534 #ifdef __linux__
00535       ROS_ERROR("Permission denied opening /dev/bus/usb/%03d/%03d",
00536                 uvc_get_bus_number(dev_), uvc_get_device_address(dev_));
00537 #else
00538       ROS_ERROR("Permission denied opening device %d on bus %d",
00539                 uvc_get_device_address(dev_), uvc_get_bus_number(dev_));
00540 #endif
00541       break;
00542     default:
00543 #ifdef __linux__
00544       ROS_ERROR("Can't open /dev/bus/usb/%03d/%03d: %s (%d)",
00545                 uvc_get_bus_number(dev_), uvc_get_device_address(dev_),
00546                 uvc_strerror(open_err), open_err);
00547 #else
00548       ROS_ERROR("Can't open device %d on bus %d: %s (%d)",
00549                 uvc_get_device_address(dev_), uvc_get_bus_number(dev_),
00550                 uvc_strerror(open_err), open_err);
00551 #endif
00552       break;
00553     }
00554 
00555     uvc_unref_device(dev_);
00556     return;
00557   }
00558 
00559   uvc_set_status_callback(devh_, &CameraDriver::AutoControlsCallbackAdapter, this);
00560 
00561   uvc_stream_ctrl_t ctrl;
00562   uvc_error_t mode_err = uvc_get_stream_ctrl_format_size(
00563     devh_, &ctrl,
00564     GetVideoMode(new_config.video_mode),
00565     new_config.width, new_config.height,
00566     new_config.frame_rate);
00567 
00568   if (mode_err != UVC_SUCCESS) {
00569     uvc_perror(mode_err, "uvc_get_stream_ctrl_format_size");
00570     uvc_close(devh_);
00571     uvc_unref_device(dev_);
00572     ROS_ERROR("check video_mode/width/height/frame_rate are available");
00573     uvc_print_diag(devh_, NULL);
00574     return;
00575   }
00576 
00577   uvc_error_t stream_err = uvc_start_streaming(devh_, &ctrl, &CameraDriver::ImageCallbackAdapter, this, 0);
00578 
00579   if (stream_err != UVC_SUCCESS) {
00580     uvc_perror(stream_err, "uvc_start_streaming");
00581     uvc_close(devh_);
00582     uvc_unref_device(dev_);
00583     return;
00584   }
00585 
00586   if (rgb_frame_)
00587     uvc_free_frame(rgb_frame_);
00588 
00589   rgb_frame_ = uvc_allocate_frame(new_config.width * new_config.height * 3);
00590   assert(rgb_frame_);
00591 
00592   state_ = kRunning;
00593 }
00594 
00595 void CameraDriver::CloseCamera() {
00596   assert(state_ == kRunning);
00597 
00598   uvc_close(devh_);
00599   devh_ = NULL;
00600 
00601   uvc_unref_device(dev_);
00602   dev_ = NULL;
00603 
00604   state_ = kStopped;
00605 }
00606 
00607 };


astra_camera
Author(s): Tim Liu
autogenerated on Wed Jul 10 2019 03:18:54