mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
ArduCopter: ensure RTL performs a land if a failsafe has been triggered
This commit is contained in:
parent
6e64b1b357
commit
d3cbf733ba
@ -511,7 +511,7 @@ static bool verify_RTL()
|
||||
// check if we've loitered long enough
|
||||
if( millis() - rtl_loiter_start_time > (uint32_t)g.rtl_loiter_time.get() ) {
|
||||
// initiate landing or descent
|
||||
if(g.rtl_alt_final == 0) {
|
||||
if(g.rtl_alt_final == 0 || ap.failsafe) {
|
||||
// land
|
||||
do_land();
|
||||
// override landing location (do_land defaults to current location)
|
||||
|
Loading…
Reference in New Issue
Block a user