|
|
|
@ -35,6 +35,7 @@
@@ -35,6 +35,7 @@
|
|
|
|
|
#define HAL_BOARD_SUBTYPE_LINUX_QFLIGHT 1011 |
|
|
|
|
#define HAL_BOARD_SUBTYPE_LINUX_PXFMINI 1012 |
|
|
|
|
#define HAL_BOARD_SUBTYPE_LINUX_NAVIO2 1013 |
|
|
|
|
#define HAL_BOARD_SUBTYPE_LINUX_DISCO 1014 |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
HAL PX4 sub-types, starting at 2000 |
|
|
|
@ -236,6 +237,45 @@
@@ -236,6 +237,45 @@
|
|
|
|
|
/* 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_DISCO |
|
|
|
|
#define HAL_BOARD_LOG_DIRECTORY "/data/ftp/internal_000/APM/logs" |
|
|
|
|
#define HAL_BOARD_TERRAIN_DIRECTORY "/data/ftp/internal_000/APM/terrain" |
|
|
|
|
#define HAL_INS_DEFAULT HAL_INS_MPU60XX_I2C |
|
|
|
|
#define HAL_INS_MPU60x0_I2C_BUS 2 |
|
|
|
|
#define HAL_INS_MPU60x0_I2C_ADDR 0x68 |
|
|
|
|
#define HAL_COMPASS_DEFAULT HAL_COMPASS_AK8963_I2C |
|
|
|
|
#define HAL_COMPASS_AK8963_I2C_BUS 1 |
|
|
|
|
#define HAL_COMPASS_AK8963_I2C_ADDR 0x0d |
|
|
|
|
#define HAL_BARO_DEFAULT HAL_BARO_MS5607_I2C |
|
|
|
|
#define HAL_BARO_MS5607_I2C_BUS 1 |
|
|
|
|
#define HAL_BARO_MS5607_I2C_ADDR 0x77 |
|
|
|
|
#define HAL_AIRSPEED_MS4515DO_I2C_BUS 1 |
|
|
|
|
#define HAL_UTILS_HEAT HAL_LINUX_HEAT_PWM |
|
|
|
|
#define HAL_LINUX_HEAT_PWM_NUM 10 |
|
|
|
|
#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 |
|
|
|
|
#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_RCOUT_DISCO_BLDC_I2C_BUS 1 |
|
|
|
|
#define HAL_RCOUT_DISCO_BLDC_I2C_ADDR 0x08 |
|
|
|
|
#define HAL_PARAM_DEFAULTS_PATH "/etc/arducopter/bebop.parm" |
|
|
|
|
/* 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" |
|
|
|
|