Plane: fix bug in RTL_AUTOLAND with rally points

After loading the rally point, ModeRTL:navigate checks if rally altitude
has been reached before altitude_error_cm gets updated
This commit is contained in:
Bob Long 2023-04-12 02:09:16 -04:00 committed by Andrew Tridgell
parent ff86e2dda8
commit f8d7be5e43
1 changed files with 1 additions and 0 deletions

View File

@ -348,6 +348,7 @@ void Plane::do_RTL(int32_t rtl_altitude_AMSL_cm)
next_WP_loc = calc_best_rally_or_home_location(current_loc, rtl_altitude_AMSL_cm);
setup_terrain_target_alt(next_WP_loc);
set_target_altitude_location(next_WP_loc);
plane.altitude_error_cm = calc_altitude_error_cm();
if (aparm.loiter_radius < 0) {
loiter.direction = -1;