ardupilot/libraries/AP_HAL_Linux/hwdef/ocpoc_zynq/hwdef.dat
2025-02-25 14:38:45 +11:00

17 lines
530 B
Plaintext

# SPI Devices:
# MPU9250 is restricted to 1MHz for non-data and interrupt registers
# NAME BUS SUBDEV MODE BPW CS_PIN LOWSPD HIGHSPD
LINUX_SPIDEV "mpu9250" 1 0 SPI_MODE_3 8 SPI_CS_KERNEL 1*MHZ 10*MHZ
LINUX_SPIDEV "ms5611" 1 1 SPI_MODE_3 8 SPI_CS_KERNEL 1*MHZ 10*MHZ
# IMUs:
IMU Invensense SPI:mpu9250 ROTATION_NONE
define INS_MAX_INSTANCES 3
# Compasses:
COMPASS AK8963:probe_mpu9250 0 ROTATION_NONE
define HAL_PROBE_EXTERNAL_I2C_COMPASSES 1
# Baros:
BARO MS56XX SPI:ms5611