From 5fa2fcfa56c61710bbfb9feb6f916051ab583769 Mon Sep 17 00:00:00 2001 From: bnsgeyer Date: Mon, 1 Jul 2024 17:56:23 -0400 Subject: [PATCH] AC_AutoTune: return freqresp ring buffers to original implementation --- .../AC_AutoTune/AC_AutoTune_FreqResp.cpp | 20 ++++++------------- libraries/AC_AutoTune/AC_AutoTune_FreqResp.h | 7 ++----- 2 files changed, 8 insertions(+), 19 deletions(-) diff --git a/libraries/AC_AutoTune/AC_AutoTune_FreqResp.cpp b/libraries/AC_AutoTune/AC_AutoTune_FreqResp.cpp index feea5fa04f..c85aa33f65 100644 --- a/libraries/AC_AutoTune/AC_AutoTune_FreqResp.cpp +++ b/libraries/AC_AutoTune/AC_AutoTune_FreqResp.cpp @@ -26,12 +26,8 @@ void AC_AutoTune_FreqResp::init(InputType input_type, ResponseType response_type max_meas_rate = 0.0f; max_command = 0.0f; dwell_cycles = cycles; - if (meas_peak_info_buffer != nullptr) { - meas_peak_info_buffer->clear(); - } - if (tgt_peak_info_buffer != nullptr) { - tgt_peak_info_buffer->clear(); - } + meas_peak_info_buffer.clear(); + tgt_peak_info_buffer.clear(); 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.amplitude = amplitude; 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 void AC_AutoTune_FreqResp::pull_from_meas_buffer(uint16_t &count, float &litude, uint32_t &time_ms) { peak_info sample; - if ((meas_peak_info_buffer == nullptr) || !meas_peak_info_buffer->pop(sample)) { + if (!meas_peak_info_buffer.pop(sample)) { // no sample return; } @@ -288,16 +282,14 @@ void AC_AutoTune_FreqResp::push_to_tgt_buffer(uint16_t count, float amplitude, u sample.curr_count = count; sample.amplitude = amplitude; 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 void AC_AutoTune_FreqResp::pull_from_tgt_buffer(uint16_t &count, float &litude, uint32_t &time_ms) { peak_info sample; - if ((tgt_peak_info_buffer == nullptr) || !tgt_peak_info_buffer->pop(sample)) { + if (!tgt_peak_info_buffer.pop(sample)) { // no sample return; } diff --git a/libraries/AC_AutoTune/AC_AutoTune_FreqResp.h b/libraries/AC_AutoTune/AC_AutoTune_FreqResp.h index e36121643b..ada80e103a 100644 --- a/libraries/AC_AutoTune/AC_AutoTune_FreqResp.h +++ b/libraries/AC_AutoTune/AC_AutoTune_FreqResp.h @@ -11,9 +11,6 @@ public: // Constructor 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(12); - tgt_peak_info_buffer = NEW_NOTHROW ObjectBuffer(12); } // Enumeration of input type @@ -183,10 +180,10 @@ private: }; // Buffer object for measured peak data - ObjectBuffer *meas_peak_info_buffer; + ObjectBuffer meas_peak_info_buffer{12}; // Buffer object for target peak data - ObjectBuffer *tgt_peak_info_buffer; + ObjectBuffer tgt_peak_info_buffer{12}; // Push data into measured peak data buffer object void push_to_meas_buffer(uint16_t count, float amplitude, uint32_t time_ms);