mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
ArduCopter: Added check to make sure user defined approach alt is at least 5.
This commit is contained in:
parent
cddcdb8be3
commit
2954bf6f76
@ -1814,7 +1814,7 @@ static void update_navigation()
|
||||
wp_control = LOITER_MODE;
|
||||
}
|
||||
|
||||
if(g.rtl_approach_alt > 0){
|
||||
if(g.rtl_approach_alt > 5){
|
||||
set_mode(APPROACH);
|
||||
}
|
||||
// Kick us out of loiter and begin landing if the auto_land_timer is set
|
||||
|
Loading…
Reference in New Issue
Block a user