mirror of https://github.com/ArduPilot/ardupilot
AC_PID: fixed default leak min for heli
This commit is contained in:
parent
b012d5bb7b
commit
cf08c46f30
|
@ -10,7 +10,7 @@
|
|||
#include <cmath>
|
||||
#include "AC_PID.h"
|
||||
|
||||
#define AC_PID_LEAK_MIN 500.0 // Default I-term Leak Minimum
|
||||
#define AC_PID_LEAK_MIN 0.1 // Default I-term Leak Minimum
|
||||
|
||||
/// @class AC_HELI_PID
|
||||
/// @brief Heli PID control class
|
||||
|
|
Loading…
Reference in New Issue