mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 08:13:56 -04:00
AP_InertialSensor: use MPU6500 on aerofc
This commit is contained in:
parent
b4d0569339
commit
87846fe049
@ -83,6 +83,7 @@ SPIDesc SPIDeviceManager::device_table[] = {
|
||||
#endif
|
||||
#if defined(PX4_SPIDEV_MPU)
|
||||
SPIDesc("mpu9250", PX4_SPI_BUS_SENSORS, (spi_dev_e)PX4_SPIDEV_MPU, SPIDEV_MODE3, 1*MHZ, 8*MHZ),
|
||||
SPIDesc("mpu6500", PX4_SPI_BUS_SENSORS, (spi_dev_e)PX4_SPIDEV_MPU, SPIDEV_MODE3, 1*MHZ, 8*MHZ),
|
||||
#endif
|
||||
#ifdef PX4_SPIDEV_EXT_MPU
|
||||
SPIDesc("mpu6000_ext", PX4_SPI_BUS_EXT, (spi_dev_e)PX4_SPIDEV_EXT_MPU, SPIDEV_MODE3, 500*KHZ, 8*MHZ),
|
||||
|
@ -742,6 +742,10 @@ AP_InertialSensor::detect_backends(void)
|
||||
_add_backend(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU9250_NAME), ROTATION_YAW_270));
|
||||
break;
|
||||
|
||||
case AP_BoardConfig::PX4_BOARD_AEROFC:
|
||||
_add_backend(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU6500_NAME), ROTATION_YAW_270));
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user