diff --git a/libraries/AP_L1_Control/AP_L1_Control.cpp b/libraries/AP_L1_Control/AP_L1_Control.cpp index 9199e3ba0b..aca1b48c28 100644 --- a/libraries/AP_L1_Control/AP_L1_Control.cpp +++ b/libraries/AP_L1_Control/AP_L1_Control.cpp @@ -60,6 +60,7 @@ int32_t AP_L1_Control::target_bearing_cd(void) float AP_L1_Control::turn_distance(float wp_radius) { + wp_radius *= sq(_ahrs->get_EAS2TAS()); return min(wp_radius, _L1_dist); } @@ -168,6 +169,10 @@ void AP_L1_Control::update_loiter(const struct Location ¢er_WP, float radius { struct Location _current_loc; + // scale loiter radius with square of EAS2TAS to allow us to stay + // stable at high altitude + radius *= sq(_ahrs->get_EAS2TAS()); + // Calculate guidance gains used by PD loop (used during circle tracking) float omega = (6.2832f / _L1_period); float Kx = omega * omega;