00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
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 #define libuvc_VERSION (libuvc_VERSION_MAJOR * 10000 \
00043 + libuvc_VERSION_MINOR * 100 \
00044 + libuvc_VERSION_PATCH)
00045
00046 namespace libuvc_camera {
00047
00048 CameraDriver::CameraDriver(ros::NodeHandle nh, ros::NodeHandle priv_nh)
00049 : nh_(nh), priv_nh_(priv_nh),
00050 state_(kInitial),
00051 ctx_(NULL), dev_(NULL), devh_(NULL), rgb_frame_(NULL),
00052 it_(nh_),
00053 config_server_(mutex_, priv_nh_),
00054 config_changed_(false),
00055 cinfo_manager_(nh) {
00056 cam_pub_ = it_.advertiseCamera("image_raw", 1, false);
00057 }
00058
00059 CameraDriver::~CameraDriver() {
00060 if (rgb_frame_)
00061 uvc_free_frame(rgb_frame_);
00062
00063 if (ctx_)
00064 uvc_exit(ctx_);
00065 }
00066
00067 bool CameraDriver::Start() {
00068 assert(state_ == kInitial);
00069
00070 uvc_error_t err;
00071
00072 err = uvc_init(&ctx_, NULL);
00073
00074 if (err != UVC_SUCCESS) {
00075 uvc_perror(err, "ERROR: uvc_init");
00076 return false;
00077 }
00078
00079 state_ = kStopped;
00080
00081 config_server_.setCallback(boost::bind(&CameraDriver::ReconfigureCallback, this, _1, _2));
00082
00083 return state_ == kRunning;
00084 }
00085
00086 void CameraDriver::Stop() {
00087 boost::recursive_mutex::scoped_lock(mutex_);
00088
00089 assert(state_ != kInitial);
00090
00091 if (state_ == kRunning)
00092 CloseCamera();
00093
00094 assert(state_ == kStopped);
00095
00096 uvc_exit(ctx_);
00097 ctx_ = NULL;
00098
00099 state_ = kInitial;
00100 }
00101
00102 void CameraDriver::ReconfigureCallback(UVCCameraConfig &new_config, uint32_t level) {
00103 boost::recursive_mutex::scoped_lock(mutex_);
00104
00105 if ((level & kReconfigureClose) == kReconfigureClose) {
00106 if (state_ == kRunning)
00107 CloseCamera();
00108 }
00109
00110 if (state_ == kStopped) {
00111 OpenCamera(new_config);
00112 }
00113
00114 if (new_config.camera_info_url != config_.camera_info_url)
00115 cinfo_manager_.loadCameraInfo(new_config.camera_info_url);
00116
00117 if (state_ == kRunning) {
00118 #define PARAM_INT(name, fn, value) if (new_config.name != config_.name) { \
00119 int val = (value); \
00120 if (uvc_set_##fn(devh_, val)) { \
00121 ROS_WARN("Unable to set " #name " to %d", val); \
00122 new_config.name = config_.name; \
00123 } \
00124 }
00125
00126 PARAM_INT(scanning_mode, scanning_mode, new_config.scanning_mode);
00127 PARAM_INT(auto_exposure, ae_mode, 1 << new_config.auto_exposure);
00128 PARAM_INT(auto_exposure_priority, ae_priority, new_config.auto_exposure_priority);
00129 PARAM_INT(exposure_absolute, exposure_abs, new_config.exposure_absolute * 10000);
00130 PARAM_INT(auto_focus, focus_auto, new_config.auto_focus ? 1 : 0);
00131 PARAM_INT(focus_absolute, focus_abs, new_config.focus_absolute);
00132 #if libuvc_VERSION > 00005
00133 PARAM_INT(gain, gain, new_config.gain);
00134 PARAM_INT(iris_absolute, iris_abs, new_config.iris_absolute);
00135 PARAM_INT(brightness, brightness, new_config.brightness);
00136 #endif
00137
00138
00139 if (new_config.pan_absolute != config_.pan_absolute || new_config.tilt_absolute != config_.tilt_absolute) {
00140 if (uvc_set_pantilt_abs(devh_, new_config.pan_absolute, new_config.tilt_absolute)) {
00141 ROS_WARN("Unable to set pantilt to %d, %d", new_config.pan_absolute, new_config.tilt_absolute);
00142 new_config.pan_absolute = config_.pan_absolute;
00143 new_config.tilt_absolute = config_.tilt_absolute;
00144 }
00145 }
00146
00147
00148
00149
00150
00151
00152
00153
00154
00155
00156
00157
00158
00159 }
00160
00161 config_ = new_config;
00162 }
00163
00164 void CameraDriver::ImageCallback(uvc_frame_t *frame) {
00165 ros::Time timestamp = ros::Time(frame->capture_time.tv_sec, frame->capture_time.tv_usec);
00166
00167 boost::recursive_mutex::scoped_lock(mutex_);
00168
00169 assert(state_ == kRunning);
00170 assert(rgb_frame_);
00171
00172 sensor_msgs::Image::Ptr image(new sensor_msgs::Image());
00173 image->width = config_.width;
00174 image->height = config_.height;
00175 image->step = image->width * 3;
00176 image->data.resize(image->step * image->height);
00177
00178 if (frame->frame_format == UVC_FRAME_FORMAT_BGR){
00179 image->encoding = "bgr8";
00180 memcpy(&(image->data[0]), frame->data, frame->data_bytes);
00181 } else if (frame->frame_format == UVC_FRAME_FORMAT_RGB){
00182 image->encoding = "rgb8";
00183 memcpy(&(image->data[0]), frame->data, frame->data_bytes);
00184 } else if (frame->frame_format == UVC_FRAME_FORMAT_UYVY) {
00185 image->encoding = "yuv422";
00186 memcpy(&(image->data[0]), frame->data, frame->data_bytes);
00187 } else if (frame->frame_format == UVC_FRAME_FORMAT_YUYV) {
00188
00189 uvc_error_t conv_ret = uvc_yuyv2bgr(frame, rgb_frame_);
00190 if (conv_ret != UVC_SUCCESS) {
00191 uvc_perror(conv_ret, "Couldn't convert frame to RGB");
00192 return;
00193 }
00194 image->encoding = "bgr8";
00195 memcpy(&(image->data[0]), rgb_frame_->data, rgb_frame_->data_bytes);
00196 #if libuvc_VERSION > 00005
00197 } else if (frame->frame_format == UVC_FRAME_FORMAT_MJPEG) {
00198
00199
00200 uvc_error_t conv_ret = uvc_mjpeg2rgb(frame, rgb_frame_);
00201 if (conv_ret != UVC_SUCCESS) {
00202 uvc_perror(conv_ret, "Couldn't convert frame to RGB");
00203 return;
00204 }
00205 image->encoding = "rgb8";
00206 memcpy(&(image->data[0]), rgb_frame_->data, rgb_frame_->data_bytes);
00207 #endif
00208 } else {
00209 uvc_error_t conv_ret = uvc_any2bgr(frame, rgb_frame_);
00210 if (conv_ret != UVC_SUCCESS) {
00211 uvc_perror(conv_ret, "Couldn't convert frame to RGB");
00212 return;
00213 }
00214 image->encoding = "bgr8";
00215 memcpy(&(image->data[0]), rgb_frame_->data, rgb_frame_->data_bytes);
00216 }
00217
00218
00219 sensor_msgs::CameraInfo::Ptr cinfo(
00220 new sensor_msgs::CameraInfo(cinfo_manager_.getCameraInfo()));
00221
00222 image->header.frame_id = config_.frame_id;
00223 image->header.stamp = timestamp;
00224 cinfo->header.frame_id = config_.frame_id;
00225 cinfo->header.stamp = timestamp;
00226
00227 cam_pub_.publish(image, cinfo);
00228
00229 if (config_changed_) {
00230 config_server_.updateConfig(config_);
00231 config_changed_ = false;
00232 }
00233 }
00234
00235 void CameraDriver::ImageCallbackAdapter(uvc_frame_t *frame, void *ptr) {
00236 CameraDriver *driver = static_cast<CameraDriver*>(ptr);
00237
00238 driver->ImageCallback(frame);
00239 }
00240
00241 void CameraDriver::AutoControlsCallback(
00242 enum uvc_status_class status_class,
00243 int event,
00244 int selector,
00245 enum uvc_status_attribute status_attribute,
00246 void *data, size_t data_len) {
00247 boost::recursive_mutex::scoped_lock(mutex_);
00248
00249 printf("Controls callback. class: %d, event: %d, selector: %d, attr: %d, data_len: %u\n",
00250 status_class, event, selector, status_attribute, data_len);
00251
00252 if (status_attribute == UVC_STATUS_ATTRIBUTE_VALUE_CHANGE) {
00253 switch (status_class) {
00254 case UVC_STATUS_CLASS_CONTROL_CAMERA: {
00255 switch (selector) {
00256 case UVC_CT_EXPOSURE_TIME_ABSOLUTE_CONTROL:
00257 uint8_t *data_char = (uint8_t*) data;
00258 uint32_t exposure_int = ((data_char[0]) | (data_char[1] << 8) |
00259 (data_char[2] << 16) | (data_char[3] << 24));
00260 config_.exposure_absolute = exposure_int * 0.0001;
00261 config_changed_ = true;
00262 break;
00263 }
00264 break;
00265 }
00266 case UVC_STATUS_CLASS_CONTROL_PROCESSING: {
00267 switch (selector) {
00268 case UVC_PU_WHITE_BALANCE_TEMPERATURE_CONTROL:
00269 uint8_t *data_char = (uint8_t*) data;
00270 config_.white_balance_temperature =
00271 data_char[0] | (data_char[1] << 8);
00272 config_changed_ = true;
00273 break;
00274 }
00275 break;
00276 }
00277 }
00278
00279
00280 }
00281 }
00282
00283 void CameraDriver::AutoControlsCallbackAdapter(
00284 enum uvc_status_class status_class,
00285 int event,
00286 int selector,
00287 enum uvc_status_attribute status_attribute,
00288 void *data, size_t data_len,
00289 void *ptr) {
00290 CameraDriver *driver = static_cast<CameraDriver*>(ptr);
00291
00292 driver->AutoControlsCallback(status_class, event, selector,
00293 status_attribute, data, data_len);
00294 }
00295
00296 enum uvc_frame_format CameraDriver::GetVideoMode(std::string vmode){
00297 if(vmode == "uncompressed") {
00298 return UVC_COLOR_FORMAT_UNCOMPRESSED;
00299 } else if (vmode == "compressed") {
00300 return UVC_COLOR_FORMAT_COMPRESSED;
00301 } else if (vmode == "yuyv") {
00302 return UVC_COLOR_FORMAT_YUYV;
00303 } else if (vmode == "uyvy") {
00304 return UVC_COLOR_FORMAT_UYVY;
00305 } else if (vmode == "rgb") {
00306 return UVC_COLOR_FORMAT_RGB;
00307 } else if (vmode == "bgr") {
00308 return UVC_COLOR_FORMAT_BGR;
00309 } else if (vmode == "mjpeg") {
00310 return UVC_COLOR_FORMAT_MJPEG;
00311 } else if (vmode == "gray8") {
00312 return UVC_COLOR_FORMAT_GRAY8;
00313 } else {
00314 ROS_ERROR_STREAM("Invalid Video Mode: " << vmode);
00315 ROS_WARN_STREAM("Continue using video mode: uncompressed");
00316 return UVC_COLOR_FORMAT_UNCOMPRESSED;
00317 }
00318 };
00319
00320 void CameraDriver::OpenCamera(UVCCameraConfig &new_config) {
00321 assert(state_ == kStopped);
00322
00323 int vendor_id = strtol(new_config.vendor.c_str(), NULL, 0);
00324 int product_id = strtol(new_config.product.c_str(), NULL, 0);
00325
00326 ROS_INFO("Opening camera with vendor=0x%x, product=0x%x, serial=\"%s\", index=%d",
00327 vendor_id, product_id, new_config.serial.c_str(), new_config.index);
00328
00329 uvc_device_t **devs;
00330
00331
00332
00333 #if libuvc_VERSION > 00005
00334 uvc_error_t find_err = uvc_find_devices(
00335 ctx_, &devs,
00336 vendor_id,
00337 product_id,
00338 new_config.serial.empty() ? NULL : new_config.serial.c_str());
00339
00340 if (find_err != UVC_SUCCESS) {
00341 uvc_perror(find_err, "uvc_find_device");
00342 return;
00343 }
00344
00345
00346 dev_ = NULL;
00347 int dev_idx = 0;
00348 while (devs[dev_idx] != NULL) {
00349 if(dev_idx == new_config.index) {
00350 dev_ = devs[dev_idx];
00351 }
00352 else {
00353 uvc_unref_device(devs[dev_idx]);
00354 }
00355
00356 dev_idx++;
00357 }
00358
00359 if(dev_ == NULL) {
00360 ROS_ERROR("Unable to find device at index %d", new_config.index);
00361 return;
00362 }
00363 #else
00364 uvc_error_t find_err = uvc_find_device(
00365 ctx_, &dev_,
00366 vendor_id,
00367 product_id,
00368 new_config.serial.empty() ? NULL : new_config.serial.c_str());
00369
00370 if (find_err != UVC_SUCCESS) {
00371 uvc_perror(find_err, "uvc_find_device");
00372 return;
00373 }
00374
00375 #endif
00376 uvc_error_t open_err = uvc_open(dev_, &devh_);
00377
00378 if (open_err != UVC_SUCCESS) {
00379 switch (open_err) {
00380 case UVC_ERROR_ACCESS:
00381 #ifdef __linux__
00382 ROS_ERROR("Permission denied opening /dev/bus/usb/%03d/%03d",
00383 uvc_get_bus_number(dev_), uvc_get_device_address(dev_));
00384 #else
00385 ROS_ERROR("Permission denied opening device %d on bus %d",
00386 uvc_get_device_address(dev_), uvc_get_bus_number(dev_));
00387 #endif
00388 break;
00389 default:
00390 #ifdef __linux__
00391 ROS_ERROR("Can't open /dev/bus/usb/%03d/%03d: %s (%d)",
00392 uvc_get_bus_number(dev_), uvc_get_device_address(dev_),
00393 uvc_strerror(open_err), open_err);
00394 #else
00395 ROS_ERROR("Can't open device %d on bus %d: %s (%d)",
00396 uvc_get_device_address(dev_), uvc_get_bus_number(dev_),
00397 uvc_strerror(open_err), open_err);
00398 #endif
00399 break;
00400 }
00401
00402 uvc_unref_device(dev_);
00403 return;
00404 }
00405
00406 uvc_set_status_callback(devh_, &CameraDriver::AutoControlsCallbackAdapter, this);
00407
00408 uvc_stream_ctrl_t ctrl;
00409 uvc_error_t mode_err = uvc_get_stream_ctrl_format_size(
00410 devh_, &ctrl,
00411 GetVideoMode(new_config.video_mode),
00412 new_config.width, new_config.height,
00413 new_config.frame_rate);
00414
00415 if (mode_err != UVC_SUCCESS) {
00416 uvc_perror(mode_err, "uvc_get_stream_ctrl_format_size");
00417 uvc_close(devh_);
00418 uvc_unref_device(dev_);
00419 ROS_ERROR("check video_mode/width/height/frame_rate are available");
00420 uvc_print_diag(devh_, NULL);
00421 return;
00422 }
00423
00424 uvc_error_t stream_err = uvc_start_streaming(devh_, &ctrl, &CameraDriver::ImageCallbackAdapter, this, 0);
00425
00426 if (stream_err != UVC_SUCCESS) {
00427 uvc_perror(stream_err, "uvc_start_streaming");
00428 uvc_close(devh_);
00429 uvc_unref_device(dev_);
00430 return;
00431 }
00432
00433 if (rgb_frame_)
00434 uvc_free_frame(rgb_frame_);
00435
00436 rgb_frame_ = uvc_allocate_frame(new_config.width * new_config.height * 3);
00437 assert(rgb_frame_);
00438
00439 state_ = kRunning;
00440 }
00441
00442 void CameraDriver::CloseCamera() {
00443 assert(state_ == kRunning);
00444
00445 uvc_close(devh_);
00446 devh_ = NULL;
00447
00448 uvc_unref_device(dev_);
00449 dev_ = NULL;
00450
00451 state_ = kStopped;
00452 }
00453
00454 };