mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_L1_Control: Sanatize loiter radius to prevent bad input from
propegating
This commit is contained in:
parent
ad01d345d1
commit
536a894850
@ -336,7 +336,7 @@ void AP_L1_Control::update_loiter(const struct Location ¢er_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…
Reference in New Issue
Block a user