mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
AC_PID: correct AC_PID_LEAK_MIN constant type
This commit is contained in:
parent
2c5373e278
commit
112ace8adb
@ -9,7 +9,7 @@
|
||||
#include <cmath>
|
||||
#include "AC_PID.h"
|
||||
|
||||
#define AC_PID_LEAK_MIN 0.1 // Default I-term Leak Minimum
|
||||
static const float AC_PID_LEAK_MIN = 0.1f; // Default I-term Leak Minimum
|
||||
|
||||
/// @class AC_HELI_PID
|
||||
/// @brief Heli PID control class
|
||||
|
Loading…
Reference in New Issue
Block a user