mirror of https://github.com/ArduPilot/ardupilot
ArduCopter, commands_logic: Updated logic to allow as low as 5m.
This commit is contained in:
parent
2954bf6f76
commit
77d6f22864
|
@ -1814,7 +1814,7 @@ static void update_navigation()
|
|||
wp_control = LOITER_MODE;
|
||||
}
|
||||
|
||||
if(g.rtl_approach_alt > 5){
|
||||
if(g.rtl_approach_alt >= 5){
|
||||
set_mode(APPROACH);
|
||||
}
|
||||
// Kick us out of loiter and begin landing if the auto_land_timer is set
|
||||
|
|
|
@ -295,7 +295,7 @@ static void do_land()
|
|||
static void do_approach()
|
||||
{
|
||||
// Make sure we are not using this to land
|
||||
if(g.rtl_approach_alt > 5){
|
||||
if(g.rtl_approach_alt >= 5){
|
||||
wp_control = LOITER_MODE;
|
||||
|
||||
// just to make sure
|
||||
|
|
Loading…
Reference in New Issue