mirror of https://github.com/ArduPilot/ardupilot
Plane: fixed sense of altitude test for glide slope
This commit is contained in:
parent
71132058b4
commit
c9be610dca
|
@ -79,7 +79,7 @@ static void setup_glide_slope(void)
|
||||||
// is basically to prevent situations where we try to slowly
|
// is basically to prevent situations where we try to slowly
|
||||||
// gain height at low altitudes, potentially hitting
|
// gain height at low altitudes, potentially hitting
|
||||||
// obstacles.
|
// obstacles.
|
||||||
if (relative_altitude() > 40 || !above_location_current(next_WP_loc)) {
|
if (relative_altitude() > 40 || above_location_current(next_WP_loc)) {
|
||||||
set_offset_altitude_location(next_WP_loc);
|
set_offset_altitude_location(next_WP_loc);
|
||||||
} else {
|
} else {
|
||||||
reset_offset_altitude();
|
reset_offset_altitude();
|
||||||
|
|
Loading…
Reference in New Issue