mirror of https://github.com/ArduPilot/ardupilot
Plane: fixed above_location_current() for non-terrain alt
thanks to Lekston for finding the bug (PR#2610)
This commit is contained in:
parent
5c9d248407
commit
8f0e7e0693
|
@ -398,8 +398,8 @@ bool Plane::above_location_current(const Location &loc)
|
|||
#endif
|
||||
|
||||
float loc_alt_cm = loc.alt;
|
||||
if (!loc.flags.relative_alt) {
|
||||
loc_alt_cm -= home.alt;
|
||||
if (loc.flags.relative_alt) {
|
||||
loc_alt_cm += home.alt;
|
||||
}
|
||||
return current_loc.alt > loc_alt_cm;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue