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
038116f521
commit
cf6d73ec88
|
@ -109,6 +109,8 @@ static int32_t get_RTL_alt()
|
|||
{
|
||||
if(g.RTL_altitude <= 0){
|
||||
return current_loc.alt;
|
||||
}else if (g.RTL_altitude < current_loc.alt){
|
||||
return current_loc.alt;
|
||||
}else{
|
||||
return g.RTL_altitude;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue