From d3cbf733bac3f07f74c8c87cfa937d7fbc12ba28 Mon Sep 17 00:00:00 2001 From: rmackay9 Date: Mon, 17 Dec 2012 21:49:57 +0900 Subject: [PATCH] ArduCopter: ensure RTL performs a land if a failsafe has been triggered --- ArduCopter/commands_logic.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/commands_logic.pde b/ArduCopter/commands_logic.pde index 01faa63d85..eccde0b683 100644 --- a/ArduCopter/commands_logic.pde +++ b/ArduCopter/commands_logic.pde @@ -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)