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) 49 : nh_(nh), priv_nh_(priv_nh),
51 ctx_(NULL), dev_(NULL), devh_(NULL), rgb_frame_(NULL),
53 config_server_(mutex_, priv_nh_),
54 config_changed_(false),
72 err = uvc_init(&
ctx_, NULL);
74 if (err != UVC_SUCCESS) {
75 uvc_perror(err,
"ERROR: uvc_init");
87 boost::recursive_mutex::scoped_lock lock(
mutex_);
103 boost::recursive_mutex::scoped_lock lock(
mutex_);
114 if (new_config.camera_info_url !=
config_.camera_info_url)
118 #define PARAM_INT(name, fn, value) if (new_config.name != config_.name) { \ 120 if (uvc_set_##fn(devh_, val)) { \ 121 ROS_WARN("Unable to set " #name " to %d", val); \ 122 new_config.name = config_.name; \ 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 134 PARAM_INT(iris_absolute, iris_abs, new_config.iris_absolute);
135 PARAM_INT(brightness, brightness, new_config.brightness);
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;
165 ros::Time timestamp =
ros::Time(frame->capture_time.tv_sec, frame->capture_time.tv_usec * 1000);
170 boost::recursive_mutex::scoped_lock lock(
mutex_);
175 sensor_msgs::Image::Ptr image(
new sensor_msgs::Image());
177 image->height =
config_.height;
178 image->step = image->width * 3;
179 image->data.resize(image->step * image->height);
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");
193 image->encoding =
"bgr8";
195 }
else if (frame->frame_format == UVC_FRAME_FORMAT_GRAY8) {
196 image->encoding =
"8UC1";
197 image->step = image->width;
198 image->data.resize(image->step * image->height);
199 memcpy(&(image->data[0]), frame->data, frame->data_bytes);
200 }
else if (frame->frame_format == UVC_FRAME_FORMAT_GRAY16) {
201 image->encoding =
"16UC1";
202 image->step = image->width*2;
203 image->data.resize(image->step * image->height);
204 memcpy(&(image->data[0]), frame->data, frame->data_bytes);
205 }
else if (frame->frame_format == UVC_FRAME_FORMAT_YUYV) {
207 uvc_error_t conv_ret = uvc_yuyv2bgr(frame,
rgb_frame_);
208 if (conv_ret != UVC_SUCCESS) {
209 uvc_perror(conv_ret,
"Couldn't convert frame to RGB");
212 image->encoding =
"bgr8";
214 #if libuvc_VERSION > 00005 215 }
else if (frame->frame_format == UVC_FRAME_FORMAT_MJPEG) {
218 uvc_error_t conv_ret = uvc_mjpeg2rgb(frame,
rgb_frame_);
219 if (conv_ret != UVC_SUCCESS) {
220 uvc_perror(conv_ret,
"Couldn't convert frame to RGB");
223 image->encoding =
"rgb8";
227 uvc_error_t conv_ret = uvc_any2bgr(frame,
rgb_frame_);
228 if (conv_ret != UVC_SUCCESS) {
229 uvc_perror(conv_ret,
"Couldn't convert frame to RGB");
232 image->encoding =
"bgr8";
237 sensor_msgs::CameraInfo::Ptr cinfo(
240 image->header.frame_id =
config_.frame_id;
241 image->header.stamp = timestamp;
242 cinfo->header.frame_id =
config_.frame_id;
243 cinfo->header.stamp = timestamp;
260 enum uvc_status_class status_class,
263 enum uvc_status_attribute status_attribute,
264 void *data,
size_t data_len) {
265 boost::recursive_mutex::scoped_lock lock(
mutex_);
267 printf(
"Controls callback. class: %d, event: %d, selector: %d, attr: %d, data_len: %zu\n",
268 status_class, event, selector, status_attribute, data_len);
270 if (status_attribute == UVC_STATUS_ATTRIBUTE_VALUE_CHANGE) {
271 switch (status_class) {
272 case UVC_STATUS_CLASS_CONTROL_CAMERA: {
274 case UVC_CT_EXPOSURE_TIME_ABSOLUTE_CONTROL:
275 uint8_t *data_char = (uint8_t*) data;
276 uint32_t exposure_int = ((data_char[0]) | (data_char[1] << 8) |
277 (data_char[2] << 16) | (data_char[3] << 24));
278 config_.exposure_absolute = exposure_int * 0.0001;
284 case UVC_STATUS_CLASS_CONTROL_PROCESSING: {
286 case UVC_PU_WHITE_BALANCE_TEMPERATURE_CONTROL:
287 uint8_t *data_char = (uint8_t*) data;
288 config_.white_balance_temperature =
289 data_char[0] | (data_char[1] << 8);
302 enum uvc_status_class status_class,
305 enum uvc_status_attribute status_attribute,
306 void *data,
size_t data_len,
311 status_attribute, data, data_len);
315 if(vmode ==
"uncompressed") {
316 return UVC_COLOR_FORMAT_UNCOMPRESSED;
317 }
else if (vmode ==
"compressed") {
318 return UVC_COLOR_FORMAT_COMPRESSED;
319 }
else if (vmode ==
"yuyv") {
320 return UVC_COLOR_FORMAT_YUYV;
321 }
else if (vmode ==
"uyvy") {
322 return UVC_COLOR_FORMAT_UYVY;
323 }
else if (vmode ==
"rgb") {
324 return UVC_COLOR_FORMAT_RGB;
325 }
else if (vmode ==
"bgr") {
326 return UVC_COLOR_FORMAT_BGR;
327 }
else if (vmode ==
"mjpeg") {
328 return UVC_COLOR_FORMAT_MJPEG;
329 }
else if (vmode ==
"gray8") {
330 return UVC_COLOR_FORMAT_GRAY8;
331 }
else if (vmode ==
"gray16") {
332 return UVC_COLOR_FORMAT_GRAY16;
336 return UVC_COLOR_FORMAT_UNCOMPRESSED;
343 int vendor_id = strtol(new_config.vendor.c_str(), NULL, 0);
344 int product_id = strtol(new_config.product.c_str(), NULL, 0);
346 ROS_INFO(
"Opening camera with vendor=0x%x, product=0x%x, serial=\"%s\", index=%d",
347 vendor_id, product_id, new_config.serial.c_str(), new_config.index);
353 #if libuvc_VERSION > 00005 354 uvc_error_t find_err = uvc_find_devices(
358 new_config.serial.empty() ? NULL : new_config.serial.c_str());
360 if (find_err != UVC_SUCCESS) {
361 uvc_perror(find_err,
"uvc_find_device");
368 while (devs[dev_idx] != NULL) {
369 if(dev_idx == new_config.index) {
370 dev_ = devs[dev_idx];
373 uvc_unref_device(devs[dev_idx]);
380 ROS_ERROR(
"Unable to find device at index %d", new_config.index);
384 uvc_error_t find_err = uvc_find_device(
388 new_config.serial.empty() ? NULL : new_config.serial.c_str());
390 if (find_err != UVC_SUCCESS) {
391 uvc_perror(find_err,
"uvc_find_device");
396 uvc_error_t open_err = uvc_open(
dev_, &
devh_);
398 if (open_err != UVC_SUCCESS) {
400 case UVC_ERROR_ACCESS:
402 ROS_ERROR(
"Permission denied opening /dev/bus/usb/%03d/%03d",
403 uvc_get_bus_number(
dev_), uvc_get_device_address(
dev_));
405 ROS_ERROR(
"Permission denied opening device %d on bus %d",
406 uvc_get_device_address(
dev_), uvc_get_bus_number(
dev_));
411 ROS_ERROR(
"Can't open /dev/bus/usb/%03d/%03d: %s (%d)",
412 uvc_get_bus_number(
dev_), uvc_get_device_address(
dev_),
413 uvc_strerror(open_err), open_err);
415 ROS_ERROR(
"Can't open device %d on bus %d: %s (%d)",
416 uvc_get_device_address(
dev_), uvc_get_bus_number(
dev_),
417 uvc_strerror(open_err), open_err);
422 uvc_unref_device(
dev_);
428 uvc_stream_ctrl_t ctrl;
429 uvc_error_t mode_err = uvc_get_stream_ctrl_format_size(
432 new_config.width, new_config.height,
433 new_config.frame_rate);
435 if (mode_err != UVC_SUCCESS) {
436 uvc_perror(mode_err,
"uvc_get_stream_ctrl_format_size");
438 uvc_unref_device(
dev_);
439 ROS_ERROR(
"check video_mode/width/height/frame_rate are available");
440 uvc_print_diag(
devh_, NULL);
446 if (stream_err != UVC_SUCCESS) {
447 uvc_perror(stream_err,
"uvc_start_streaming");
449 uvc_unref_device(
dev_);
456 rgb_frame_ = uvc_allocate_frame(new_config.width * new_config.height * 3);
468 uvc_unref_device(
dev_);
boost::recursive_mutex mutex_
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_
dynamic_reconfigure::Server< UVCCameraConfig > config_server_
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 PARAM_INT(name, fn, value)
#define ROS_WARN_STREAM(args)
void OpenCamera(UVCCameraConfig &new_config)
image_transport::CameraPublisher cam_pub_
camera_info_manager::CameraInfoManager cinfo_manager_
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 const int kReconfigureClose
CameraDriver(ros::NodeHandle nh, ros::NodeHandle priv_nh)
#define ROS_ERROR_STREAM(args)
uvc_device_handle_t * devh_