ardupilot/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-Airspeed/hwdef.dat

24 lines
601 B
Plaintext

include ../f103-periph/hwdef.inc
# board ID for firmware load
APJ_BOARD_ID 1077
define HAL_COMPASS_MAX_SENSORS 1
define HAL_AIRSPEED_BUS_DEFAULT 0
# 1 I2C-MS4525D0 sensor by default
define HAL_AIRSPEED_TYPE_DEFAULT 1
define AIRSPEED_MAX_SENSORS 1
define HAL_PERIPH_ENABLE_AIRSPEED
define HAL_PERIPH_ENABLE_MAG
COMPASS QMC5883L I2C:0:0x0D false ROTATION_NONE
COMPASS RM3100 I2C:0:0x20 false ROTATION_NONE
COMPASS RM3100 I2C:0:0x21 false ROTATION_NONE
COMPASS RM3100 I2C:0:0x22 false ROTATION_NONE
COMPASS RM3100 I2C:0:0x23 false ROTATION_NONE
define HAL_PERIPH_ENABLE_NCP5623_LED_WITHOUT_NOTIFY