ardupilot/libraries/AP_HAL_Linux/hwdef/aero/hwdef.dat

18 lines
590 B
Plaintext

# Intel Aero board
define HAL_RCOUTPUT_TAP_DEVICE "/dev/ttyS1"
define HAL_NUM_CAN_IFACES 1
# NAME BUS SUBDEV MODE BPW CS_PIN LOWSPD HIGHSPD
LINUX_SPIDEV "aeroio" 1 1 SPI_MODE_0 8 SPI_CS_KERNEL 10*MHZ 10*MHZ
LINUX_SPIDEV "bmi160" 3 0 SPI_MODE_3 8 SPI_CS_KERNEL 1*MHZ 10*MHZ
define HAL_LINUX_GPIO_AERO_ENABLED 1
# AP_InertialSensor configuration:
define BMI160_INT1_GPIO AERO_GPIO_BMI160_INT1
define BMI160_INT1_GPIO AERO_GPIO_BMI160_INT1
define BMI160_DEFAULT_ROTATION ROTATION_ROLL_180
define BMI270_DEFAULT_ROTATION ROTATION_ROLL_180