21 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP ||\ 22 CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_MINLURE 27 #include <linux/videodev2.h> 35 #include <sys/select.h> 43 using namespace Linux;
65 struct v4l2_capability cap;
70 _fd =
open(device_path, O_RDWR|O_CLOEXEC);
79 memset(&cap, 0,
sizeof cap);
80 ret = ioctl(
_fd, VIDIOC_QUERYCAP, &cap);
86 if (!(cap.capabilities & V4L2_CAP_VIDEO_CAPTURE)) {
87 hal.
console->
printf(
"Error opening device %s: is not a video capture device\n",
99 struct v4l2_requestbuffers rb;
100 struct v4l2_buffer buf;
105 memset(&rb, 0,
sizeof rb);
107 rb.type = (v4l2_buf_type) V4L2_CAP_VIDEO_CAPTURE;
110 ret = ioctl(
_fd, VIDIOC_REQBUFS, &rb);
116 buffers = (
struct buffer *)
calloc(rb.count,
sizeof buffers[0]);
117 if (buffers ==
nullptr) {
122 for (i=0; i < rb.count; i++) {
123 memset(&buf, 0,
sizeof(buf));
126 buf.memory = rb.memory;
127 ret = ioctl(
_fd, VIDIOC_QUERYBUF, &buf);
129 hal.
console->
printf(
"Unable to query buffer %u: %s(%d).\n", i,
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) {
143 buffers[i].
size = buf.length;
145 case V4L2_MEMORY_USERPTR:
146 ret = posix_memalign(&buffers[i].mem, getpagesize(), buf.length);
148 hal.
console->
printf(
"Unable to allocate buffer %u (%d)\n", i,
152 buffers[i].
size = buf.length;
165 struct v4l2_fmtdesc fmtdesc;
167 memset(&fmtdesc, 0,
sizeof fmtdesc);
169 fmtdesc.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
171 while (ioctl(
_fd, VIDIOC_ENUM_FMT, &fmtdesc) == 0) {
172 formats->insert(formats->begin(), fmtdesc.pixelformat);
178 uint32_t *bytesperline, uint32_t *sizeimage)
180 struct v4l2_format fmt;
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;
190 ret = ioctl(
_fd, VIDIOC_S_FMT, &fmt);
192 hal.
console->
printf(
"VideoIn: unable to set format: %s (%d).\n",
200 if ((fmt.fmt.pix.pixelformat != *format) ||
201 (fmt.fmt.pix.width != *width) ||
202 (fmt.fmt.pix.height != *height)) {
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,
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;
220 uint32_t width, uint32_t height)
222 struct v4l2_crop crop;
225 memset(&crop, 0,
sizeof crop);
228 crop.c.width = width;
229 crop.c.height = height;
230 crop.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
232 ret = ioctl(
_fd, VIDIOC_S_CROP, &crop);
235 hal.
console->
printf(
"VideoIn: unable to set crop: %s (%d).\n",
248 for (i = 0; i <
_nbufs; ++i) {
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)
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;
266 block_y = top * width;
267 block_position = left + block_y;
269 for (i = 0; i < out_height; i++) {
271 for (j = 0; j < out_width; j++) {
275 for(k = 0; k < fy; k++) {
276 for(kk = 0; kk < fx; kk++) {
277 px += buffer[block_position + kk + width_sum];
282 new_buffer[j + out_width_sum] = px / (fx_fy);
285 block_position = block_x + block_y;
287 block_y += width_per_fy;
288 out_width_sum += out_width;
293 uint32_t width, uint32_t left, uint32_t crop_width,
294 uint32_t top, uint32_t crop_height)
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;
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];
305 buffer_index += width;
306 new_buffer_index += crop_width;
313 uint32_t new_buffer_position = 0;
315 for (uint32_t i = 0; i < buffer_size; i += 2) {
316 new_buffer[new_buffer_position] = buffer[i];
317 new_buffer_position++;
323 return (1.0e6 * tv.tv_sec + tv.tv_usec);
329 struct v4l2_buffer buf;
331 memset(&buf, 0,
sizeof buf);
333 buf.type = (v4l2_buf_type) V4L2_CAP_VIDEO_CAPTURE;
334 buf.memory = (v4l2_memory)
_memtype;
336 if (
_memtype == V4L2_MEMORY_USERPTR) {
337 buf.m.userptr = (
unsigned long)
_buffers[index].mem;
340 ret = ioctl(
_fd, VIDIOC_QBUF, &buf);
349 int type = V4L2_CAP_VIDEO_CAPTURE;
352 ret = ioctl(
_fd, enable ? VIDIOC_STREAMON : VIDIOC_STREAMOFF, &type);
354 printf(
"Unable to %s streaming: %s (%d).\n",
364 struct v4l2_buffer buf;
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);
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;
int printf(const char *fmt,...)
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
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)
AP_HAL::UARTDriver * console
char * strerror(int errnum)
POSIX strerror() - convert POSIX errno to text with user message.
bool set_crop(uint32_t left, uint32_t top, uint32_t width, uint32_t height)
static void yuyv_to_grey(uint8_t *buffer, uint32_t buffer_size, uint8_t *new_buffer)
void put_frame(Frame &frame)
void * calloc(size_t nmemb, size_t size)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
bool open_device(const char *device_path, uint32_t memtype)
bool _dequeue_frame(Frame &frame)
virtual void printf(const char *,...) FMT_PRINTF(2
void get_pixel_formats(std::vector< uint32_t > *formats)
bool get_frame(Frame &frame)
int close(int fileno)
POSIX Close a file with fileno handel.
bool allocate_buffers(uint32_t nbufs)
void _queue_buffer(int index)
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)
bool set_format(uint32_t *width, uint32_t *height, uint32_t *format, uint32_t *bytesperline, uint32_t *sizeimage)
uint32_t _timeval_to_us(struct timeval &tv)
int errno
Note: fdevopen assigns stdin,stdout,stderr.
bool _set_streaming(bool enable)
void panic(const char *errormsg,...) FMT_PRINTF(1