mirror of https://github.com/ArduPilot/ardupilot
Arducopter: enabled RTL_altitude, renamed function to be more accurate
This commit is contained in:
parent
b199fb22a2
commit
8c8f44e6f7
|
@ -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;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
|
|
@ -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
|
||||
|
|
Loading…
Reference in New Issue