diff --git a/libraries/APM_Control/AP_YawController.cpp b/libraries/APM_Control/AP_YawController.cpp index 03acdc4984..27bbc82d47 100644 --- a/libraries/APM_Control/AP_YawController.cpp +++ b/libraries/APM_Control/AP_YawController.cpp @@ -20,6 +20,11 @@ const AP_Param::GroupInfo AP_YawController::var_info[] PROGMEM = { AP_GROUPEND }; +// Low pass filter cut frequency for derivative calculation. +// FCUT macro computes a frequency cut based on an acceptable delay. +#define FCUT(d) (1 / ( 2 * 3.14 * (d) ) ) +const float AP_YawController::_fCut = FCUT(.5); + int32_t AP_YawController::get_servo_out(float scaler, bool stick_movement) { uint32_t tnow = hal.scheduler->millis(); diff --git a/libraries/APM_Control/AP_YawController.h b/libraries/APM_Control/AP_YawController.h index d636a4578b..33860da8a5 100644 --- a/libraries/APM_Control/AP_YawController.h +++ b/libraries/APM_Control/AP_YawController.h @@ -9,7 +9,8 @@ class AP_YawController { public: - AP_YawController() { + AP_YawController() + { AP_Param::setup_object_defaults(this, var_info); } @@ -39,10 +40,7 @@ private: AP_AHRS *_ahrs; AP_InertialSensor *_ins; - // Low pass filter cut frequency for derivative calculation. - // FCUT macro computes a frequency cut based on an acceptable delay. - #define FCUT(d) (1 / ( 2 * 3.14 * (d) ) ) - const float _fCut = FCUT(.5); + static const float _fCut; }; #endif // __AP_YAW_CONTROLLER_H__