AC_AutoTune: remove deletion of ring buffers

This commit is contained in:
bnsgeyer 2024-06-22 13:52:20 -04:00 committed by Bill Geyer
parent f50bb54112
commit bb6c52d508
3 changed files with 9 additions and 23 deletions

View File

@ -6,7 +6,7 @@ This library receives time history data (angular rate or angle) during a dwell t
#include "AC_AutoTune_FreqResp.h" #include "AC_AutoTune_FreqResp.h"
// Initialize the Frequency Response Object. Must be called before running dwell or frequency sweep tests // Initialize the Frequency Response Object. Must be called before running dwell or frequency sweep tests
void AC_AutoTune_FreqResp::init(InputType input_type, ResponseType response_type) void AC_AutoTune_FreqResp::init(InputType input_type, ResponseType response_type, uint8_t cycles)
{ {
excitation = input_type; excitation = input_type;
response = response_type; response = response_type;
@ -25,6 +25,7 @@ void AC_AutoTune_FreqResp::init(InputType input_type, ResponseType response_type
max_accel = 0.0f; max_accel = 0.0f;
max_meas_rate = 0.0f; max_meas_rate = 0.0f;
max_command = 0.0f; max_command = 0.0f;
dwell_cycles = cycles;
if (meas_peak_info_buffer != nullptr) { if (meas_peak_info_buffer != nullptr) {
meas_peak_info_buffer->clear(); meas_peak_info_buffer->clear();
} }
@ -305,12 +306,3 @@ void AC_AutoTune_FreqResp::pull_from_tgt_buffer(uint16_t &count, float &amplitud
time_ms = sample.time_ms; time_ms = sample.time_ms;
} }
void AC_AutoTune_FreqResp::set_dwell_cycles(uint8_t cycles)
{
dwell_cycles = cycles;
delete meas_peak_info_buffer;
meas_peak_info_buffer = NEW_NOTHROW ObjectBuffer<peak_info>(cycles);
delete tgt_peak_info_buffer;
tgt_peak_info_buffer = NEW_NOTHROW ObjectBuffer<peak_info>(cycles);
}

View File

@ -11,9 +11,9 @@ public:
// Constructor // Constructor
AC_AutoTune_FreqResp() AC_AutoTune_FreqResp()
{ {
dwell_cycles = 6; // ring buffers sized to for more cycles than are needed. Most cycles needed are 6.
meas_peak_info_buffer = NEW_NOTHROW ObjectBuffer<peak_info>(dwell_cycles); meas_peak_info_buffer = NEW_NOTHROW ObjectBuffer<peak_info>(12);
tgt_peak_info_buffer = NEW_NOTHROW ObjectBuffer<peak_info>(dwell_cycles); tgt_peak_info_buffer = NEW_NOTHROW ObjectBuffer<peak_info>(12);
} }
// Enumeration of input type // Enumeration of input type
@ -30,7 +30,7 @@ public:
// Initialize the Frequency Response Object. // Initialize the Frequency Response Object.
// Must be called before running dwell or frequency sweep tests // Must be called before running dwell or frequency sweep tests
void init(InputType input_type, ResponseType response_type); void init(InputType input_type, ResponseType response_type, uint8_t cycles);
// Determines the gain and phase based on angle response for a dwell or sweep // Determines the gain and phase based on angle response for a dwell or sweep
void update(float command, float tgt_resp, float meas_resp, float tgt_freq); void update(float command, float tgt_resp, float meas_resp, float tgt_freq);
@ -41,10 +41,6 @@ public:
// Reset cycle_complete flag // Reset cycle_complete flag
void reset_cycle_complete() { cycle_complete = false; } void reset_cycle_complete() { cycle_complete = false; }
void set_dwell_cycles(uint8_t cycles);
uint8_t get_dwell_cycles() { return dwell_cycles;}
// Frequency response data accessors // Frequency response data accessors
float get_freq() { return curr_test_freq; } float get_freq() { return curr_test_freq; }
float get_gain() { return curr_test_gain; } float get_gain() { return curr_test_gain; }

View File

@ -753,17 +753,15 @@ void AC_AutoTune_Heli::dwell_test_init(float start_frq, float stop_frq, float am
curr_test.phase = 0.0f; curr_test.phase = 0.0f;
chirp_input.init(0.001f * sweep_time_ms, start_frq / M_2PI, stop_frq / M_2PI, 0.0f, 0.0001f * sweep_time_ms, 0.0f); chirp_input.init(0.001f * sweep_time_ms, start_frq / M_2PI, stop_frq / M_2PI, 0.0f, 0.0001f * sweep_time_ms, 0.0f);
} else { } else {
freqresp_tgt.set_dwell_cycles(num_dwell_cycles);
freqresp_mtr.set_dwell_cycles(num_dwell_cycles);
if (!is_zero(start_frq)) { if (!is_zero(start_frq)) {
// time limit set by adding the pre calc cycles with the dwell cycles. 500 ms added to account for settling with buffer. // time limit set by adding the pre calc cycles with the dwell cycles. 500 ms added to account for settling with buffer.
step_time_limit_ms = (uint32_t) (2000 + ((float) freqresp_tgt.get_dwell_cycles() + pre_calc_cycles + 2.0f) * 1000.0f * M_2PI / start_frq); step_time_limit_ms = (uint32_t) (2000 + ((float)num_dwell_cycles + pre_calc_cycles + 2.0f) * 1000.0f * M_2PI / start_frq);
} }
chirp_input.init(0.001f * step_time_limit_ms, start_frq / M_2PI, stop_frq / M_2PI, 0.0f, 0.0001f * step_time_limit_ms, 0.0f); chirp_input.init(0.001f * step_time_limit_ms, start_frq / M_2PI, stop_frq / M_2PI, 0.0f, 0.0001f * step_time_limit_ms, 0.0f);
} }
freqresp_tgt.init(test_input_type, resp_type); freqresp_tgt.init(test_input_type, resp_type, num_dwell_cycles);
freqresp_mtr.init(test_input_type, resp_type); freqresp_mtr.init(test_input_type, resp_type, num_dwell_cycles);
dwell_start_time_ms = 0.0f; dwell_start_time_ms = 0.0f;
settle_time = 200; settle_time = 200;