mirror of https://github.com/ArduPilot/ardupilot
AC_AutoTune: have circular buffers in freqresp object statically allocated
This commit is contained in:
parent
38ff36fca7
commit
7bccaac327
|
@ -24,8 +24,8 @@ void AC_AutoTune_FreqResp::init(InputType input_type)
|
|||
max_accel = 0.0f;
|
||||
max_meas_rate = 0.0f;
|
||||
max_command = 0.0f;
|
||||
meas_peak_info_buffer->clear();
|
||||
tgt_peak_info_buffer->clear();
|
||||
meas_peak_info_buffer.clear();
|
||||
tgt_peak_info_buffer.clear();
|
||||
cycle_complete = false;
|
||||
}
|
||||
|
||||
|
@ -407,14 +407,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;
|
||||
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->pop(sample)) {
|
||||
if (!meas_peak_info_buffer.pop(sample)) {
|
||||
// no sample
|
||||
return;
|
||||
}
|
||||
|
@ -430,7 +430,7 @@ 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;
|
||||
tgt_peak_info_buffer->push(sample);
|
||||
tgt_peak_info_buffer.push(sample);
|
||||
|
||||
}
|
||||
|
||||
|
@ -438,7 +438,7 @@ void AC_AutoTune_FreqResp::push_to_tgt_buffer(uint16_t count, float amplitude, u
|
|||
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->pop(sample)) {
|
||||
if (!tgt_peak_info_buffer.pop(sample)) {
|
||||
// no sample
|
||||
return;
|
||||
}
|
||||
|
|
|
@ -14,9 +14,6 @@ public:
|
|||
// Constructor
|
||||
AC_AutoTune_FreqResp()
|
||||
{
|
||||
// initialize test variables
|
||||
meas_peak_info_buffer = new ObjectBuffer<peak_info>(AUTOTUNE_DWELL_CYCLES);
|
||||
tgt_peak_info_buffer = new ObjectBuffer<peak_info>(AUTOTUNE_DWELL_CYCLES);
|
||||
}
|
||||
|
||||
// Enumeration of input type
|
||||
|
@ -177,10 +174,10 @@ private:
|
|||
};
|
||||
|
||||
// Buffer object for measured peak data
|
||||
ObjectBuffer<peak_info> *meas_peak_info_buffer;
|
||||
ObjectBuffer<peak_info> meas_peak_info_buffer{AUTOTUNE_DWELL_CYCLES};
|
||||
|
||||
// Buffer object for target peak data
|
||||
ObjectBuffer<peak_info> *tgt_peak_info_buffer;
|
||||
ObjectBuffer<peak_info> tgt_peak_info_buffer{AUTOTUNE_DWELL_CYCLES};
|
||||
|
||||
// Push data into measured peak data buffer object
|
||||
void push_to_meas_buffer(uint16_t count, float amplitude, uint32_t time_ms);
|
||||
|
|
Loading…
Reference in New Issue