AP_Mount: don't use disabled IMUs in solo gimbal code

This commit is contained in:
Andrew Tridgell 2019-07-05 12:40:03 +10:00
parent 3dd7e7e83a
commit a45e364252
1 changed files with 1 additions and 1 deletions

View File

@ -229,7 +229,7 @@ void SoloGimbal::readVehicleDeltaAngle(uint8_t ins_index, Vector3f &dAng) {
void SoloGimbal::update_fast() {
const AP_InertialSensor &ins = AP::ins();
if (ins.get_gyro_health(0) && ins.get_gyro_health(1)) {
if (ins.use_gyro(0) && ins.use_gyro(1)) {
// dual gyro mode - average first two gyros
Vector3f dAng;
readVehicleDeltaAngle(0, dAng);