From 2450c255448ee411fa7ab807371ce57a54059dfc Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 30 Jun 2012 15:34:55 -0700 Subject: [PATCH] Arducopter: enabled RTL_altitude, renamed function to be more accurate --- ArduCopter/commands.pde | 12 +++++------- ArduCopter/commands_logic.pde | 3 +-- 2 files changed, 6 insertions(+), 9 deletions(-) diff --git a/ArduCopter/commands.pde b/ArduCopter/commands.pde index 25f3f8c3e6..466dd47b45 100644 --- a/ArduCopter/commands.pde +++ b/ArduCopter/commands.pde @@ -105,15 +105,13 @@ static void set_cmd_with_index(struct Location temp, int i) g.command_total.set_and_save(i+1); } -static int32_t read_alt_to_hold() +static int32_t get_RTL_alt() { - return current_loc.alt; - /* - if(g.RTL_altitude <= 0) + if(g.RTL_altitude <= 0){ return current_loc.alt; - else - return g.RTL_altitude;// + home.alt; - */ + }else{ + return g.RTL_altitude; + } } diff --git a/ArduCopter/commands_logic.pde b/ArduCopter/commands_logic.pde index e20172b154..2c5dc4ba28 100644 --- a/ArduCopter/commands_logic.pde +++ b/ArduCopter/commands_logic.pde @@ -198,7 +198,7 @@ static void do_RTL(void) { // TODO: Altitude option from mission planner Location temp = home; - temp.alt = read_alt_to_hold(); + temp.alt = get_RTL_alt(); //so we know where we are navigating from // -------------------------------------- @@ -561,7 +561,6 @@ static bool verify_loiter_turns() static bool verify_RTL() { - // loiter at the WP wp_control = WP_MODE; // Did we pass the WP? // Distance checking