camera_driver.cpp
Go to the documentation of this file.
1 #include <cstdio>
2 #include <linux/videodev2.h>
3 #include <sstream>
4 #include <string>
5 
7 #include "usb_cam/converters.h"
8 #include "usb_cam/types.h"
9 
10 using namespace usb_cam;
11 
12 /* STATIC DATA INITIALIZERS */
13 /* V4L/HARDWARE */
20 
21 /* FFMPEG */
24 unsigned int AbstractV4LUSBCam::buffers_count = 0; // n_buffers_
25 AVFrame* AbstractV4LUSBCam::avframe_camera = nullptr;
26 AVFrame* AbstractV4LUSBCam::avframe_rgb = nullptr;
27 AVPacket* AbstractV4LUSBCam::avpkt = nullptr;
28 AVCodec* AbstractV4LUSBCam::avcodec = nullptr;
29 AVCodecID AbstractV4LUSBCam::codec_id = AV_CODEC_ID_NONE;
30 AVDictionary* AbstractV4LUSBCam::avoptions = nullptr;
31 AVCodecContext* AbstractV4LUSBCam::avcodec_context = nullptr;
34 struct SwsContext* AbstractV4LUSBCam::video_sws = nullptr;
36 bool AbstractV4LUSBCam::capturing = false;
37 std::vector<capture_format_t> AbstractV4LUSBCam::supported_formats = std::vector<capture_format_t>();
38 
39 /* V4L camera parameters */
41 std::string AbstractV4LUSBCam::video_device_name = "/dev/video0";
42 std::string AbstractV4LUSBCam::io_method_name = "mmap";
43 std::string AbstractV4LUSBCam::pixel_format_name = "uyvy";
44 unsigned int AbstractV4LUSBCam::v4l_pixel_format = V4L2_PIX_FMT_UYVY;
45 std::string AbstractV4LUSBCam::color_format_name = "yuv422p";
49 std::vector<camera_control_t> AbstractV4LUSBCam::controls = std::vector<camera_control_t>();
50 std::set<std::string> AbstractV4LUSBCam::ignore_controls = std::set<std::string>();
51 
52 
54 {
55  // Resolving I/O method name tables
58  {
59  printf("Unknown IO method '%s'\n", io_method_name.c_str());
60  return false;
61  }
64  {
65  printf("Unknown pixel format '%s'\n", pixel_format_name.c_str());
66  return false;
67  }
70  {
71  printf("Unknown color format '%s'\n", color_format_name.c_str());
72  return false;
73  }
75  if(v4l_pixel_format == UINT_MAX)
76  {
77  printf("Error in conversion between FFMPEG and Video4Linux pixel format constant '%s'\n", pixel_format_name.c_str());
78  return false;
79  }
80 
81  /* Initializing decoder */
82  if(!init_decoder())
83  {
84  printf("Unable to initialize FFMPEG decoder\n");
85  return false;
86  }
87  return true;
88 }
89 
91 {
92  // V4L initilaization data
93  struct stat st;
94  struct v4l2_capability cap;
95  struct v4l2_cropcap cropcap;
96  struct v4l2_crop crop;
97  struct v4l2_format fmt;
98  unsigned int min;
99  struct v4l2_streamparm stream_params;
100 
101  /* Creating filesystem handler for streaming device */
102  printf("Opening streaming device %s\n", video_device_name.c_str());
103  if(stat(video_device_name.c_str(), &st) < 0)
104  {
105  printf("Cannot identify device by name '%s' (%i)\n", video_device_name.c_str(), errno);
106  return false;
107  }
108  if(!S_ISCHR(st.st_mode))
109  {
110  printf("'%s' is not a proper V4L device (%i)\n", video_device_name.c_str(), errno);
111  return false;
112  }
113  file_dev = open(video_device_name.c_str(),
114  O_RDWR|O_NONBLOCK,
115  0);
116  if(file_dev < 0)
117  {
118  printf("Cannot create a file handler for V4L device '%s' (%i)\n", video_device_name.c_str(), errno);
119  return false;
120  }
121 
122  /* Initializing V4L capture pipeline */
123  if(usb_cam::util::xioctl(file_dev, static_cast<int>(VIDIOC_QUERYCAP), &cap) < 0)
124  {
125  if(errno == EINVAL)
126  printf("File handler created for V4L-incompatible device '%s' (%i)\n", video_device_name.c_str(), errno);
127  else
128  printf("Cannot query capabilities from V4L device '%s' (%i)\n", video_device_name.c_str(), errno);
129  return false;
130  }
131  if(!(cap.capabilities & V4L2_CAP_VIDEO_CAPTURE))
132  {
133  printf("V4L device '%s' does not support capture mode (%i)\n", video_device_name.c_str(), errno);
134  return false;
135  }
136  switch(io_method)
137  {
138  case IO_METHOD_READ:
139  if(!(cap.capabilities & V4L2_CAP_READWRITE))
140  {
141  printf("Device '%s' does not support '%s' access method (read/write error)\n", video_device_name.c_str(), io_method_name.c_str());
142  return false;
143  }
144  break;
147  if(!(cap.capabilities & V4L2_CAP_STREAMING))
148  {
149  printf("Device '%s' does not support '%s' access method (streaming error)\n", video_device_name.c_str(), io_method_name.c_str());
150  return false;
151  }
152  break;
153  default:
154  printf("Cannot parse access mode for device '%s': '%s', system malfunction expected\n", video_device_name.c_str(), io_method_name.c_str());
155  }
156  /* V4L pipeline tuning */
157  CLEAR(cropcap);
158  cropcap.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
159  if(usb_cam::util::xioctl(file_dev, static_cast<int>(VIDIOC_CROPCAP), &cropcap) == 0)
160  {
161  crop.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
162  crop.c = cropcap.defrect; /* reset to default */
163  if(usb_cam::util::xioctl(file_dev, VIDIOC_S_CROP, &crop) < 0)
164  {
165  if(errno == EINVAL)
166  printf("Video4Linux: CROP mode is not supported\n");
167  else
168  printf("Video4Linux: IOCTL is not supported\n");
169  }
170  }
171  else
172  printf("Video4Linux: internal error occurred, hoping for device fallback\n");
173  CLEAR(fmt);
174  fmt.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
175  fmt.fmt.pix.width = image_width;
176  fmt.fmt.pix.height = image_height;
177  fmt.fmt.pix.pixelformat = v4l_pixel_format;
178  fmt.fmt.pix.field = V4L2_FIELD_INTERLACED;
179  if(usb_cam::util::xioctl(file_dev, static_cast<int>(VIDIOC_S_FMT), &fmt) < 0)
180  {
181  printf("Cannot set pixel format '%s' (%u)\n", pixel_format_name.c_str(), v4l_pixel_format);
182  return false;
183  }
184  // Buggy driver prevention
185  min = fmt.fmt.pix.width * 2;
186  if(fmt.fmt.pix.bytesperline < min)
187  fmt.fmt.pix.bytesperline = min;
188  min = fmt.fmt.pix.bytesperline * fmt.fmt.pix.height;
189  if(fmt.fmt.pix.sizeimage < min)
190  fmt.fmt.pix.sizeimage = min;
191  image_width = fmt.fmt.pix.width;
192  image_height = fmt.fmt.pix.height;
193  CLEAR(stream_params);
194  stream_params.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
195  if(usb_cam::util::xioctl(file_dev, static_cast<int>(VIDIOC_G_PARM), &stream_params) < 0)
196  {
197  printf("Cannot set stream parameters (%i)\n", errno);
198  return false;
199  }
200  if(!stream_params.parm.capture.capability && V4L2_CAP_TIMEPERFRAME)
201  printf("Video4Linux: V4L2_CAP_TIMEPERFRAME not supported\n");
202  // TODO(lucasw) need to get list of valid numerator/denominator pairs
203  // and match closest to what user put in.
204  stream_params.parm.capture.timeperframe.numerator = 1;
205  stream_params.parm.capture.timeperframe.denominator = framerate;
206  if (usb_cam::util::xioctl(file_dev, static_cast<int>(VIDIOC_S_PARM), &stream_params) < 0)
207  printf("Video4Linux: cannot set desired framerate: %i fps (%i)\n", framerate, errno);
208  /* Final frame grabber setup */
209  run_grabber(fmt.fmt.pix.sizeimage);
210 
211  image = reinterpret_cast<camera_image_t *>(calloc(1, sizeof(camera_image_t)));
212 
215  image->bytes_per_pixel = 3; // corrected 11/10/15 (BYTES not BITS per pixel)
216 
218  image->is_new = 0;
219  image->image = reinterpret_cast<char *>(calloc(image->image_size, sizeof(char)));
220  memset(image->image, 0, image->image_size * sizeof(char));
221 
222  return true;
223 }
224 
226 {
227  suspend();
228  release_device();
229  close_handlers();
230 
231  av_packet_free(&avpkt);
232  if(video_sws)
233  sws_freeContext(video_sws);
234  video_sws = nullptr;
235  if(avcodec_context)
236  {
237  avcodec_close(avcodec_context);
238  av_free(avcodec_context);
239  avcodec_context = nullptr;
240  }
241  if(avframe_camera)
242  av_free(avframe_camera);
243  avframe_camera = nullptr;
244  if(avframe_rgb)
245  av_free(avframe_rgb);
246  avframe_rgb = nullptr;
247  if(image)
248  free(image);
249  image = nullptr;
250 }
251 
253 {
254 #if LIBAVCODEC_VERSION_INT < AV_VERSION_INT(58, 9, 100)
255  avcodec_register_all();
256 #endif
257  if(v4l_pixel_format == V4L2_PIX_FMT_MJPEG)
258  {
260  printf("Initializing FFMPEG decoder for MJPEG compression\n");
261  }
262  else if(v4l_pixel_format == V4L2_PIX_FMT_H264)
263  {
264  codec_id = AV_CODEC_ID_H264;
265  printf("Initializing FFMPEG decoder for H.264 compression\n");
266  }
267  else
268  return true;
269  avcodec = const_cast<AVCodec*>(avcodec_find_decoder(codec_id));
270  if(!avcodec)
271  {
272  printf("Cannot find FFMPEG decoder for %s\n", pixel_format_name.c_str());
273  return false;
274  }
275  avcodec_context = avcodec_alloc_context3(avcodec);
276  /* Suppress warnings of the following form:
277  * [swscaler @ 0x############] deprecated pixel format used, make sure you did set range correctly
278  * Or set this to AV_LOG_FATAL to additionally suppress occasional frame errors, e.g.:
279  * [mjpeg @ 0x############] overread 4
280  * [mjpeg @ 0x############] No JPEG data found in image
281  * [ERROR] [##########.##########]: Error while decoding frame.
282  */
283  if(!full_ffmpeg_log)
284  av_log_set_level(AV_LOG_ERROR);
285  else
286  av_log_set_level(AV_LOG_INFO);
287 #if LIBAVCODEC_VERSION_MAJOR < 55
288  avframe_camera = avcodec_alloc_frame();
289  avframe_rgb = avcodec_alloc_frame();
290 #else
291  avframe_camera = av_frame_alloc();
292  avframe_rgb = av_frame_alloc();
293 #endif
294 #if LIBAVCODEC_VERSION_MAJOR < 55
295  avpicture_alloc(reinterpret_cast<AVPicture *>(avframe_rgb),
296  AV_PIX_FMT_RGB24,
297  image_width,
298  image_height);
299 #else
300  /*av_image_alloc(reinterpret_cast<uint8_t **>(avframe_rgb),
301  0,
302  image_width,
303  image_height,
304  AV_PIX_FMT_RGB24,
305  1); */
306  avframe_rgb->format = AV_PIX_FMT_RGB24;
307  avframe_rgb->width = image_width;
308  avframe_rgb->height = image_height;
309  av_frame_get_buffer(avframe_rgb, 1);
310 #endif
311  avcodec_context->codec_id = codec_id;
312  avcodec_context->width = image_width;
313  avcodec_context->height = image_height;
314 #if LIBAVCODEC_VERSION_MAJOR > 52
316  avcodec_context->pix_fmt = AV_PIX_FMT_YUV422P;
317  else
318  avcodec_context->pix_fmt = AV_PIX_FMT_YUV420P;
319  avcodec_context->codec_type = AVMEDIA_TYPE_VIDEO;
320 
321  if(avcodec_context->codec_id == AV_CODEC_ID_MJPEG)
322  {
323  switch(avcodec_context->pix_fmt)
324  {
325  case AV_PIX_FMT_YUVJ420P:
326  avcodec_context->pix_fmt = AV_PIX_FMT_YUV420P;
327  avcodec_context->color_range = AVCOL_RANGE_JPEG;
328  break;
329  case AV_PIX_FMT_YUVJ422P:
330  avcodec_context->pix_fmt = AV_PIX_FMT_YUV422P;
331  avcodec_context->color_range = AVCOL_RANGE_JPEG;
332  break;
333  case AV_PIX_FMT_YUVJ444P:
334  avcodec_context->pix_fmt = AV_PIX_FMT_YUV444P;
335  avcodec_context->color_range = AVCOL_RANGE_JPEG;
336  break;
337  default:
338  break;
339  }
340  }
341 #endif
342 #if LIBAVCODEC_VERSION_MAJOR < 55
344  avframe_camera_size = avpicture_get_size(AV_PIX_FMT_YUV422P, image_width, image_height);
345  else
346  avframe_camera_size = av_image_get_buffer_size(AV_PIX_FMT_YUV420P, image_width, image_height);
347  avframe_rgb_size = avpicture_get_size(AV_PIX_FMT_RGB24, image_width, image_height);
348 #else
350  avframe_camera_size = av_image_get_buffer_size(AV_PIX_FMT_YUV422P, image_width, image_height, 1);
351  else
352  avframe_camera_size = av_image_get_buffer_size(AV_PIX_FMT_YUV420P, image_width, image_height, 1);
353  avframe_rgb_size = av_image_get_buffer_size(AV_PIX_FMT_RGB24, image_width, image_height, 1);
354 #endif
355  if(avcodec_open2(avcodec_context, avcodec, &avoptions) < 0)
356  {
357  printf("Cannot open FFMPEG decoder context\n");
358  return false;
359  }
360  if((v4l_pixel_format == V4L2_PIX_FMT_MJPEG) || (v4l_pixel_format == V4L2_PIX_FMT_H264)) // Setting up format converter between YUV and RGB from libswscale
361  video_sws = sws_getContext(image_width,
362  image_height,
363  avcodec_context->pix_fmt,
364  image_width,
365  image_height,
366  AV_PIX_FMT_RGB24,
367  SWS_FAST_BILINEAR,
368  nullptr,
369  nullptr,
370  nullptr);
371  avpkt = av_packet_alloc();
372  return true;
373 }
374 
376 {
377  if(streaming_status)
378  return false;
379 
380  unsigned int i;
381  enum v4l2_buf_type type;
382 
383  switch(io_method)
384  {
385  case IO_METHOD_READ:
386  printf("Capturing from block device, cancelling memory remap\n");
387  break;
388  case IO_METHOD_MMAP:
389  for (i = 0; i < buffers_count; ++i)
390  {
391  struct v4l2_buffer buf;
392  CLEAR(buf);
393  buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
394  buf.memory = V4L2_MEMORY_MMAP;
395  buf.index = i;
396  if(usb_cam::util::xioctl(file_dev, static_cast<int>(VIDIOC_QBUF), &buf) < 0)
397  {
398  printf("Video4linux: unable to configure stream (%i)\n", errno);
399  return false;
400  }
401  }
402  break;
403  case IO_METHOD_USERPTR:
404  for (i = 0; i < buffers_count; ++i)
405  {
406  struct v4l2_buffer buf;
407  CLEAR(buf);
408  buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
409  buf.memory = V4L2_MEMORY_USERPTR;
410  buf.index = i;
411  buf.m.userptr = reinterpret_cast<uint64_t>(buffers[i].start);
412  buf.length = buffers[i].length;
413  if(usb_cam::util::xioctl(file_dev, static_cast<int>(VIDIOC_QBUF), &buf) < 0)
414  {
415  printf("Video4linux: unable to configure stream (%i)\n", errno);
416  return false;
417  }
418  }
419  break;
420  default:
421  printf("Video4linux: attempt to start stream with unknown I/O method. Dropping request\n");
422  }
423  type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
424  if (usb_cam::util::xioctl(file_dev, VIDIOC_STREAMON, &type) < 0)
425  {
426  printf("Video4linux: unable to start stream (%i)\n", errno);
427  return false;
428  }
429  streaming_status = true;
430  return true;
431 }
432 
434 {
435  if(!streaming_status)
436  return false;
437  enum v4l2_buf_type type;
438  streaming_status = false;
439  switch(io_method)
440  {
441  case IO_METHOD_READ:
442  return true;
443  case IO_METHOD_MMAP:
444  case IO_METHOD_USERPTR:
445  type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
446  if (usb_cam::util::xioctl(file_dev, VIDIOC_STREAMOFF, &type) < 0)
447  {
448  printf("Video4linux: cannot stop the device properly (%i)\n", errno);
449  return false;
450  }
451  return true;
452  default:
453  printf("Attempt to stop streaming over unknown I/O channel\n");
454  return false;
455  }
456 }
457 
459 {
460  unsigned int i;
461  switch(io_method)
462  {
463  case IO_METHOD_READ:
464  free(buffers[0].start);
465  break;
466  case IO_METHOD_MMAP:
467  for (i = 0; i < buffers_count; ++i)
468  {
469  if (munmap(buffers[i].start, buffers[i].length) < 0)
470  printf("Video4linux: unable to deallocate frame buffers\n");
471  }
472  break;
473  case IO_METHOD_USERPTR:
474  for (i = 0; i < buffers_count; ++i)
475  free(buffers[i].start);
476  break;
477  default:
478  printf("Attempt to free buffer for unknown I/O method\n");
479  }
480  free(buffers);
481 }
482 
484 {
485  int res = close(file_dev);
486  file_dev = -1;
487  if(res < 0)
488  printf("Unable to close device handler properly\n");
489 }
490 
492 {
493 }
494 
496 {
497  if((image->width == 0) || (image->height == 0))
498  return nullptr;
499 
500  fd_set fds;
501  struct timeval tv;
502  int r;
503  FD_ZERO(&fds);
504  FD_SET(file_dev, &fds);
505  // Timeout
506  tv.tv_sec = 5;
507  tv.tv_usec = 0;
508  r = select(file_dev + 1, &fds, nullptr, nullptr, &tv);
509  /* if the v4l2_buffer timestamp isn't available use this time, though
510  * it may be 10s of milliseconds after the frame acquisition.
511  * image->stamp = clock->now(); */
512  timespec_get(&image->stamp, TIME_UTC);
513  if(r < 0)
514  {
515  if(errno == EINTR)
516  return nullptr;
517  printf("Video4linux: frame mapping operation failed (%i)\n", errno);
518  }
519  else if(r == 0)
520  {
521  printf("Video4linux: frame mapping timeout (%i)\n", errno);
522  return nullptr;
523  }
524 
525  // Reading the actual frame
526  struct v4l2_buffer buf;
527  unsigned int i;
528  int len;
529  struct timespec stamp;
530  int64_t buffer_time_us;
531  switch(io_method)
532  {
533  case IO_METHOD_READ:
534  len = read(file_dev, buffers[0].start, buffers[0].length);
535  if(len < 0)
536  {
537  if(errno == EAGAIN)
538  return nullptr;
539  else if(errno == EIO){}
540  else
541  {
542  printf("Block device read failure (%i)\n", errno);
543  return nullptr;
544  }
545  }
546  // Process image
547  break;
548  case IO_METHOD_MMAP:
549  CLEAR(buf);
550  buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
551  buf.memory = V4L2_MEMORY_MMAP;
552  if (usb_cam::util::xioctl(file_dev, static_cast<int>(VIDIOC_DQBUF), &buf) < 0)
553  {
554  if(errno == EAGAIN)
555  return nullptr;
556  else if(errno == EIO){}
557  else
558  {
559  printf("Memory mapping failure (%i)\n", errno);
560  return nullptr;
561  }
562  }
564  timespec_get(&image->stamp, TIME_UTC);
565  assert(buf.index < buffers_count);
566  len = buf.bytesused;
567  // Process image
568  if(usb_cam::util::xioctl(file_dev, static_cast<int>(VIDIOC_QBUF), &buf) < 0)
569  {
570  printf("Unable to exchange buffer with driver (%i)\n", errno);
571  return nullptr;
572  }
573  break;
574  case IO_METHOD_USERPTR:
575  CLEAR(buf);
576  buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
577  buf.memory = V4L2_MEMORY_USERPTR;
578  if (usb_cam::util::xioctl(file_dev, static_cast<int>(VIDIOC_DQBUF), &buf) < 0)
579  {
580  if(errno == EAGAIN)
581  return nullptr;
582  else if(errno == EIO){}
583  else
584  {
585  printf("Unable to exchange poiner with driver (%i)\n", errno);
586  return nullptr;
587  }
588  }
590  timespec_get(&image->stamp, TIME_UTC);
591 
592  for(i = 0; i < buffers_count; ++i)
593  if(buf.m.userptr == reinterpret_cast<uint64_t>(buffers[i].start) && buf.length == buffers[i].length)
594  break;
595  assert(i < buffers_count);
596  len = buf.bytesused;
597  // Process image
598  if(usb_cam::util::xioctl(file_dev, static_cast<int>(VIDIOC_QBUF), &buf) < 0)
599  {
600  printf("Unable to exchange buffer with driver (%i)\n", errno);
601  return nullptr;
602  }
603  break;
604  default:
605  printf("Attempt to grab the frame via unknown I/O method (%i)\n", errno);
606  }
607  bool processing_result = false;
609  processing_result = process_image(buffers[0].start, len, image);
610  else if(io_method == IO_METHOD_MMAP)
611  processing_result = process_image(buffers[buf.index].start, len, image);
612  else if(io_method == IO_METHOD_USERPTR)
613  processing_result = process_image(reinterpret_cast<const void *>(buf.m.userptr), len, image);
614  if(!processing_result)
615  {
616  printf("2D processing operation fault\n");
617  return nullptr;
618  }
619 
620  // Setting color table for grayscale image
621  if(monochrome)
622  {
623  image->encoding = "mono8";
624  image->step = image->width;
625  }
626  else
627  {
628  // TODO(lucasw) aren't there other encoding types?
629  image->encoding = "rgb8";
630  image->step = image->width * 3;
631  }
632 
633  image->is_new = 1;
634  return image;
635 }
636 
637 void AbstractV4LUSBCam::run_grabber(unsigned int &buffer_size)
638 {
640  {
641  struct v4l2_requestbuffers req;
642  CLEAR(req);
643  req.count = 4;
644  req.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
645  req.memory = V4L2_MEMORY_MMAP;
646  if(usb_cam::util::xioctl(file_dev, static_cast<int>(VIDIOC_REQBUFS), &req) < 0)
647  {
648  if(errno == EINVAL)
649  printf("Video4Linux: device '%s' does not support memory mapping (%i)\n", video_device_name.c_str(), errno);
650  else
651  printf("Video4Linux: unable to start memory mapping (%i)\n", errno);
652  return;
653  }
654  if(req.count < 2)
655  {
656  printf("Video4Linux: insufficient memory buffers number (%i)\n", req.count);
657  return;
658  }
659  buffers = reinterpret_cast<buffer *>(calloc(req.count, sizeof(*buffers)));
660  if(!buffers)
661  {
662  printf("Out of memory\n");
663  return;
664  }
665  for (buffers_count = 0; buffers_count < req.count; ++buffers_count)
666  {
667  struct v4l2_buffer buf;
668 
669  CLEAR(buf);
670 
671  buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
672  buf.memory = V4L2_MEMORY_MMAP;
673  buf.index = buffers_count;
674 
675  if (usb_cam::util::xioctl(file_dev, static_cast<int>(VIDIOC_QUERYBUF), &buf) < 0)
676  {
677  printf("Video4Linux: unable to query buffer status (%i)\n", errno);
678  return;
679  }
680  buffers[buffers_count].length = buf.length;
681  buffers[buffers_count].start = mmap(NULL,
682  buf.length,
683  PROT_READ | PROT_WRITE,
684  MAP_SHARED, file_dev,
685  buf.m.offset);
686  if (buffers[buffers_count].start == MAP_FAILED)
687  {
688  printf("Video4Linux: unable to allocate memory (%i)\n", errno);
689  return;
690  }
691  }
692  }
693  else if(io_method == IO_METHOD_READ)
694  {
695  buffers = reinterpret_cast<buffer *>(calloc(1, sizeof(*buffers)));
696  if (!buffers)
697  {
698  printf("Out of memory\n");
699  return;
700  }
701  buffers[0].length = buffer_size;
702  buffers[0].start = malloc(buffer_size);
703  if (!buffers[0].start)
704  {
705  printf("Out of memory\n");
706  return;
707  }
708  }
709  else if(io_method == IO_METHOD_USERPTR)
710  {
711  struct v4l2_requestbuffers req;
712  unsigned int page_size;
713  page_size = getpagesize();
714  buffer_size = (buffer_size + page_size - 1) & ~(page_size - 1);
715  CLEAR(req);
716  req.count = 4;
717  req.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
718  req.memory = V4L2_MEMORY_USERPTR;
719  if (usb_cam::util::xioctl(file_dev, static_cast<int>(VIDIOC_REQBUFS), &req) < 0)
720  {
721  if (errno == EINVAL)
722  {
723  printf("Video4Linux: device '%s' does not support USERPTR access mode\n", video_device_name.c_str());
724  return;
725  }
726  else
727  {
728  printf("Video4Linux: device '%s' does not support streaming access\n", video_device_name.c_str());
729  return;
730  }
731  }
732  buffers = reinterpret_cast<buffer *>(calloc(4, sizeof(*buffers)));
733  if (!buffers)
734  {
735  printf("Out of memory\n");
736  return;
737  }
738  for (buffers_count = 0; buffers_count < 4; ++buffers_count)
739  {
740  buffers[buffers_count].length = buffer_size;
741  buffers[buffers_count].start = memalign(page_size, buffer_size);
743  {
744  printf("Out of memory\n");
745  return;
746  }
747  }
748  }
749  else
750  {
751  printf("Cannot parse access mode for device '%s': '%s', system malfunction expected\n", video_device_name.c_str(), io_method_name.c_str());
752  return;
753  }
754 }
755 
756 bool AbstractV4LUSBCam::decode_ffmpeg(const void *src, int len, camera_image_t *dest)
757 {
758  char* MJPEG = const_cast<char *>(reinterpret_cast<const char *>(src));
759  char* RGB = dest->image;
760  static int got_picture = 1;
761  // clear the picture
762  memset(RGB, 0, avframe_rgb_size);
763 #if LIBAVCODEC_VERSION_MAJOR > 52
764  av_init_packet(avpkt);
765  av_packet_from_data(avpkt, reinterpret_cast<unsigned char*>(MJPEG), len);
766  if(avcodec_send_packet(avcodec_context, avpkt) < 0)
767  {
768  printf("FFMPEG: error passing frame to decoder context\n");
769  return false;
770  }
771 #else
772  avcodec_decode_video(avcodec_context, avframe_camera, &got_picture, (uint8_t *) MJPEG, len);
773  if (!got_picture)
774  {
775  printf("FFMPEG: buffer empty: expected picture data\n");
776  return;
777  }
778 #endif
779  if (avcodec_receive_frame(avcodec_context, avframe_camera) < 0)
780  {
781  printf("FFMPEG: error decoding frame\n");
782  return false;
783  }
784  if (!got_picture)
785  {
786  printf("FFMPEG: MJPEG frame data expected, but was not received\n");
787  return false;
788  }
789  int xsize = avcodec_context->width;
790  int ysize = avcodec_context->height;
791 
792 #if LIBAVCODEC_VERSION_MAJOR > 52
793  int pic_size = av_image_get_buffer_size(avcodec_context->pix_fmt, xsize, ysize, 1);
794 #else
795  // TODO(lucasw) avpicture_get_size corrupts the pix_fmt
796  int pic_size = avpicture_get_size(avcodec_context->pix_fmt, xsize, ysize);
797 #endif
798  // int pic_size = av_image_get_buffer_size(avcodec_context_->pix_fmt, xsize, ysize);
799  if (pic_size != avframe_camera_size)
800  {
801  printf("FFMPEG: MJPEG output buffer size mismatch: %i (%i expected)\n", avframe_camera_size, pic_size);
802  return false;
803  }
804  // YUV format conversion to RGB
805  sws_scale(video_sws, avframe_camera->data, avframe_camera->linesize, 0, ysize, avframe_rgb->data, avframe_rgb->linesize);
806 
807 #if LIBAVCODEC_VERSION_MAJOR > 52
808  int size = av_image_copy_to_buffer(
809  reinterpret_cast<uint8_t *>(RGB),
811  avframe_rgb->data,
812  avframe_rgb->linesize,
813  AV_PIX_FMT_RGB24,
814  xsize,
815  ysize,
816  1);
817 #else
818  int size = avpicture_layout(
819  reinterpret_cast<AVPicture *>(avframe_rgb), AV_PIX_FMT_RGB24,
820  xsize, ysize, reinterpret_cast<uint8_t *>(RGB), avframe_rgb_size);
821 #endif
822  if (size != avframe_rgb_size)
823  {
824  printf("FFMPEG: image layout mismatch: %i (%i expected)\n", size, avframe_rgb_size);
825  return false;
826  }
827  return true;
828 }
829 
830 std::vector<capture_format_t> &AbstractV4LUSBCam::get_supported_formats()
831 {
832  supported_formats.clear();
833  struct v4l2_fmtdesc current_format;
834  current_format.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
835  current_format.index = 0;
836  for(current_format.index = 0;
837  usb_cam::util::xioctl(file_dev, static_cast<int>(VIDIOC_ENUM_FMT), &current_format) == 0;
838  current_format.index++)
839  {
840  struct v4l2_frmsizeenum current_size;
841  current_size.index = 0;
842  current_size.pixel_format = current_format.pixelformat;
843 
844  for(current_size.index = 0;
846  file_dev, static_cast<int>(VIDIOC_ENUM_FRAMESIZES), &current_size) == 0;
847  current_size.index++)
848  {
849  struct v4l2_frmivalenum current_interval;
850  current_interval.index = 0;
851  current_interval.pixel_format = current_size.pixel_format;
852  current_interval.width = current_size.discrete.width;
853  current_interval.height = current_size.discrete.height;
854  for(current_interval.index = 0;
856  file_dev, static_cast<int>(VIDIOC_ENUM_FRAMEINTERVALS), &current_interval) == 0;
857  current_interval.index++)
858  {
859  if(current_interval.type == V4L2_FRMIVAL_TYPE_DISCRETE) {
860  capture_format_t capture_format;
861  capture_format.format = current_format;
862  capture_format.size = current_size;
863  capture_format.interval = current_interval;
864  supported_formats.push_back(capture_format);
865  }
866  } // interval loop
867  } // size loop
868  } // fmt loop
869  return supported_formats;
870 }
871 
872 bool AbstractV4LUSBCam::process_image(const void *src, int len, camera_image_t *dest)
873 {
874  bool result = false;
875  if(v4l_pixel_format == V4L2_PIX_FMT_YUYV)
876  {
877  if(monochrome) // actually format V4L2_PIX_FMT_Y16, but usb_cam::utils::xioctl gets unhappy if you don't use the advertised type (yuyv)
878  result = util::converters::MONO102MONO8(const_cast<char *>(reinterpret_cast<const char *>(src)), dest->image, dest->width * dest->height);
879  else
880  result = util::converters::YUYV2RGB(const_cast<char *>(reinterpret_cast<const char *>(src)), dest->image, dest->width * dest->height);
881  }
882  else if(v4l_pixel_format == V4L2_PIX_FMT_UYVY)
883  result = util::converters::UYVY2RGB(const_cast<char *>(reinterpret_cast<const char *>(src)), dest->image, dest->width * dest->height);
884  else if(v4l_pixel_format == V4L2_PIX_FMT_MJPEG || v4l_pixel_format == V4L2_PIX_FMT_H264)
885  result = decode_ffmpeg(src, len, dest); // Internal conversion: condext-dependent
886  else if(v4l_pixel_format == V4L2_PIX_FMT_RGB24 || v4l_pixel_format == V4L2_PIX_FMT_GREY)
887  result = util::converters::COPY2RGB(const_cast<char *>(reinterpret_cast<const char *>(src)), dest->image, dest->width * dest->height);
888  else if(v4l_pixel_format == V4L2_PIX_FMT_YUV420)
889  result = util::converters::YUV4202RGB(const_cast<char *>(reinterpret_cast<const char *>(src)), dest->image, dest->width, dest->height);
890  else if(v4l_pixel_format == V4L2_PIX_FMT_BGR24) // Direct copy for OpenCV
891  {
892  memcpy(dest->image, src, len);
893  result = true;
894  }
895  return result;
896 }
897 
898 bool AbstractV4LUSBCam::set_v4l_parameter(const std::string &param, const std::string &value)
899 {
900  std::stringstream ss;
901  ss << "v4l2-ctl --device=" << video_device_name << " -c " << param << "=" << value << " 2>&1";
902  std::string cmd = ss.str();
903  // printf("%s\n", cmd.c_str());
904  // capture the output
905  std::string output;
906  const int kBufferSize = 256;
907  char buffer[kBufferSize];
908  FILE * stream = popen(cmd.c_str(), "r");
909  if(stream)
910  {
911  while (!feof(stream))
912  {
913  if(fgets(buffer, kBufferSize, stream) != NULL)
914  output.append(buffer);
915  }
916  pclose(stream);
917  // any output should be an error
918  if (output.length() > 0)
919  {
920  printf("Video4linux: error setting camera parameter: '%s'\n", output.c_str());
921  return false;
922  }
923  }
924  else
925  {
926  printf("Video4linux: error running control command: '%s'\n", cmd.c_str());
927  return false;
928  }
929  return true;
930 }
931 
933 {
934  // https://gist.github.com/tugstugi/2627647
935  // https://www.kernel.org/doc/html/v4.8/media/uapi/v4l/extended-controls.html
936  printf("Video4linux: Querying V4L2 driver for available controls (register base 0x%X, 0..99)\n", V4L2_CID_BASE);
937  struct v4l2_queryctrl ctrl;
938  struct v4l2_querymenu menu;
939  memset (&ctrl, 0, sizeof (ctrl));
940  memset (&menu, 0, sizeof (menu));
941  std::vector<std::string> disabled_controls;
942  // std::vector<std::string> ignored_controls;
943  ctrl.id = V4L2_CID_BASE;
944  while(ioctl(file_dev, VIDIOC_QUERYCTRL, &ctrl) == 0)
945  {
946  camera_control_t control;
947  std::stringstream description;
948  if(ctrl.flags & V4L2_CTRL_FLAG_DISABLED)
949  {
950  disabled_controls.push_back(util::converters::v4l_control_name_to_param_name(reinterpret_cast<char*>(ctrl.name)));
951  }
952  else
953  {
954  control.name = util::converters::v4l_control_name_to_param_name(reinterpret_cast<char*>(ctrl.name));
955  control.type = static_cast<v4l2_ctrl_type>(ctrl.type);
956  control.value = std::to_string(ctrl.default_value);
957  description << std::string(reinterpret_cast<char*>(ctrl.name)) << ", min = "
958  << std::to_string(ctrl.minimum) << ", max = "
959  << std::to_string(ctrl.maximum) << ", step = "
960  << std::to_string(ctrl.step) << ", flags = 0x" << std::hex << ctrl.flags << std::dec;
961  if(ctrl.type == V4L2_CTRL_TYPE_MENU)
962  {
963  menu.id = ctrl.id;
964  description << " [ ";
965  for(menu.index = ctrl.minimum; menu.index <= ctrl.maximum; menu.index++)
966  {
967  if(ioctl(file_dev, VIDIOC_QUERYMENU, &menu) == 0)
968  description << menu.index << ": " << std::string(reinterpret_cast<char*>(menu.name)) << " ";
969  }
970  description << "]";
971  }
972  control.description = description.str();
973  controls.push_back(control);
974  }
975  //std::cout << util::converters::v4l_control_name_to_param_name(reinterpret_cast<char*>(ctrl.name)) << std::endl;
976 
977  ctrl.id |= V4L2_CTRL_FLAG_NEXT_CTRL;
978  }
979  if(!disabled_controls.empty())
980  {
981  std::cout << "Disabled controls: ";
982  for(auto dc: disabled_controls)
983  std::cout << dc << " ";
984  std::cout << std::endl;
985  }
986  printf("Sorting control names:\n");
987  if(!controls.empty())
988  {
989  for(auto c = controls.begin(); c != controls.end(); c++)
990  {
991  if(c->name.find("auto") != std::string::npos)
992  {
993  camera_control_t tc = (*c);
994  controls.erase(c);
995  controls.insert(controls.begin(), tc);
996  }
997  }
998  }
999  for(auto c: controls)
1000  printf("\t%s\n", c.name.c_str());
1001 }
1002 
1004 {
1005  printf("Video4linux: Setting up auxiliary camera parameters\n");
1006  if(controls.empty())
1007  {
1008  printf("Video4linux: camera controls was not queried properly, please call v4l_query_controls() before!\n");
1009  return;
1010  }
1011  for(auto control: controls)
1012  {
1013  if(ignore_controls.find(control.name) == ignore_controls.end())
1014  if(!set_v4l_parameter(control.name, control.value))
1015  printf("Video4linux: cannot set V4L control %s\n", control.name.c_str());
1016  }
1017  /* REPLACED WITH DYNAMICALLY QUERIED PARAMETERS
1018  // Autofocus
1019  if(autofocus)
1020  {
1021  struct v4l2_queryctrl queryctrl;
1022  struct v4l2_ext_control control;
1023 
1024  memset(&queryctrl, 0, sizeof(queryctrl));
1025  queryctrl.id = V4L2_CID_FOCUS_AUTO;
1026 
1027  if (usb_cam::util::xioctl(file_dev, static_cast<int>(VIDIOC_QUERYCTRL), &queryctrl) < 0)
1028  {
1029  if (errno != EINVAL)
1030  printf("Video4linux: cannot query auxiliary control (FOCUS_AUTO, %i)\n", errno);
1031  else
1032  printf("Video4linux: auto focus not supported (%i)\n", errno);
1033  }
1034  else if (queryctrl.flags & V4L2_CTRL_FLAG_DISABLED)
1035  printf("Video4linux: auto focus not supported (%i)\n", errno);
1036  else
1037  {
1038  memset(&control, 0, sizeof(control));
1039  control.id = V4L2_CID_FOCUS_AUTO;
1040  control.value = 1;
1041 
1042  if (usb_cam::util::xioctl(file_dev, static_cast<int>(VIDIOC_S_CTRL), &control) < 0)
1043  printf("Video4linux: auxiliary control not supported (%i)\n", errno);
1044  }
1045  set_v4l_parameter("focus_auto", 1);
1046  }
1047  else
1048  {
1049  set_v4l_parameter("focus_auto", 0);
1050  if(focus >= 0)
1051  set_v4l_parameter("focus_absolute", focus);
1052  }
1053  // Autoexposure
1054  if(autoexposure)
1055  set_v4l_parameter("exposure_auto", 1);
1056  else
1057  {
1058  set_v4l_parameter("exposure_auto", 0);
1059  set_v4l_parameter("exposure_absolute", exposure);
1060  }
1061  // Auto white balance
1062  if(auto_white_balance)
1063  set_v4l_parameter("white_balance_temperature_auto", 1);
1064  else
1065  {
1066  set_v4l_parameter("white_balance_temperature_auto", 0);
1067  set_v4l_parameter("white_balance_temperature", white_balance);
1068  }
1069  // Brightness
1070  if(brightness >= 0)
1071  set_v4l_parameter("brightness", brightness);
1072  // Contrast
1073  if(contrast >= 0)
1074  set_v4l_parameter("contrast", contrast);
1075  // Saturation
1076  if(saturation >= 0)
1077  set_v4l_parameter("saturation", saturation);
1078  // Sharpness
1079  if(sharpness >= 0)
1080  set_v4l_parameter("sharpness", sharpness);
1081  // Gain
1082  if(gain >= 0)
1083  set_v4l_parameter("gain", gain);
1084  */
1085 }
usb_cam::util::converters::v4l_control_name_to_param_name
std::string v4l_control_name_to_param_name(const char *name)
Definition: converters.cpp:237
usb_cam::AbstractV4LUSBCam::AbstractV4LUSBCam
AbstractV4LUSBCam()
Definition: camera_driver.cpp:491
usb_cam::camera_control_t::type
v4l2_ctrl_type type
Definition: types.h:134
usb_cam::AbstractV4LUSBCam::set_v4l_parameter
static bool set_v4l_parameter(const std::string &param, const std::string &value)
Definition: camera_driver.cpp:898
usb_cam::camera_image_t::step
uint32_t step
Definition: types.h:116
usb_cam::camera_image_t::encoding
std::string encoding
Definition: types.h:117
usb_cam::AbstractV4LUSBCam::supported_formats
static std::vector< capture_format_t > supported_formats
Definition: camera_driver.h:67
usb_cam::AbstractV4LUSBCam::full_ffmpeg_log
static bool full_ffmpeg_log
Definition: camera_driver.h:51
usb_cam::util::calc_img_timestamp
timespec calc_img_timestamp(const timeval &buffer_time, const time_t &epoch_time_shift_us)
Calculate image timestamp from buffer time and epoch time shift. In this, the buffer time is first co...
Definition: util.cpp:23
usb_cam::AbstractV4LUSBCam::monochrome
static bool monochrome
Definition: camera_driver.h:46
usb_cam::AbstractV4LUSBCam::color_format
static color_format_t color_format
Definition: camera_driver.h:45
types.h
usb_cam::AbstractV4LUSBCam::v4l_query_controls
static void v4l_query_controls()
Definition: camera_driver.cpp:932
usb_cam
Definition: camera_driver.h:35
usb_cam::IO_METHOD_READ
@ IO_METHOD_READ
Definition: types.h:76
usb_cam::camera_image_t::image_size
int image_size
Definition: types.h:119
usb_cam::camera_control_t::name
std::string name
Definition: types.h:135
usb_cam::AbstractV4LUSBCam::run_grabber
static void run_grabber(unsigned int &buffer_size)
Definition: camera_driver.cpp:637
usb_cam::AbstractV4LUSBCam::buffers
static buffer * buffers
Definition: camera_driver.h:52
usb_cam::AbstractV4LUSBCam::avframe_rgb
static AVFrame * avframe_rgb
Definition: camera_driver.h:55
usb_cam::AbstractV4LUSBCam::avpkt
static AVPacket * avpkt
Definition: camera_driver.h:56
usb_cam::util::converters::UYVY2RGB
bool UYVY2RGB(const char *YUV, char *&RGB, const int &NumPixels)
Definition: converters.cpp:215
usb_cam::AbstractV4LUSBCam::~AbstractV4LUSBCam
virtual ~AbstractV4LUSBCam()
Definition: camera_driver.cpp:225
usb_cam::AbstractV4LUSBCam::buffers_count
static unsigned int buffers_count
Definition: camera_driver.h:53
usb_cam::camera_image_t
Definition: types.h:112
usb_cam::AbstractV4LUSBCam::streaming_status
static bool streaming_status
Definition: camera_driver.h:70
usb_cam::AbstractV4LUSBCam::avframe_rgb_size
static int avframe_rgb_size
Definition: camera_driver.h:62
usb_cam::util::converters::pixel_format_from_string
pixel_format_t pixel_format_from_string(const std::string &str)
Definition: converters.cpp:27
usb_cam::util::converters::YUYV2RGB
bool YUYV2RGB(const char *YUV, char *&RGB, const int &NumPixels)
Definition: converters.cpp:162
usb_cam::AbstractV4LUSBCam::framerate
static int framerate
Definition: camera_driver.h:77
usb_cam::camera_control_t::description
std::string description
Definition: types.h:136
usb_cam::util::converters::io_method_from_string
io_method_t io_method_from_string(const std::string &str)
Definition: converters.cpp:15
usb_cam::camera_image_t::width
uint32_t width
Definition: types.h:114
usb_cam::camera_image_t::stamp
struct timespec stamp
Definition: types.h:120
usb_cam::AbstractV4LUSBCam::image
static camera_image_t * image
Definition: camera_driver.h:65
usb_cam::AbstractV4LUSBCam::io_method_name
static std::string io_method_name
Definition: camera_driver.h:72
usb_cam::AbstractV4LUSBCam::controls
static std::vector< camera_control_t > controls
Definition: camera_driver.h:78
usb_cam::util::get_epoch_time_shift_us
time_t get_epoch_time_shift_us()
Get epoch time shift.
Definition: util.cpp:5
usb_cam::AbstractV4LUSBCam::release_device
static void release_device()
Definition: camera_driver.cpp:458
AV_CODEC_ID_MJPEG
#define AV_CODEC_ID_MJPEG
Definition: camera_driver.h:13
usb_cam::AbstractV4LUSBCam::init_decoder
static bool init_decoder()
Definition: camera_driver.cpp:252
usb_cam::AbstractV4LUSBCam::decode_ffmpeg
static bool decode_ffmpeg(const void *src, int len, camera_image_t *dest)
Definition: camera_driver.cpp:756
usb_cam::AbstractV4LUSBCam::avframe_camera
static AVFrame * avframe_camera
Definition: camera_driver.h:54
usb_cam::AbstractV4LUSBCam::color_format_name
static std::string color_format_name
Definition: camera_driver.h:74
usb_cam::capture_format_t::format
struct v4l2_fmtdesc format
Definition: types.h:127
usb_cam::COLOR_FORMAT_YUV422P
@ COLOR_FORMAT_YUV422P
Definition: types.h:101
usb_cam::capture_format_t::size
struct v4l2_frmsizeenum size
Definition: types.h:128
usb_cam::AbstractV4LUSBCam::avframe_camera_size
static int avframe_camera_size
Definition: camera_driver.h:61
usb_cam::AbstractV4LUSBCam::image_width
static int image_width
Definition: camera_driver.h:75
usb_cam::camera_image_t::image
char * image
Definition: types.h:121
usb_cam::util::converters::v4l_pixel_format_from_pixel_format
unsigned int v4l_pixel_format_from_pixel_format(const pixel_format_t &pixelformat, bool &mono)
Definition: converters.cpp:90
usb_cam::buffer::length
std::size_t length
Definition: types.h:109
usb_cam::AbstractV4LUSBCam::pixel_format
static pixel_format_t pixel_format
Definition: camera_driver.h:43
usb_cam::AbstractV4LUSBCam::close_handlers
static void close_handlers()
Definition: camera_driver.cpp:483
usb_cam::AbstractV4LUSBCam::io_method
static io_method_t io_method
Definition: camera_driver.h:42
usb_cam::camera_control_t
Definition: types.h:132
usb_cam::camera_image_t::is_new
int is_new
Definition: types.h:122
usb_cam::camera_image_t::height
uint32_t height
Definition: types.h:115
usb_cam::buffer::start
void * start
Definition: types.h:108
CLEAR
#define CLEAR(x)
Definition: util.h:6
camera_driver.h
usb_cam::AbstractV4LUSBCam::get_supported_formats
static std::vector< capture_format_t > & get_supported_formats()
Definition: camera_driver.cpp:830
usb_cam::AbstractV4LUSBCam::suspend
static bool suspend()
Definition: camera_driver.cpp:433
usb_cam::capture_format_t
Definition: types.h:125
usb_cam::util::xioctl
int xioctl(int fd, int request, void *arg)
Definition: util.cpp:36
usb_cam::AbstractV4LUSBCam::start
static bool start()
Definition: camera_driver.cpp:90
usb_cam::AbstractV4LUSBCam::epoch_time_shift_us
static const time_t epoch_time_shift_us
Definition: camera_driver.h:48
usb_cam::color_format_t
color_format_t
Definition: types.h:98
usb_cam::AbstractV4LUSBCam::image_height
static int image_height
Definition: camera_driver.h:76
usb_cam::AbstractV4LUSBCam::adjust_camera
static void adjust_camera()
Definition: camera_driver.cpp:1003
usb_cam::util::converters::MONO102MONO8
bool MONO102MONO8(const char *RAW, char *&MONO, const int &NumPixels)
Definition: converters.cpp:151
usb_cam::capture_format_t::interval
struct v4l2_frmivalenum interval
Definition: types.h:129
usb_cam::buffer
Definition: types.h:106
usb_cam::util::converters::YUV4202RGB
bool YUV4202RGB(char *YUV, char *&RGB, const int &width, const int &height)
Definition: converters.cpp:192
usb_cam::AbstractV4LUSBCam::video_device_name
static std::string video_device_name
Definition: camera_driver.h:71
usb_cam::util::converters::color_format_from_string
color_format_t color_format_from_string(const std::string &str)
Definition: converters.cpp:79
usb_cam::pixel_format_t
pixel_format_t
Definition: types.h:83
usb_cam::util::converters::COPY2RGB
bool COPY2RGB(const char *input, char *&output, const int &NumPixels)
Definition: converters.cpp:186
usb_cam::AbstractV4LUSBCam::start_capture
static bool start_capture()
Definition: camera_driver.cpp:375
usb_cam::IO_METHOD_MMAP
@ IO_METHOD_MMAP
Definition: types.h:77
usb_cam::AbstractV4LUSBCam::v4l_pixel_format
static unsigned int v4l_pixel_format
Definition: camera_driver.h:44
usb_cam::io_method_t
io_method_t
Definition: types.h:74
param
T param(const std::string &param_name, const T &default_val)
usb_cam::AbstractV4LUSBCam::init
static bool init()
Definition: camera_driver.cpp:53
usb_cam::AbstractV4LUSBCam::ignore_controls
static std::set< std::string > ignore_controls
Definition: camera_driver.h:79
usb_cam::AbstractV4LUSBCam::avoptions
static AVDictionary * avoptions
Definition: camera_driver.h:59
usb_cam::camera_control_t::value
std::string value
Definition: types.h:137
usb_cam::COLOR_FORMAT_UNKNOWN
@ COLOR_FORMAT_UNKNOWN
Definition: types.h:102
converters.h
usb_cam::IO_METHOD_USERPTR
@ IO_METHOD_USERPTR
Definition: types.h:78
usb_cam::AbstractV4LUSBCam::avcodec
static AVCodec * avcodec
Definition: camera_driver.h:57
cmd
string cmd
usb_cam::AbstractV4LUSBCam::pixel_format_name
static std::string pixel_format_name
Definition: camera_driver.h:73
usb_cam::camera_image_t::bytes_per_pixel
int bytes_per_pixel
Definition: types.h:118
usb_cam::AbstractV4LUSBCam::video_sws
static struct SwsContext * video_sws
Definition: camera_driver.h:63
usb_cam::AbstractV4LUSBCam::file_dev
static int file_dev
Definition: camera_driver.h:47
usb_cam::IO_METHOD_UNKNOWN
@ IO_METHOD_UNKNOWN
Definition: types.h:79
usb_cam::AbstractV4LUSBCam::read_frame
static camera_image_t * read_frame()
Definition: camera_driver.cpp:495
usb_cam::AbstractV4LUSBCam::codec_id
static AVCodecID codec_id
Definition: camera_driver.h:58
usb_cam::PIXEL_FORMAT_UNKNOWN
@ PIXEL_FORMAT_UNKNOWN
Definition: types.h:94
usb_cam::AbstractV4LUSBCam::process_image
static bool process_image(const void *src, int len, camera_image_t *dest)
Definition: camera_driver.cpp:872
usb_cam::AbstractV4LUSBCam::capturing
static bool capturing
Definition: camera_driver.h:66
usb_cam::AbstractV4LUSBCam::avcodec_context
static AVCodecContext * avcodec_context
Definition: camera_driver.h:60


usb_cam
Author(s): Benjamin Pitzer
autogenerated on Fri Apr 12 2024 02:42:53