APM:Libraries
VideoIn.cpp
Go to the documentation of this file.
1 /*
2  This class has been implemented based on
3  yavta -- Yet Another V4L2 Test Application written by:
4  Laurent Pinchart <laurent.pinchart@ideasonboard.com>
5 
6  This program is free software: you can redistribute it and/or modify
7  it under the terms of the GNU General Public License as published by
8  the Free Software Foundation, either version 3 of the License, or
9  (at your option) any later version.
10 
11  This program is distributed in the hope that it will be useful,
12  but WITHOUT ANY WARRANTY; without even the implied warranty of
13  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14  GNU General Public License for more details.
15 
16  You should have received a copy of the GNU General Public License
17  along with this program. If not, see <http://www.gnu.org/licenses/>.
18  */
19 
20 #include <AP_HAL/AP_HAL.h>
21 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP ||\
22  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_MINLURE
23 #include "VideoIn.h"
24 
25 #include <errno.h>
26 #include <fcntl.h>
27 #include <linux/videodev2.h>
28 #include <pthread.h>
29 #include <sched.h>
30 #include <stdio.h>
31 #include <stdlib.h>
32 #include <string.h>
33 #include <sys/ioctl.h>
34 #include <sys/mman.h>
35 #include <sys/select.h>
36 #include <sys/stat.h>
37 #include <sys/time.h>
38 #include <time.h>
39 #include <unistd.h>
40 
41 extern const AP_HAL::HAL& hal;
42 
43 using namespace Linux;
44 
46 {
47  if (!_streaming) {
48  if (!_set_streaming(true)) {
49  AP_HAL::panic("couldn't start streaming\n");
50  return false;
51  }
52  _streaming = true;
53  }
54 
55  return _dequeue_frame(frame);
56 }
57 
59 {
60  _queue_buffer((uint32_t)frame.buf_index);
61 }
62 
63 bool VideoIn::open_device(const char *device_path, uint32_t memtype)
64 {
65  struct v4l2_capability cap;
66  int ret;
67 
68  _fd = -1;
69  _buffers = nullptr;
70  _fd = open(device_path, O_RDWR|O_CLOEXEC);
71  _memtype = memtype;
72  if (_fd < 0) {
73  hal.console->printf("Error opening device %s: %s (%d).\n",
74  device_path,
75  strerror(errno), errno);
76  return false;
77  }
78 
79  memset(&cap, 0, sizeof cap);
80  ret = ioctl(_fd, VIDIOC_QUERYCAP, &cap);
81  if (ret < 0) {
82  hal.console->printf("Error querying caps\n");
83  return false;
84  }
85 
86  if (!(cap.capabilities & V4L2_CAP_VIDEO_CAPTURE)) {
87  hal.console->printf("Error opening device %s: is not a video capture device\n",
88  device_path);
89  close(_fd);
90  _fd = -1;
91  return false;
92  }
93 
94  return true;
95 }
96 
97 bool VideoIn::allocate_buffers(uint32_t nbufs)
98 {
99  struct v4l2_requestbuffers rb;
100  struct v4l2_buffer buf;
101  struct buffer *buffers;
102  unsigned int i;
103  int ret;
104 
105  memset(&rb, 0, sizeof rb);
106  rb.count = nbufs;
107  rb.type = (v4l2_buf_type) V4L2_CAP_VIDEO_CAPTURE;
108  rb.memory = (v4l2_memory) _memtype;
109 
110  ret = ioctl(_fd, VIDIOC_REQBUFS, &rb);
111  if (ret < 0) {
112  printf("Unable to request buffers: %s (%d).\n", strerror(errno), errno);
113  return ret;
114  }
115 
116  buffers = (struct buffer *)calloc(rb.count, sizeof buffers[0]);
117  if (buffers == nullptr) {
118  hal.console->printf("Unable to allocate buffers\n");
119  return false;
120  }
121 
122  for (i=0; i < rb.count; i++) {
123  memset(&buf, 0, sizeof(buf));
124  buf.index = i;
125  buf.type = rb.type;
126  buf.memory = rb.memory;
127  ret = ioctl(_fd, VIDIOC_QUERYBUF, &buf);
128  if (ret < 0) {
129  hal.console->printf("Unable to query buffer %u: %s(%d).\n", i,
130  strerror(errno), errno);
131  return false;
132  }
133 
134  switch (_memtype) {
135  case V4L2_MEMORY_MMAP:
136  buffers[i].mem = mmap(0, buf.length, PROT_READ | PROT_WRITE,
137  MAP_SHARED, _fd, buf.m.offset);
138  if (buffers[i].mem == MAP_FAILED) {
139  hal.console->printf("Unable to map buffer %u: %s (%d)\n", i,
140  strerror(errno), errno);
141  return false;
142  }
143  buffers[i].size = buf.length;
144  break;
145  case V4L2_MEMORY_USERPTR:
146  ret = posix_memalign(&buffers[i].mem, getpagesize(), buf.length);
147  if (ret < 0) {
148  hal.console->printf("Unable to allocate buffer %u (%d)\n", i,
149  ret);
150  return false;
151  }
152  buffers[i].size = buf.length;
153  break;
154  default:
155  return false;
156  }
157  }
158  _nbufs = rb.count;
159  _buffers = buffers;
160  return true;
161 }
162 
163 void VideoIn::get_pixel_formats(std::vector<uint32_t> *formats)
164 {
165  struct v4l2_fmtdesc fmtdesc;
166 
167  memset(&fmtdesc, 0, sizeof fmtdesc);
168 
169  fmtdesc.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
170 
171  while (ioctl(_fd, VIDIOC_ENUM_FMT, &fmtdesc) == 0) {
172  formats->insert(formats->begin(), fmtdesc.pixelformat);
173  fmtdesc.index++;
174  }
175 }
176 
177 bool VideoIn::set_format(uint32_t *width, uint32_t *height, uint32_t *format,
178  uint32_t *bytesperline, uint32_t *sizeimage)
179 {
180  struct v4l2_format fmt;
181  int ret;
182 
183  memset(&fmt, 0, sizeof fmt);
184  fmt.type = (v4l2_buf_type) V4L2_CAP_VIDEO_CAPTURE;
185  fmt.fmt.pix.width = *width;
186  fmt.fmt.pix.height = *height;
187  fmt.fmt.pix.pixelformat = *format;
188  fmt.fmt.pix.colorspace = V4L2_COLORSPACE_REC709;
189 
190  ret = ioctl(_fd, VIDIOC_S_FMT, &fmt);
191  if (ret < 0) {
192  hal.console->printf("VideoIn: unable to set format: %s (%d).\n",
193  strerror(errno), errno);
194  return false;
195  }
196 
197  /* warn if format different from the one that was supposed
198  * to be set
199  */
200  if ((fmt.fmt.pix.pixelformat != *format) ||
201  (fmt.fmt.pix.width != *width) ||
202  (fmt.fmt.pix.height != *height)) {
203  hal.console->printf("format set to (%08x)"
204  "%ux%u buffer size %u field : %d\n",
205  fmt.fmt.pix.pixelformat, fmt.fmt.pix.width,
206  fmt.fmt.pix.height, fmt.fmt.pix.sizeimage,
207  fmt.fmt.pix.field);
208  }
209 
210  *width = fmt.fmt.pix.width;
211  *height = fmt.fmt.pix.height;
212  *format = fmt.fmt.pix.pixelformat;
213  *bytesperline = fmt.fmt.pix.bytesperline;
214  *sizeimage = fmt.fmt.pix.sizeimage;
215 
216  return true;
217 }
218 
219 bool VideoIn::set_crop(uint32_t left, uint32_t top,
220  uint32_t width, uint32_t height)
221 {
222  struct v4l2_crop crop;
223  int ret;
224 
225  memset(&crop, 0, sizeof crop);
226  crop.c.top = top;
227  crop.c.left = left;
228  crop.c.width = width;
229  crop.c.height = height;
230  crop.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
231 
232  ret = ioctl(_fd, VIDIOC_S_CROP, &crop);
233 
234  if (ret < 0) {
235  hal.console->printf("VideoIn: unable to set crop: %s (%d).\n",
236  strerror(errno), errno);
237  return false;
238  }
239 
240  return true;
241 }
242 
244 {
245  unsigned int i;
246 
247  /* Queue the buffers. */
248  for (i = 0; i < _nbufs; ++i) {
249  _queue_buffer(i);
250  }
251 }
252 
253 void VideoIn::shrink_8bpp(uint8_t *buffer, uint8_t *new_buffer,
254  uint32_t width, uint32_t height, uint32_t left,
255  uint32_t selection_width, uint32_t top,
256  uint32_t selection_height, uint32_t fx, uint32_t fy)
257 {
258  uint32_t i, j, k, kk, px, block_x, block_y, block_position;
259  uint32_t out_width = selection_width / fx;
260  uint32_t out_height = selection_height / fy;
261  uint32_t width_per_fy = width * fy;
262  uint32_t fx_fy = fx * fy;
263  uint32_t width_sum, out_width_sum = 0;
264 
265  /* selection offset */
266  block_y = top * width;
267  block_position = left + block_y;
268 
269  for (i = 0; i < out_height; i++) {
270  block_x = left;
271  for (j = 0; j < out_width; j++) {
272  px = 0;
273 
274  width_sum = 0;
275  for(k = 0; k < fy; k++) {
276  for(kk = 0; kk < fx; kk++) {
277  px += buffer[block_position + kk + width_sum];
278  }
279  width_sum += width;
280  }
281 
282  new_buffer[j + out_width_sum] = px / (fx_fy);
283 
284  block_x += fx;
285  block_position = block_x + block_y;
286  }
287  block_y += width_per_fy;
288  out_width_sum += out_width;
289  }
290 }
291 
292 void VideoIn::crop_8bpp(uint8_t *buffer, uint8_t *new_buffer,
293  uint32_t width, uint32_t left, uint32_t crop_width,
294  uint32_t top, uint32_t crop_height)
295 {
296  uint32_t crop_x = left + crop_width;
297  uint32_t crop_y = top + crop_height;
298  uint32_t buffer_index = top * width;
299  uint32_t new_buffer_index = 0;
300 
301  for (uint32_t j = top; j < crop_y; j++) {
302  for (uint32_t i = left; i < crop_x; i++) {
303  new_buffer[i - left + new_buffer_index] = buffer[i + buffer_index];
304  }
305  buffer_index += width;
306  new_buffer_index += crop_width;
307  }
308 }
309 
310 void VideoIn::yuyv_to_grey(uint8_t *buffer, uint32_t buffer_size,
311  uint8_t *new_buffer)
312 {
313  uint32_t new_buffer_position = 0;
314 
315  for (uint32_t i = 0; i < buffer_size; i += 2) {
316  new_buffer[new_buffer_position] = buffer[i];
317  new_buffer_position++;
318  }
319 }
320 
321 uint32_t VideoIn::_timeval_to_us(struct timeval& tv)
322 {
323  return (1.0e6 * tv.tv_sec + tv.tv_usec);
324 }
325 
326 void VideoIn::_queue_buffer(int index)
327 {
328  int ret;
329  struct v4l2_buffer buf;
330 
331  memset(&buf, 0, sizeof buf);
332  buf.index = index;
333  buf.type = (v4l2_buf_type) V4L2_CAP_VIDEO_CAPTURE;
334  buf.memory = (v4l2_memory) _memtype;
335  buf.length = _buffers[index].size;
336  if (_memtype == V4L2_MEMORY_USERPTR) {
337  buf.m.userptr = (unsigned long) _buffers[index].mem;
338  }
339 
340  ret = ioctl(_fd, VIDIOC_QBUF, &buf);
341  if (ret < 0) {
342  hal.console->printf("Unable to queue buffer : %s (%d).\n",
343  strerror(errno), errno);
344  }
345 }
346 
347 bool VideoIn::_set_streaming(bool enable)
348 {
349  int type = V4L2_CAP_VIDEO_CAPTURE;
350  int ret;
351 
352  ret = ioctl(_fd, enable ? VIDIOC_STREAMON : VIDIOC_STREAMOFF, &type);
353  if (ret < 0) {
354  printf("Unable to %s streaming: %s (%d).\n",
355  enable ? "start" : "stop", strerror(errno), errno);
356  return false;
357  }
358 
359  return true;
360 }
361 
363 {
364  struct v4l2_buffer buf;
365  int ret;
366 
367  /* Dequeue a buffer. */
368  memset(&buf, 0, sizeof buf);
369  buf.type = (v4l2_buf_type) V4L2_CAP_VIDEO_CAPTURE;
370  buf.memory = (v4l2_memory) _memtype;
371  ret = ioctl(_fd, VIDIOC_DQBUF, &buf);
372  if (ret < 0) {
373  if (errno != EIO) {
374  hal.console->printf("Unable to dequeue buffer: %s (%d).\n",
375  strerror(errno), errno);
376  return false;
377  }
378  buf.type = (v4l2_buf_type) V4L2_CAP_VIDEO_CAPTURE;
379  buf.memory = (v4l2_memory) _memtype;
380  if (_memtype == V4L2_MEMORY_USERPTR) {
381  buf.m.userptr = (unsigned long)_buffers[buf.index].mem;
382  }
383  }
384 
385  frame.data = _buffers[buf.index].mem;
386  frame.buf_index = buf.index;
387  frame.timestamp = _timeval_to_us(buf.timestamp);
388  frame.sequence = buf.sequence;
389 
390  return true;
391 }
392 
393 #endif
int printf(const char *fmt,...)
Definition: stdio.c:113
uint32_t timestamp
Definition: VideoIn.h:36
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
Definition: posix.c:885
struct buffer * _buffers
Definition: VideoIn.h:75
static void shrink_8bpp(uint8_t *buffer, uint8_t *new_buffer, uint32_t width, uint32_t height, uint32_t left, uint32_t selection_width, uint32_t top, uint32_t selection_height, uint32_t fx, uint32_t fy)
Definition: VideoIn.cpp:253
AP_HAL::UARTDriver * console
Definition: HAL.h:110
char * strerror(int errnum)
POSIX strerror() - convert POSIX errno to text with user message.
Definition: posix.c:1852
bool set_crop(uint32_t left, uint32_t top, uint32_t width, uint32_t height)
Definition: VideoIn.cpp:219
static void yuyv_to_grey(uint8_t *buffer, uint32_t buffer_size, uint8_t *new_buffer)
Definition: VideoIn.cpp:310
void put_frame(Frame &frame)
Definition: VideoIn.cpp:58
void * calloc(size_t nmemb, size_t size)
Definition: malloc.c:76
unsigned int size
Definition: VideoIn.h:24
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
uint32_t sequence
Definition: VideoIn.h:37
void * mem
Definition: VideoIn.h:25
bool open_device(const char *device_path, uint32_t memtype)
Definition: VideoIn.cpp:63
bool _dequeue_frame(Frame &frame)
Definition: VideoIn.cpp:362
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
void get_pixel_formats(std::vector< uint32_t > *formats)
Definition: VideoIn.cpp:163
bool get_frame(Frame &frame)
Definition: VideoIn.cpp:45
int close(int fileno)
POSIX Close a file with fileno handel.
Definition: posix.c:675
uint32_t _memtype
Definition: VideoIn.h:83
bool allocate_buffers(uint32_t nbufs)
Definition: VideoIn.cpp:97
unsigned int _nbufs
Definition: VideoIn.h:76
uint32_t buf_index
Definition: VideoIn.h:40
void _queue_buffer(int index)
Definition: VideoIn.cpp:326
bool _streaming
Definition: VideoIn.h:77
void prepare_capture()
Definition: VideoIn.cpp:243
static void crop_8bpp(uint8_t *buffer, uint8_t *new_buffer, uint32_t width, uint32_t left, uint32_t crop_width, uint32_t top, uint32_t crop_height)
Definition: VideoIn.cpp:292
bool set_format(uint32_t *width, uint32_t *height, uint32_t *format, uint32_t *bytesperline, uint32_t *sizeimage)
Definition: VideoIn.cpp:177
uint32_t _timeval_to_us(struct timeval &tv)
Definition: VideoIn.cpp:321
int errno
Note: fdevopen assigns stdin,stdout,stderr.
Definition: posix.c:118
bool _set_streaming(bool enable)
Definition: VideoIn.cpp:347
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140