mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-01 03:04:04 -04:00
62 lines
2.2 KiB
Plaintext
62 lines
2.2 KiB
Plaintext
# Parrot Bebop multirotor
|
|
|
|
define HAL_BOARD_LOG_DIRECTORY "/data/ftp/internal_000/ardupilot/logs"
|
|
define HAL_BOARD_TERRAIN_DIRECTORY "/data/ftp/internal_000/ardupilot/terrain"
|
|
define HAL_BOARD_STORAGE_DIRECTORY "/data/ftp/internal_000/ardupilot"
|
|
|
|
# Heater support
|
|
define HAL_HAVE_IMU_HEATER 1
|
|
define HAL_IMU_TEMP_DEFAULT 55
|
|
define HAL_UTILS_HEAT HAL_LINUX_HEAT_PWM
|
|
define HAL_LINUX_HEAT_PWM_NUM 6
|
|
define HAL_LINUX_HEAT_KP 20000
|
|
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
|
|
|
|
# in-built optical flow support:
|
|
define OPTICAL_FLOW_TYPE_DEFAULT Type::BEBOP
|
|
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
|
|
|
|
define HAL_PARAM_DEFAULTS_PATH "/data/ftp/internal_000/ardupilot/bebop.parm"
|
|
|
|
define HAL_RCOUT_BEBOP_BLDC_I2C_BUS 1
|
|
define HAL_RCOUT_BEBOP_BLDC_I2C_ADDR 0x08
|
|
|
|
# focal length 2.21mm pixel size 3.6 um, 2x binning in each direction
|
|
# 240x240 crop rescaled to 64x64
|
|
define HAL_FLOW_PX4_FOCAL_LENGTH_MILLIPX (2.21 / (3.6 * 2.0 * 240 / 64))
|
|
|
|
define HAL_RANGEFINDER_LIGHTWARE_I2C_BUS 0
|
|
|
|
define AP_BATTERY_BEBOP_ENABLED AP_BATTERY_BACKEND_DEFAULT_ENABLED
|
|
define HAL_BATT_MONITOR_DEFAULT AP_BattMonitor::Type::BEBOP
|
|
|
|
# NAME BUS SUBDEV MODE BPW CS_PIN LOWSPD HIGHSPD
|
|
LINUX_SPIDEV "bebop" 1 0 SPI_MODE_0 8 SPI_CS_KERNEL 320*KHZ 320*KHZ
|
|
|
|
define HAL_LINUX_GPIO_BEBOP_ENABLED 1
|
|
|
|
define AP_RANGEFINDER_BEBOP_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED && defined(HAVE_LIBIIO)
|
|
|
|
define MAG_BOARD_ORIENTATION ROTATION_YAW_90
|
|
|
|
define AP_OPTICALFLOW_ONBOARD_ENABLED AP_OPTICALFLOW_BACKEND_DEFAULT_ENABLED
|
|
|
|
# AP_InertialSensor configuration
|
|
define INVENSENSE_EXT_SYNC_ENABLE 1
|