mirror of https://github.com/ArduPilot/ardupilot
AP_InertialSensor: fixed orientation of 2nd OmnibusF7V2 IMU
This commit is contained in:
parent
c8cbbb9246
commit
1b19d09653
|
@ -863,7 +863,7 @@ AP_InertialSensor::detect_backends(void)
|
|||
ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device("icm20789")));
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_OMNIBUSF7V2
|
||||
ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device("mpu6000"), ROTATION_NONE));
|
||||
ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device("mpu6500"), ROTATION_NONE));
|
||||
ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device("mpu6500"), ROTATION_YAW_90));
|
||||
#elif HAL_INS_DEFAULT == HAL_INS_NONE
|
||||
// no INS device
|
||||
#else
|
||||
|
|
Loading…
Reference in New Issue