Skip to content

Commit

Permalink
Plane: fix bug in RTL_AUTOLAND with rally points
Browse files Browse the repository at this point in the history
After loading the rally point, ModeRTL:navigate checks if rally altitude
has been reached before altitude_error_cm gets updated
  • Loading branch information
robertlong13 authored and tridge committed Oct 2, 2023
1 parent af061d4 commit 383dcf5
Showing 1 changed file with 1 addition and 0 deletions.
1 change: 1 addition & 0 deletions ArduPlane/commands_logic.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -347,6 +347,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;
Expand Down

0 comments on commit 383dcf5

Please sign in to comment.