mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
AC_AutoTune: fixed missing else statement
This commit is contained in:
parent
ce27eb5de1
commit
d6a23fd22a
@ -1276,8 +1276,9 @@ void AC_AutoTune::twitching_abort_rate(float angle, float rate, float angle_max,
|
|||||||
step_scaler *= 0.9f;
|
step_scaler *= 0.9f;
|
||||||
// ignore result and start test again
|
// ignore result and start test again
|
||||||
step = WAITING_FOR_LEVEL;
|
step = WAITING_FOR_LEVEL;
|
||||||
|
} else {
|
||||||
|
step = UPDATE_GAINS;
|
||||||
}
|
}
|
||||||
step = UPDATE_GAINS;
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user