Arducopter: enabled RTL_altitude, renamed function to be more accurate

This commit is contained in:
Jason Short 2012-06-30 15:34:55 -07:00
parent 2e8eee9306
commit 2450c25544
2 changed files with 6 additions and 9 deletions

View File

@ -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;
}
}

View File

@ -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