From e2086decc6033dfb50381966aef7fc16660c34a0 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Wed, 23 May 2012 22:00:49 -0700 Subject: [PATCH] Arducopter.pde : setting rtl_approach_alt above 1 would force auto landing even if auto-landing was disabled. --- ArduCopter/ArduCopter.pde | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 7a17382604..154542753f 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -350,8 +350,6 @@ static const char* flight_mode_strings[] = { static int16_t x_actual_speed; static int16_t y_actual_speed; -static int16_t x_rate_d; -static int16_t y_rate_d; // The difference between the desired rate of travel and the actual rate of travel // updated after GPS read - 5-10hz @@ -1773,7 +1771,7 @@ static void update_navigation() if((wp_distance <= g.waypoint_radius) || check_missed_wp()){ // if loiter_timer value > 0, we are set to trigger auto_land or approach after 20 seconds set_mode(LOITER); - if(g.rtl_approach_alt >= 1 || g.rtl_land_enabled || failsafe) + if(g.rtl_land_enabled || failsafe) loiter_timer = millis(); else loiter_timer = 0;