mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
Made RTL always the current Altitude
This commit is contained in:
parent
c970ba4f93
commit
414a2581a0
@ -107,10 +107,13 @@ static void set_cmd_with_index(struct Location temp, int i)
|
|||||||
|
|
||||||
static int32_t read_alt_to_hold()
|
static int32_t read_alt_to_hold()
|
||||||
{
|
{
|
||||||
|
return current_loc.alt;
|
||||||
|
/*
|
||||||
if(g.RTL_altitude <= 0)
|
if(g.RTL_altitude <= 0)
|
||||||
return current_loc.alt;
|
return current_loc.alt;
|
||||||
else
|
else
|
||||||
return g.RTL_altitude;// + home.alt;
|
return g.RTL_altitude;// + home.alt;
|
||||||
|
*/
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user