mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
fix issue with low throttle in air
This commit is contained in:
parent
151479f769
commit
ef9418c2de
@ -905,8 +905,8 @@ static void fast_loop()
|
||||
|
||||
if(takeoff_complete == false){
|
||||
// reset these I terms to prevent awkward tipping on takeoff
|
||||
reset_rate_I();
|
||||
reset_stability_I();
|
||||
//reset_rate_I();
|
||||
//reset_stability_I();
|
||||
}
|
||||
|
||||
// custom code/exceptions for flight modes
|
||||
|
Loading…
Reference in New Issue
Block a user