ardupilot/libraries/AP_HAL_ChibiOS/hwdef/f103-QiotekPeriph/hwdef.dat

21 lines
601 B
Plaintext
Raw Normal View History

include ../f103-periph/hwdef.inc
undef HAL_COMPASS_MAX_SENSORS 1
2021-04-23 04:49:19 -03:00
define HAL_COMPASS_MAX_SENSORS 2
define HAL_AIRSPEED_BUS_DEFAULT 0
# 15 ASP5033 sensor by default
define HAL_AIRSPEED_TYPE_DEFAULT 15
define AIRSPEED_MAX_SENSORS 1
define HAL_PERIPH_ENABLE_AIRSPEED
define HAL_PERIPH_ENABLE_MAG
COMPASS IST8310 I2C:0:0x0E false ROTATION_ROLL_180_YAW_270
COMPASS QMC5883L I2C:0:0x0D false ROTATION_ROLL_180_YAW_270
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