mirror of https://github.com/ArduPilot/ardupilot
Failsafe: Looking for takeoff_complete now vs unreliable GPS
This commit is contained in:
parent
08bf04dd08
commit
15774366ba
|
@ -147,7 +147,7 @@ static void throttle_failsafe(uint16_t pwm)
|
|||
// Don't enter Failsafe if we are not armed
|
||||
// home distance is in meters
|
||||
// This is to prevent accidental RTL
|
||||
if(motors.armed() && (home_distance > 1000)){
|
||||
if(motors.armed() && takeoff_complete){
|
||||
SendDebug("MSG FS ON ");
|
||||
SendDebugln(pwm, DEC);
|
||||
set_failsafe(true);
|
||||
|
|
Loading…
Reference in New Issue