Plane: change threshold for no glide slope to 20m

40m is quite high for most planes
This commit is contained in:
Andrew Tridgell 2014-08-04 19:59:33 +10:00
parent 8610d9a8ea
commit 28facc220d
1 changed files with 3 additions and 3 deletions

View File

@ -74,12 +74,12 @@ static void setup_glide_slope(void)
break; break;
case AUTO: case AUTO:
// we only do glide slide handling in AUTO when above 40m or // we only do glide slide handling in AUTO when above 20m or
// when descending. The 40 meter threshold is arbitrary, and // when descending. The 20 meter threshold is arbitrary, and
// 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() > 20 || 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();