mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
pulling throttle low in flight turns out to be more common than thought. Removed clearing of takeoff_complete flag. This is still cleared during disarm which is automatic after 30 seconds of no throttle.
This commit is contained in:
parent
09f4a16bfb
commit
08bf04dd08
@ -1633,7 +1633,7 @@ void update_throttle_mode(void)
|
|||||||
|
|
||||||
}else{
|
}else{
|
||||||
// we are on the ground
|
// we are on the ground
|
||||||
takeoff_complete = false;
|
//takeoff_complete = false;
|
||||||
|
|
||||||
// reset baro data if we are near home
|
// reset baro data if we are near home
|
||||||
if(home_distance < 400 || GPS_enabled == false){ // 4m from home
|
if(home_distance < 400 || GPS_enabled == false){ // 4m from home
|
||||||
|
Loading…
Reference in New Issue
Block a user