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>
46 #define libuvc_VERSION (libuvc_VERSION_MAJOR * 10000 \
47 + libuvc_VERSION_MINOR * 100 \
48 + libuvc_VERSION_PATCH)
53 : nh_(nh), priv_nh_(priv_nh),
55 ctx_(NULL), dev_(NULL), devh_(NULL), rgb_frame_(NULL),
57 config_server_(mutex_, priv_nh_),
58 config_changed_(false),
76 for (slash_end = 0; slash_end <
ns.length(); slash_end++)
78 if (
ns[slash_end] !=
'/')
98 uvc_error_t err = uvc_get_exposure_abs(
devh_, &expo, UVC_GET_CUR);
100 return (err == UVC_SUCCESS);
105 if (req.exposure == 0)
107 uvc_set_ae_mode(
devh_, 2);
110 uvc_set_ae_mode(
devh_, 1);
111 if (req.exposure > 330)
113 ROS_ERROR(
"Please set exposure lower than 330");
116 uvc_error_t err = uvc_set_exposure_abs(
devh_, req.exposure);
117 return (err == UVC_SUCCESS);
123 uvc_error_t err = uvc_get_gain(
devh_, &gain, UVC_GET_CUR);
125 return (err == UVC_SUCCESS);
130 uvc_error_t err = uvc_set_gain(
devh_, req.gain);
131 return (err == UVC_SUCCESS);
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);
144 if (req.white_balance == 0)
146 uvc_set_white_balance_temperature_auto(
devh_, 1);
149 uvc_set_white_balance_temperature_auto(
devh_, 0);
150 uvc_error_t err = uvc_set_white_balance_temperature(
devh_, req.white_balance);
151 return (err == UVC_SUCCESS);
159 err = uvc_init(&
ctx_, NULL);
161 if (err != UVC_SUCCESS) {
162 uvc_perror(err,
"ERROR: uvc_init");
174 boost::recursive_mutex::scoped_lock(
mutex_);
190 boost::recursive_mutex::scoped_lock(
mutex_);
201 if (new_config.camera_info_url !=
config_.camera_info_url)
205 #define PARAM_INT(name, fn, value) if (new_config.name != config_.name) { \
207 if (uvc_set_##fn(devh_, val)) { \
208 ROS_WARN("Unable to set " #name " to %d", val); \
209 new_config.name = config_.name; \
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
221 PARAM_INT(iris_absolute, iris_abs, new_config.iris_absolute);
222 PARAM_INT(brightness, brightness, new_config.brightness);
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;
252 ros::Time timestamp =
ros::Time(frame->capture_time.tv_sec, frame->capture_time.tv_usec);
257 boost::recursive_mutex::scoped_lock(
mutex_);
262 sensor_msgs::Image::Ptr image(
new sensor_msgs::Image());
264 image->height =
config_.height;
265 image->step = image->width * 3;
266 image->data.resize(image->step * image->height);
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) {
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");
284 image->encoding =
"bgr8";
286 #if libuvc_VERSION > 00005
287 }
else if (frame->frame_format == UVC_FRAME_FORMAT_MJPEG) {
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");
295 image->encoding =
"rgb8";
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");
304 image->encoding =
"bgr8";
308 astra_camera::GetDeviceType device_type_srv;
309 astra_camera::GetCameraInfo camera_info_srv;
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;
370 for (
int i = 0; i < 9; i++)
377 for (
int i = 0; i < 12; i++)
382 image->header.frame_id =
ns_no_slash +
"_rgb_optical_frame";
383 cinfo->header.frame_id =
ns_no_slash +
"_rgb_optical_frame";
387 image->header.frame_id =
config_.frame_id;
388 cinfo->header.frame_id =
config_.frame_id;
390 image->header.stamp = timestamp;
391 cinfo->header.stamp = timestamp;
409 enum uvc_status_class status_class,
412 enum uvc_status_attribute status_attribute,
413 void *data,
size_t data_len) {
414 boost::recursive_mutex::scoped_lock(
mutex_);
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);
419 if (status_attribute == UVC_STATUS_ATTRIBUTE_VALUE_CHANGE) {
420 switch (status_class) {
421 case UVC_STATUS_CLASS_CONTROL_CAMERA: {
423 case UVC_CT_EXPOSURE_TIME_ABSOLUTE_CONTROL:
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;
433 case UVC_STATUS_CLASS_CONTROL_PROCESSING: {
435 case UVC_PU_WHITE_BALANCE_TEMPERATURE_CONTROL:
437 config_.white_balance_temperature =
438 data_char[0] | (data_char[1] << 8);
451 enum uvc_status_class status_class,
454 enum uvc_status_attribute status_attribute,
455 void *data,
size_t data_len,
460 status_attribute, data, data_len);
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;
483 return UVC_COLOR_FORMAT_UNCOMPRESSED;
490 int vendor_id = strtol(new_config.vendor.c_str(), NULL, 0);
491 int product_id = strtol(new_config.product.c_str(), NULL, 0);
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);
500 #if libuvc_VERSION > 00005
501 uvc_error_t find_err = uvc_find_devices(
505 new_config.serial.empty() ? NULL : new_config.serial.c_str());
507 if (find_err != UVC_SUCCESS) {
508 uvc_perror(find_err,
"uvc_find_device");
515 while (devs[dev_idx] != NULL) {
516 if(dev_idx == new_config.index) {
517 dev_ = devs[dev_idx];
520 uvc_unref_device(devs[dev_idx]);
527 ROS_ERROR(
"Unable to find device at index %d", new_config.index);
531 uvc_error_t find_err = uvc_find_device(
535 new_config.serial.empty() ? NULL : new_config.serial.c_str());
537 if (find_err != UVC_SUCCESS) {
538 uvc_perror(find_err,
"uvc_find_device");
543 uvc_error_t open_err = uvc_open(
dev_, &
devh_);
545 if (open_err != UVC_SUCCESS) {
547 case UVC_ERROR_ACCESS:
549 ROS_ERROR(
"Permission denied opening /dev/bus/usb/%03d/%03d",
550 uvc_get_bus_number(
dev_), uvc_get_device_address(
dev_));
552 ROS_ERROR(
"Permission denied opening device %d on bus %d",
553 uvc_get_device_address(
dev_), uvc_get_bus_number(
dev_));
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);
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);
569 uvc_unref_device(
dev_);
575 uvc_stream_ctrl_t ctrl;
576 uvc_error_t mode_err = uvc_get_stream_ctrl_format_size(
579 new_config.width, new_config.height,
580 new_config.frame_rate);
582 if (mode_err != UVC_SUCCESS) {
583 uvc_perror(mode_err,
"uvc_get_stream_ctrl_format_size");
585 uvc_unref_device(
dev_);
586 ROS_ERROR(
"check video_mode/width/height/frame_rate are available");
587 uvc_print_diag(
devh_, NULL);
593 if (stream_err != UVC_SUCCESS) {
594 uvc_perror(stream_err,
"uvc_start_streaming");
596 uvc_unref_device(
dev_);
603 rgb_frame_ = uvc_allocate_frame(new_config.width * new_config.height * 3);
615 uvc_unref_device(
dev_);