mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_HAL: Add optical flow params for bebop
Params that are necessary for optical flow
This commit is contained in:
parent
f13cd00e59
commit
eccef24fa7
@ -212,6 +212,23 @@
|
||||
#define HAL_LINUX_HEAT_KI 6
|
||||
#define HAL_LINUX_HEAT_PERIOD_NS 125000
|
||||
#define HAL_LINUX_HEAT_TARGET_TEMP 50
|
||||
#define BEBOP_CAMV_PWM 9
|
||||
#define BEBOP_CAMV_PWM_FREQ 43333333
|
||||
#define HAL_OPTFLOW_ONBOARD_VDEV_PATH "/dev/video0"
|
||||
#define HAL_OPTFLOW_ONBOARD_SUBDEV_PATH "/dev/v4l-subdev0"
|
||||
#define HAL_OPTFLOW_ONBOARD_SENSOR_WIDTH 320
|
||||
#define HAL_OPTFLOW_ONBOARD_SENSOR_HEIGHT 240
|
||||
#define HAL_OPTFLOW_ONBOARD_OUTPUT_WIDTH 64
|
||||
#define HAL_OPTFLOW_ONBOARD_OUTPUT_HEIGHT 64
|
||||
#define HAL_OPTFLOW_ONBOARD_CROP_WIDTH 240
|
||||
#define HAL_OPTFLOW_ONBOARD_CROP_HEIGHT 240
|
||||
#define HAL_OPTFLOW_ONBOARD_NBUFS 8;
|
||||
#define HAL_FLOW_PX4_MAX_FLOW_PIXEL 4
|
||||
#define HAL_FLOW_PX4_BOTTOM_FLOW_FEATURE_THRESHOLD 30
|
||||
#define HAL_FLOW_PX4_BOTTOM_FLOW_VALUE_THRESHOLD 5000
|
||||
/* focal length 3.6 um, 2x binning in each direction
|
||||
* 240x240 crop rescaled to 64x64 */
|
||||
#define HAL_FLOW_PX4_FOCAL_LENGTH_MILLIPX (2.5 / (3.6 * 2.0 * 240 / 64))
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_MINLURE
|
||||
#define HAL_BOARD_LOG_DIRECTORY "/var/APM/logs"
|
||||
#define HAL_BOARD_TERRAIN_DIRECTORY "/var/APM/terrain"
|
||||
|
Loading…
Reference in New Issue
Block a user