mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
Plane: call adjust_altitude_target after setting waypoint
if we're too close to the next waypoint then we can end up using stale altitude target data when deciding whether a waypoint is complete or not.
This commit is contained in:
parent
b6f1891f9f
commit
92a658c298
@ -59,6 +59,14 @@ void Plane::set_next_WP(const struct Location &loc)
|
||||
|
||||
setup_glide_slope();
|
||||
setup_turn_angle();
|
||||
|
||||
// update plane.target_altitude straight away, or if we are too
|
||||
// close to out loiter point we may decide we are at the correct
|
||||
// altitude before updating it (this is based on scheduler table
|
||||
// ordering, where we navigate() before we
|
||||
// adjust_altitude_target(), and navigate() uses values updated in
|
||||
// adjust_altitude_target()
|
||||
adjust_altitude_target();
|
||||
}
|
||||
|
||||
void Plane::set_guided_WP(const Location &loc)
|
||||
|
Loading…
Reference in New Issue
Block a user