APM_Control: fixed for cygwin build

This commit is contained in:
Andrew Tridgell 2021-04-02 12:54:34 +11:00
parent 364fa0680d
commit 3cb32a18f0
2 changed files with 5 additions and 5 deletions

View File

@ -236,7 +236,7 @@ void AP_AutoTune::update(AP_Logger::PID_Info &pinfo, float scaler)
unsigned(new_state),
actuator,
desired_rate,
FF0,
FF_single,
current.FF,
current.P,
current.D,
@ -277,13 +277,13 @@ void AP_AutoTune::update(AP_Logger::PID_Info &pinfo, float scaler)
// we've finished an event. calculate the single-event FF value
if (state == ATState::DEMAND_POS) {
FF0 = max_actuator / (max_rate * scaler);
FF_single = max_actuator / (max_rate * scaler);
} else {
FF0 = min_actuator / (min_rate * scaler);
FF_single = min_actuator / (min_rate * scaler);
}
// apply median filter
float FF = ff_filter.apply(FF0);
float FF = ff_filter.apply(FF_single);
const float old_FF = rpid.ff();

View File

@ -114,5 +114,5 @@ private:
float max_P;
float max_D;
float min_Dmod;
float FF0;
float FF_single;
};