mirror of https://github.com/ArduPilot/ardupilot
AP_InertialSensor: fixed rotation for mpu9250 on pixracer
This commit is contained in:
parent
790dd4769b
commit
408593465f
|
@ -686,7 +686,7 @@ AP_InertialSensor::detect_backends(void)
|
|||
hal.spi->get_device(HAL_INS_LSM9DS0_EXT_A_NAME), ROTATION_ROLL_180_YAW_270));
|
||||
_add_backend(AP_InertialSensor_MPU9250::probe(*this, hal.spi->get_device(HAL_INS_MPU9250_NAME), ROTATION_YAW_270));
|
||||
} else if (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_TEST_V4) {
|
||||
_add_backend(AP_InertialSensor_MPU9250::probe(*this, hal.spi->get_device(HAL_INS_MPU9250_NAME)));
|
||||
_add_backend(AP_InertialSensor_MPU9250::probe(*this, hal.spi->get_device(HAL_INS_MPU9250_NAME), ROTATION_ROLL_180_YAW_90));
|
||||
}
|
||||
// also add any PX4 backends (eg. canbus sensors)
|
||||
_add_backend(AP_InertialSensor_PX4::detect(*this));
|
||||
|
|
Loading…
Reference in New Issue