Browse Source

AP_L1_Control: Sanatize loiter radius to prevent bad input from

propegating
mission-4.1.18
Michael du Breuil 6 years ago committed by Andrew Tridgell
parent
commit
536a894850
  1. 2
      libraries/AP_L1_Control/AP_L1_Control.cpp

2
libraries/AP_L1_Control/AP_L1_Control.cpp

@ -336,7 +336,7 @@ void AP_L1_Control::update_loiter(const struct Location &center_WP, float radius @@ -336,7 +336,7 @@ void AP_L1_Control::update_loiter(const struct Location &center_WP, float radius
// scale loiter radius with square of EAS2TAS to allow us to stay
// stable at high altitude
radius = loiter_radius(radius);
radius = loiter_radius(fabsf(radius));
// Calculate guidance gains used by PD loop (used during circle tracking)
float omega = (6.2832f / _L1_period);

Loading…
Cancel
Save