Plane: more accurate altitude tracking close to waypoints

don't use a glide slope if the altitude change is less than 15 meters
This commit is contained in:
Andrew Tridgell 2014-08-04 17:13:30 +10:00
parent f983040401
commit 9536124300
1 changed files with 9 additions and 0 deletions

View File

@ -324,6 +324,15 @@ static void set_offset_altitude_location(const Location &loc)
target_altitude.offset_cm = target_altitude.terrain_alt_cm - (height * 100);
}
#endif
// if we are within 15 meters of the target altitude then reset
// the offset to not use a glide slope. This allows for more
// accurate flight of missions where the aircraft may lose or gain
// a bit of altitude near waypoint turn points due to local
// terrain changes
if (labs(target_altitude.offset_cm) < 1500) {
target_altitude.offset_cm = 0;
}
}
/*