Paparazzi UAS
v5.8.2_stable-0-g6260b7c
Paparazzi is a free software Unmanned Aircraft System.
|
Capture images from a V4L2 device (Video for Linux 2) More...
#include <stdio.h>
#include <string.h>
#include <assert.h>
#include <fcntl.h>
#include <unistd.h>
#include <errno.h>
#include <malloc.h>
#include <sys/mman.h>
#include <sys/ioctl.h>
#include <linux/videodev2.h>
#include <pthread.h>
#include "v4l2.h"
Go to the source code of this file.
Macros | |
#define | CLEAR(x) memset(&(x), 0, sizeof (x)) |
Functions | |
static void * | v4l2_capture_thread (void *data) |
The main capturing thread This thread handles the queue and dequeue of buffers, to make sure only the latest image buffer is preserved for image processing. More... | |
bool_t | v4l2_init_subdev (char *subdev_name, uint8_t pad, uint8_t which, uint16_t code, uint16_t width, uint16_t height) |
Initialize a V4L2 subdevice. More... | |
struct v4l2_device * | v4l2_init (char *device_name, uint16_t width, uint16_t height, uint8_t buffers_cnt, uint32_t _pixelformat) |
Initialize a V4L2(Video for Linux 2) device. More... | |
void | v4l2_image_get (struct v4l2_device *dev, struct image_t *img) |
Get the latest image buffer and lock it (Thread safe, BLOCKING) This functions blocks until image access is granted. More... | |
bool_t | v4l2_image_get_nonblock (struct v4l2_device *dev, struct image_t *img) |
Get the latest image and lock it (Thread safe, NON BLOCKING) This function returns NULL if it can't get access to the current image. More... | |
void | v4l2_image_free (struct v4l2_device *dev, struct image_t *img) |
Free the image and enqueue the buffer (Thread safe) This must be done after processing the image, because else all buffers are locked. More... | |
bool_t | v4l2_start_capture (struct v4l2_device *dev) |
Start capturing images in streaming mode (Thread safe) More... | |
bool_t | v4l2_stop_capture (struct v4l2_device *dev) |
Stop capturing of the image stream (Thread safe) This function is blocking until capturing thread is closed. More... | |
void | v4l2_close (struct v4l2_device *dev) |
Close the V4L2 device (Thread safe) This needs to be preformed to clean up all the buffers and close the device. More... | |
Capture images from a V4L2 device (Video for Linux 2)
Definition in file v4l2.c.
#define CLEAR | ( | x | ) | memset(&(x), 0, sizeof (x)) |
Definition at line 42 of file v4l2.c.
Referenced by v4l2_capture_thread(), v4l2_image_free(), v4l2_init(), v4l2_init_subdev(), and v4l2_start_capture().
|
static |
The main capturing thread This thread handles the queue and dequeue of buffers, to make sure only the latest image buffer is preserved for image processing.
[in] | *data | The Video 4 Linux 2 device pointer |
Definition at line 53 of file v4l2.c.
References v4l2_device::buffers, v4l2_device::buffers_cnt, v4l2_device::buffers_deq_idx, CLEAR, dev, v4l2_device::fd, v4l2_device::mutex, v4l2_device::name, v4l2_device::thread, v4l2_img_buf::timestamp, TRUE, and V4L2_IMG_NONE.
Referenced by v4l2_start_capture().
void v4l2_close | ( | struct v4l2_device * | dev | ) |
Close the V4L2 device (Thread safe) This needs to be preformed to clean up all the buffers and close the device.
Note that this also stops the capturing if it is still capturing.
[in] | *dev | The video for linux device to close(cleanup) |
Definition at line 481 of file v4l2.c.
References v4l2_img_buf::buf, v4l2_device::buffers, v4l2_device::buffers_cnt, v4l2_device::fd, v4l2_img_buf::length, v4l2_device::name, and v4l2_stop_capture().
void v4l2_image_free | ( | struct v4l2_device * | dev, |
struct image_t * | img | ||
) |
Free the image and enqueue the buffer (Thread safe) This must be done after processing the image, because else all buffers are locked.
[in] | *dev | The video for linux device which the image is from |
[in] | *img | The image to free |
Definition at line 366 of file v4l2.c.
References image_t::buf_idx, CLEAR, v4l2_device::fd, and v4l2_device::name.
Referenced by bebop_front_camera_thread(), opticflow_module_calc(), and video_thread_function().
void v4l2_image_get | ( | struct v4l2_device * | dev, |
struct image_t * | img | ||
) |
Get the latest image buffer and lock it (Thread safe, BLOCKING) This functions blocks until image access is granted.
This should not take that long, because it is only locked while enqueueing an image. Make sure you free the image after processing with v4l2_image_free()!
[in] | *dev | The V4L2 video device we want to get an image from |
[out] | *img | The image that we got from the video device |
Definition at line 294 of file v4l2.c.
References v4l2_img_buf::buf, image_t::buf, image_t::buf_idx, image_t::buf_size, v4l2_device::buffers, v4l2_device::buffers_deq_idx, image_t::h, v4l2_device::h, IMAGE_YUV422, v4l2_img_buf::length, v4l2_device::mutex, v4l2_img_buf::timestamp, image_t::ts, image_t::type, V4L2_IMG_NONE, image_t::w, and v4l2_device::w.
Referenced by bebop_front_camera_thread(), opticflow_module_calc(), and video_thread_function().
bool_t v4l2_image_get_nonblock | ( | struct v4l2_device * | dev, |
struct image_t * | img | ||
) |
Get the latest image and lock it (Thread safe, NON BLOCKING) This function returns NULL if it can't get access to the current image.
Make sure you free the image after processing with v4l2_image_free())!
[in] | *dev | The V4L2 video device we want to get an image from |
[out] | *img | The image that we got from the video device |
Definition at line 332 of file v4l2.c.
References v4l2_img_buf::buf, image_t::buf, image_t::buf_idx, image_t::buf_size, v4l2_device::buffers, v4l2_device::buffers_deq_idx, FALSE, image_t::h, v4l2_device::h, IMAGE_YUV422, v4l2_img_buf::length, v4l2_device::mutex, v4l2_img_buf::timestamp, TRUE, image_t::ts, image_t::type, V4L2_IMG_NONE, image_t::w, and v4l2_device::w.
struct v4l2_device* v4l2_init | ( | char * | device_name, |
uint16_t | width, | ||
uint16_t | height, | ||
uint8_t | buffers_cnt, | ||
uint32_t | _pixelformat | ||
) |
Initialize a V4L2(Video for Linux 2) device.
Note that the device must be closed with v4l2_close(dev) at the end.
[in] | device_name | The video device name (like /dev/video1) |
[in] | width,height | The width and height of the images |
[in] | buffers_cnt | The amount of buffers used for mapping |
Definition at line 177 of file v4l2.c.
References v4l2_img_buf::buf, buffers, v4l2_device::buffers, v4l2_device::buffers_cnt, CLEAR, dev, fd, v4l2_device::fd, v4l2_device::h, v4l2_img_buf::length, v4l2_device::name, and v4l2_device::w.
Referenced by bebop_front_camera_init(), opticflow_module_init(), and video_thread_init().
bool_t v4l2_init_subdev | ( | char * | subdev_name, |
uint8_t | pad, | ||
uint8_t | which, | ||
uint16_t | code, | ||
uint16_t | width, | ||
uint16_t | height | ||
) |
Initialize a V4L2 subdevice.
[in] | *subdev_name | The subdevice name (like /dev/v4l-subdev0) |
[in] | pad,which | The way the subdevice should comminicate and be connected to the real device. |
[in] | code | The encoding the subdevice uses (like V4L2_MBUS_FMT_UYVY8_2X8, see the V4L2 manual for available encodings) |
[in] | width,height | The width and height of the images |
Definition at line 130 of file v4l2.c.
References CLEAR, FALSE, fd, and TRUE.
Referenced by bebop_front_camera_init(), opticflow_module_init(), and video_thread_init().
bool_t v4l2_start_capture | ( | struct v4l2_device * | dev | ) |
Start capturing images in streaming mode (Thread safe)
[in] | *dev | The video for linux device to start capturing from |
Definition at line 387 of file v4l2.c.
References v4l2_device::buffers_cnt, v4l2_device::buffers_deq_idx, CLEAR, FALSE, v4l2_device::fd, v4l2_device::name, v4l2_device::thread, TRUE, v4l2_capture_thread(), and V4L2_IMG_NONE.
Referenced by bebop_front_camera_thread(), opticflow_module_calc(), and video_thread_function().
bool_t v4l2_stop_capture | ( | struct v4l2_device * | dev | ) |
Stop capturing of the image stream (Thread safe) This function is blocking until capturing thread is closed.
[in] | *dev | The video for linux device to stop capturing |
Definition at line 446 of file v4l2.c.
References FALSE, v4l2_device::fd, v4l2_device::name, v4l2_device::thread, and TRUE.
Referenced by bebop_front_camera_stop(), opticflow_module_stop(), v4l2_close(), and video_thread_stop().