mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
converted to cm
Signed-off-by: Jason Short <jasonshort@mac.com>
This commit is contained in:
parent
7616c3b5a1
commit
a213e05eb9
@ -158,7 +158,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((motor_armed == true) && (home_distance > 10) && (current_loc.alt > 400)){
|
||||
if((motor_armed == true) && (home_distance > 1000) && (current_loc.alt > 400)){
|
||||
SendDebug("MSG FS ON ");
|
||||
SendDebugln(pwm, DEC);
|
||||
set_failsafe(true);
|
||||
|
Loading…
Reference in New Issue
Block a user