AP_L1_Control: Sanatize loiter radius to prevent bad input from

propegating
This commit is contained in:
Michael du Breuil 2018-11-29 19:58:21 -07:00 committed by Andrew Tridgell
parent ad01d345d1
commit 536a894850
1 changed files with 1 additions and 1 deletions

View File

@ -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);