mirror of https://github.com/ArduPilot/ardupilot
commands.pde RTL Alt
fix to maintain current altitude of we are above our RTL alt for safety.
This commit is contained in:
parent
9e796899e4
commit
acfd263bab
|
@ -109,6 +109,8 @@ static int32_t get_RTL_alt()
|
||||||
{
|
{
|
||||||
if(g.RTL_altitude <= 0){
|
if(g.RTL_altitude <= 0){
|
||||||
return current_loc.alt;
|
return current_loc.alt;
|
||||||
|
}else if (g.RTL_altitude < current_loc.alt){
|
||||||
|
return current_loc.alt;
|
||||||
}else{
|
}else{
|
||||||
return g.RTL_altitude;
|
return g.RTL_altitude;
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue