APM_Control: fixed build on ARM
This commit is contained in:
parent
5a56b845c0
commit
5277dd4b0f
@ -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();
|
||||
|
@ -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__
|
||||
|
Loading…
Reference in New Issue
Block a user