17 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP ||\ 18 CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_MINLURE 22 #include <linux/v4l2-mediabus.h> 26 #include <sys/types.h> 36 #define OPTICAL_FLOW_ONBOARD_RTPRIO 11 41 using namespace Linux;
46 uint32_t crop_width, crop_height;
47 uint32_t memtype = V4L2_MEMORY_MMAP;
48 unsigned int nbufs = 0;
51 struct sched_param param = {
60 const char* device_path = HAL_OPTFLOW_ONBOARD_VDEV_PATH;
61 memtype = V4L2_MEMORY_MMAP;
62 nbufs = HAL_OPTFLOW_ONBOARD_NBUFS;
63 _width = HAL_OPTFLOW_ONBOARD_OUTPUT_WIDTH;
64 _height = HAL_OPTFLOW_ONBOARD_OUTPUT_HEIGHT;
65 crop_width = HAL_OPTFLOW_ONBOARD_CROP_WIDTH;
66 crop_height = HAL_OPTFLOW_ONBOARD_CROP_HEIGHT;
69 left = (HAL_OPTFLOW_ONBOARD_SENSOR_WIDTH -
70 HAL_OPTFLOW_ONBOARD_SENSOR_HEIGHT) / 2;
72 if (device_path ==
nullptr ||
78 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP 90 HAL_OPTFLOW_ONBOARD_SENSOR_HEIGHT,
91 V4L2_MBUS_FMT_UYVY8_2X8)) {
92 AP_HAL::panic(
"OpticalFlow_Onboard: couldn't set subdev fmt\n");
95 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_MINLURE 96 std::vector<uint32_t> pixel_formats;
100 for (uint32_t px_fmt : pixel_formats) {
101 if (px_fmt == V4L2_PIX_FMT_NV12 || px_fmt == V4L2_PIX_FMT_GREY) {
108 if (px_fmt == V4L2_PIX_FMT_YUYV) {
116 AP_HAL::panic(
"OpticalFlow_Onboard: couldn't set video format");
119 if (
_format != V4L2_PIX_FMT_NV12 &&
_format != V4L2_PIX_FMT_GREY &&
120 _format != V4L2_PIX_FMT_YUYV) {
121 AP_HAL::panic(
"OpticalFlow_Onboard: format not supported\n");
124 if (
_width == HAL_OPTFLOW_ONBOARD_OUTPUT_WIDTH &&
125 _height == HAL_OPTFLOW_ONBOARD_OUTPUT_HEIGHT) {
136 _width = HAL_OPTFLOW_ONBOARD_OUTPUT_WIDTH;
137 _height = HAL_OPTFLOW_ONBOARD_OUTPUT_HEIGHT;
154 _width = HAL_OPTFLOW_ONBOARD_OUTPUT_WIDTH;
155 _height = HAL_OPTFLOW_ONBOARD_OUTPUT_HEIGHT;
161 AP_HAL::panic(
"OpticalFlow_Onboard: couldn't allocate video buffers");
168 HAL_FLOW_PX4_MAX_FLOW_PIXEL,
169 HAL_FLOW_PX4_BOTTOM_FLOW_FEATURE_THRESHOLD,
170 HAL_FLOW_PX4_BOTTOM_FLOW_VALUE_THRESHOLD);
174 ret = pthread_mutex_init(&
_mutex,
nullptr);
179 ret = pthread_attr_init(&attr);
183 pthread_attr_setinheritsched(&attr, PTHREAD_EXPLICIT_SCHED);
184 pthread_attr_setschedpolicy(&attr, SCHED_FIFO);
185 pthread_attr_setschedparam(&attr, ¶m);
188 AP_HAL::panic(
"OpticalFlow_Onboard: failed to create thread");
200 pthread_mutex_lock(&
_mutex);
219 pthread_mutex_unlock(&
_mutex);
236 sample.
time_us = 1.0e6 * (ts.tv_sec + (ts.tv_nsec*1.0e-9));
244 unsigned int retries = 0;
248 integrated_gyro_at_time.
time_us < timestamp &&
250 gyro = integrated_gyro_at_time;
272 uint32_t convert_buffer_size = 0, output_buffer_size = 0;
273 uint32_t crop_left = 0, crop_top = 0;
274 uint32_t shrink_scale = 0, shrink_width = 0, shrink_height = 0;
275 uint32_t shrink_width_offset = 0, shrink_height_offset = 0;
276 uint8_t *convert_buffer =
nullptr, *output_buffer =
nullptr;
279 if (
_format == V4L2_PIX_FMT_YUYV) {
286 convert_buffer = (uint8_t *)
calloc(1, convert_buffer_size);
287 if (!convert_buffer) {
288 AP_HAL::panic(
"OpticalFlow_Onboard: couldn't allocate conversion buffer\n");
293 output_buffer_size = HAL_OPTFLOW_ONBOARD_OUTPUT_WIDTH *
294 HAL_OPTFLOW_ONBOARD_OUTPUT_HEIGHT;
296 output_buffer = (uint8_t *)
calloc(1, output_buffer_size);
297 if (!output_buffer) {
298 if (convert_buffer) {
299 free(convert_buffer);
302 AP_HAL::panic(
"OpticalFlow_Onboard: couldn't allocate crop buffer\n");
309 HAL_OPTFLOW_ONBOARD_OUTPUT_HEIGHT;
312 HAL_OPTFLOW_ONBOARD_OUTPUT_WIDTH;
315 shrink_width = HAL_OPTFLOW_ONBOARD_OUTPUT_WIDTH * shrink_scale;
316 shrink_height = HAL_OPTFLOW_ONBOARD_OUTPUT_HEIGHT * shrink_scale;
322 HAL_OPTFLOW_ONBOARD_OUTPUT_WIDTH / 2;
324 HAL_OPTFLOW_ONBOARD_OUTPUT_HEIGHT / 2;
330 if (convert_buffer) {
331 free(convert_buffer);
341 if (
_format == V4L2_PIX_FMT_YUYV) {
343 convert_buffer_size * 2, convert_buffer);
345 memset(video_frame.
data, 0, convert_buffer_size * 2);
346 memcpy(video_frame.
data, convert_buffer, convert_buffer_size);
354 shrink_width_offset, shrink_width,
355 shrink_height_offset, shrink_height,
356 shrink_scale, shrink_scale);
358 memcpy(video_frame.
data, output_buffer, output_buffer_size);
362 crop_left, HAL_OPTFLOW_ONBOARD_OUTPUT_WIDTH,
363 crop_top, HAL_OPTFLOW_ONBOARD_OUTPUT_HEIGHT);
366 memcpy(video_frame.
data, output_buffer, output_buffer_size);
379 #ifdef OPTICALFLOW_ONBOARD_RECORD_VIDEO 380 int fd =
open(OPTICALFLOW_ONBOARD_VIDEO_FILE, O_CLOEXEC | O_CREAT | O_WRONLY
381 | O_APPEND, S_IRUSR | S_IWUSR | S_IRGRP |
382 S_IWGRP | S_IROTH | S_IWOTH);
385 #ifdef OPTICALFLOW_ONBOARD_RECORD_METADATAS 391 } metas = { video_frame.
timestamp, rate_x, rate_y, rate_z};
392 write(fd, &metas,
sizeof(metas));
402 (uint8_t *)video_frame.
data,
405 &flow_rate.
x, &flow_rate.
y);
408 pthread_mutex_lock(&
_mutex);
410 HAL_FLOW_PX4_FOCAL_LENGTH_MILLIPX;
412 HAL_FLOW_PX4_FOCAL_LENGTH_MILLIPX;
423 pthread_mutex_unlock(&
_mutex);
432 if (convert_buffer) {
433 free(convert_buffer);
bool read(AP_HAL::OpticalFlow::Data_Frame &frame)
void clock_gettime(uint32_t a1, void *a2)
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)
static void * _read_thread(void *arg)
bool set_crop(uint32_t left, uint32_t top, uint32_t width, uint32_t height)
#define OPTICAL_FLOW_ONBOARD_RTPRIO
ssize_t write(int fd, const void *buf, size_t count)
POSIX Write count bytes from *buf to fileno fd.
void _get_integrated_gyros(uint64_t timestamp, GyroSample &gyro)
uint64_t _last_integration_time
ObjectBuffer< GyroSample > * _gyro_ring_buffer
static void yuyv_to_grey(uint8_t *buffer, uint32_t buffer_size, uint8_t *new_buffer)
void put_frame(Frame &frame)
bool set_format(uint32_t width, uint32_t height, uint32_t format)
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 -*-
CameraSensor * _camerasensor
bool open_device(const char *device_path, uint32_t memtype)
void get_pixel_formats(std::vector< uint32_t > *formats)
bool get_frame(Frame &frame)
float pixel_flow_x_integral
int close(int fileno)
POSIX Close a file with fileno handel.
float _pixel_flow_x_integral
bool allocate_buffers(uint32_t nbufs)
void push_gyro_bias(float gyro_bias_x, float gyro_bias_y)
float pixel_flow_y_integral
float _pixel_flow_y_integral
AP_HAL::I2CDeviceManager * i2c_mgr
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)
void push_gyro(float gyro_x, float gyro_y, float dt)
bool set_format(uint32_t *width, uint32_t *height, uint32_t *format, uint32_t *bytesperline, uint32_t *sizeimage)
VideoIn::Frame _last_video_frame
uint32_t _camera_output_width
void panic(const char *errormsg,...) FMT_PRINTF(1
virtual OwnPtr< AP_HAL::I2CDevice > get_device(uint8_t bus, uint8_t address, uint32_t bus_clock=400000, bool use_smbus=false, uint32_t timeout_ms=4)=0
uint32_t _camera_output_height
static const unsigned int OPTICAL_FLOW_GYRO_BUFFER_LEN
Vector2f _integrated_gyro
uint64_t _integration_timespan
uint8_t compute_flow(uint8_t *image1, uint8_t *image2, uint32_t delta_time, float *pixel_flow_x, float *pixel_flow_y)
void set_freq(uint32_t freq)