mirror of https://github.com/ArduPilot/ardupilot
AC_PID: fixed build on ARM
This commit is contained in:
parent
e7dea077b4
commit
2294acc652
|
@ -6,6 +6,14 @@
|
|||
#include <math.h>
|
||||
#include "AC_PID.h"
|
||||
|
||||
// Examples for _filter:
|
||||
// f_cut = 10 Hz -> _filter = 15.9155e-3
|
||||
// f_cut = 15 Hz -> _filter = 10.6103e-3
|
||||
// f_cut = 20 Hz -> _filter = 7.9577e-3
|
||||
// f_cut = 25 Hz -> _filter = 6.3662e-3
|
||||
// f_cut = 30 Hz -> _filter = 5.3052e-3
|
||||
const float AC_PID::_filter = 7.9577e-3; // Set to "1 / ( 2 * PI * f_cut )";
|
||||
|
||||
const AP_Param::GroupInfo AC_PID::var_info[] PROGMEM = {
|
||||
// @Param: P
|
||||
// @DisplayName: PID Proportional Gain
|
||||
|
|
|
@ -134,13 +134,7 @@ private:
|
|||
|
||||
/// Low pass filter cut frequency for derivative calculation.
|
||||
///
|
||||
static const float _filter = 7.9577e-3; // Set to "1 / ( 2 * PI * f_cut )";
|
||||
// Examples for _filter:
|
||||
// f_cut = 10 Hz -> _filter = 15.9155e-3
|
||||
// f_cut = 15 Hz -> _filter = 10.6103e-3
|
||||
// f_cut = 20 Hz -> _filter = 7.9577e-3
|
||||
// f_cut = 25 Hz -> _filter = 6.3662e-3
|
||||
// f_cut = 30 Hz -> _filter = 5.3052e-3
|
||||
static const float _filter;
|
||||
};
|
||||
|
||||
#endif // __AC_PID_H__
|
||||
|
|
Loading…
Reference in New Issue