AC_AutoTune: return freqresp ring buffers to original implementation

This commit is contained in:
bnsgeyer 2024-07-01 17:56:23 -04:00 committed by Bill Geyer
parent 475663e199
commit 5fa2fcfa56
2 changed files with 8 additions and 19 deletions

View File

@ -26,12 +26,8 @@ void AC_AutoTune_FreqResp::init(InputType input_type, ResponseType response_type
max_meas_rate = 0.0f; max_meas_rate = 0.0f;
max_command = 0.0f; max_command = 0.0f;
dwell_cycles = cycles; dwell_cycles = cycles;
if (meas_peak_info_buffer != nullptr) { meas_peak_info_buffer.clear();
meas_peak_info_buffer->clear(); tgt_peak_info_buffer.clear();
}
if (tgt_peak_info_buffer != nullptr) {
tgt_peak_info_buffer->clear();
}
cycle_complete = false; cycle_complete = false;
} }
@ -263,16 +259,14 @@ void AC_AutoTune_FreqResp::push_to_meas_buffer(uint16_t count, float amplitude,
sample.curr_count = count; sample.curr_count = count;
sample.amplitude = amplitude; sample.amplitude = amplitude;
sample.time_ms = time_ms; sample.time_ms = time_ms;
if (meas_peak_info_buffer != nullptr) { meas_peak_info_buffer.push(sample);
meas_peak_info_buffer->push(sample);
}
} }
// pull measured peak info from buffer // pull measured peak info from buffer
void AC_AutoTune_FreqResp::pull_from_meas_buffer(uint16_t &count, float &amplitude, uint32_t &time_ms) void AC_AutoTune_FreqResp::pull_from_meas_buffer(uint16_t &count, float &amplitude, uint32_t &time_ms)
{ {
peak_info sample; peak_info sample;
if ((meas_peak_info_buffer == nullptr) || !meas_peak_info_buffer->pop(sample)) { if (!meas_peak_info_buffer.pop(sample)) {
// no sample // no sample
return; return;
} }
@ -288,16 +282,14 @@ void AC_AutoTune_FreqResp::push_to_tgt_buffer(uint16_t count, float amplitude, u
sample.curr_count = count; sample.curr_count = count;
sample.amplitude = amplitude; sample.amplitude = amplitude;
sample.time_ms = time_ms; sample.time_ms = time_ms;
if (tgt_peak_info_buffer != nullptr) { tgt_peak_info_buffer.push(sample);
tgt_peak_info_buffer->push(sample);
}
} }
// pull target peak info from buffer // pull target peak info from buffer
void AC_AutoTune_FreqResp::pull_from_tgt_buffer(uint16_t &count, float &amplitude, uint32_t &time_ms) void AC_AutoTune_FreqResp::pull_from_tgt_buffer(uint16_t &count, float &amplitude, uint32_t &time_ms)
{ {
peak_info sample; peak_info sample;
if ((tgt_peak_info_buffer == nullptr) || !tgt_peak_info_buffer->pop(sample)) { if (!tgt_peak_info_buffer.pop(sample)) {
// no sample // no sample
return; return;
} }

View File

@ -11,9 +11,6 @@ public:
// Constructor // Constructor
AC_AutoTune_FreqResp() AC_AutoTune_FreqResp()
{ {
// ring buffers sized to for more cycles than are needed. Most cycles needed are 6.
meas_peak_info_buffer = NEW_NOTHROW ObjectBuffer<peak_info>(12);
tgt_peak_info_buffer = NEW_NOTHROW ObjectBuffer<peak_info>(12);
} }
// Enumeration of input type // Enumeration of input type
@ -183,10 +180,10 @@ private:
}; };
// Buffer object for measured peak data // Buffer object for measured peak data
ObjectBuffer<peak_info> *meas_peak_info_buffer; ObjectBuffer<peak_info> meas_peak_info_buffer{12};
// Buffer object for target peak data // Buffer object for target peak data
ObjectBuffer<peak_info> *tgt_peak_info_buffer; ObjectBuffer<peak_info> tgt_peak_info_buffer{12};
// Push data into measured peak data buffer object // Push data into measured peak data buffer object
void push_to_meas_buffer(uint16_t count, float amplitude, uint32_t time_ms); void push_to_meas_buffer(uint16_t count, float amplitude, uint32_t time_ms);