Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AC_AutoTune/AC_AutoTune_FreqResp.cpp
Views: 1798
/*1This library receives time history data (angular rate or angle) during a dwell test or frequency sweep test and determines the gain and phase of the response to the input. For dwell tests once the designated number of cycles are complete, the average of the gain and phase are determined over the last 5 cycles and the cycle_complete flag is set. For frequency sweep tests, phase and gain are determined for every cycle and cycle_complete flag is set to indicate when to pull the phase and gain data. The flag is reset to enable the next cycle to be analyzed. The init function must be used when initializing the dwell or frequency sweep test.2*/34#include <AP_HAL/AP_HAL.h>5#include "AC_AutoTune_FreqResp.h"67// Initialize the Frequency Response Object. Must be called before running dwell or frequency sweep tests8void AC_AutoTune_FreqResp::init(InputType input_type, ResponseType response_type, uint8_t cycles)9{10excitation = input_type;11response = response_type;12max_target_cnt = 0;13min_target_cnt = 0;14max_meas_cnt = 0;15min_meas_cnt = 0;16input_start_time_ms = 0;17new_tgt_time_ms = 0;18new_meas_time_ms = 0;19new_target = false;20new_meas = false;21curr_test_freq = 0.0f;22curr_test_gain = 0.0f;23curr_test_phase = 0.0f;24max_accel = 0.0f;25max_meas_rate = 0.0f;26max_command = 0.0f;27dwell_cycles = cycles;28meas_peak_info_buffer.clear();29tgt_peak_info_buffer.clear();30cycle_complete = false;31}3233// update_angle - this function receives time history data during a dwell and frequency sweep tests for angle_p tuning34// and determines the gain, phase, and max acceleration of the response to the input. For dwell tests once the designated number35// of cycles are complete, the average of the gain, phase, and max acceleration are determined over the last 5 cycles and the36// cycles_complete flag is set. For frequency sweep tests, phase and gain are determined for every cycle and cycle_complete flag is set37// to indicate when to pull the phase and gain data. The flag is reset to enable the next cycle to be analyzed.38void AC_AutoTune_FreqResp::update(float command, float tgt_resp, float meas_resp, float tgt_freq)39{4041uint32_t now = AP_HAL::millis();42float dt = 0.0025;43uint32_t half_cycle_time_ms = 0;44uint32_t cycle_time_ms = 0;4546if (cycle_complete) {47return;48}4950if (!is_zero(tgt_freq)) {51half_cycle_time_ms = (uint32_t)(300 * M_2PI / tgt_freq);52cycle_time_ms = (uint32_t)(1000 * M_2PI / tgt_freq);53}5455if (input_start_time_ms == 0) {56input_start_time_ms = now;57if (response == ANGLE) {58prev_tgt_resp = tgt_resp;59prev_meas_resp = meas_resp;60prev_target = 0.0f;61prev_meas = 0.0f;62}63}6465if (response == ANGLE) {66target_rate = (tgt_resp - prev_tgt_resp) / dt;67measured_rate = (meas_resp - prev_meas_resp) / dt;68} else {69target_rate = tgt_resp;70measured_rate = meas_resp;71}7273// cycles are complete! determine gain and phase and exit74if (max_meas_cnt > dwell_cycles + 1 && max_target_cnt > dwell_cycles + 1 && excitation == DWELL) {75float delta_time = 0.0f;76float sum_gain = 0.0f;77uint8_t cnt = 0;78uint8_t gcnt = 0;79uint16_t meas_cnt, tgt_cnt;80float meas_ampl = 0.0f;81float tgt_ampl = 0.0f;82uint32_t meas_time = 0;83uint32_t tgt_time = 0;84for (uint8_t i = 0; i < dwell_cycles; i++) {85meas_cnt=0;86tgt_cnt=0;87pull_from_meas_buffer(meas_cnt, meas_ampl, meas_time);88pull_from_tgt_buffer(tgt_cnt, tgt_ampl, tgt_time);89push_to_meas_buffer(0, 0.0f, 0);90push_to_tgt_buffer(0, 0.0f, 0);9192if (meas_cnt == tgt_cnt && meas_cnt != 0) {93if (tgt_ampl > 0.0f) {94sum_gain += meas_ampl / tgt_ampl;95gcnt++;96}97float d_time = (float)(meas_time - tgt_time);98if (d_time < 2.0f * (float)cycle_time_ms) {99delta_time += d_time;100cnt++;101}102} else if (meas_cnt > tgt_cnt) {103pull_from_tgt_buffer(tgt_cnt, tgt_ampl, tgt_time);104push_to_tgt_buffer(0, 0.0f, 0);105} else if (meas_cnt < tgt_cnt) {106pull_from_meas_buffer(meas_cnt, meas_ampl, meas_time);107push_to_meas_buffer(0, 0.0f, 0);108}109}110if (gcnt > 0) {111curr_test_gain = sum_gain / gcnt;112}113if (cnt > 0) {114delta_time = delta_time / cnt;115}116curr_test_phase = tgt_freq * delta_time * 0.001f * 360.0f / M_2PI;117if (curr_test_phase > 360.0f) {118curr_test_phase = curr_test_phase - 360.0f;119}120121// determine max accel for angle response type test122float dwell_max_accel;123if (response == ANGLE) {124dwell_max_accel = tgt_freq * max_meas_rate * 5730.0f;125if (!is_zero(max_command)) {126// normalize accel for input size127dwell_max_accel = dwell_max_accel / (2.0f * max_command);128}129if (dwell_max_accel > max_accel) {130max_accel = dwell_max_accel;131}132}133134curr_test_freq = tgt_freq;135cycle_complete = true;136return;137}138139// Indicates when the target(input) is positive or negative half of the cycle to notify when the max or min should be sought140if (((response == ANGLE && is_positive(prev_target) && !is_positive(target_rate))141|| (response == RATE && !is_positive(prev_target) && is_positive(target_rate)))142&& !new_target && now > new_tgt_time_ms) {143new_target = true;144new_tgt_time_ms = now + half_cycle_time_ms;145// reset max_target146max_target = 0.0f;147max_target_cnt++;148temp_min_target = min_target;149if (min_target_cnt > 0) {150sweep_tgt.max_time_m1 = temp_max_tgt_time;151temp_max_tgt_time = max_tgt_time;152sweep_tgt.count_m1 = min_target_cnt - 1;153sweep_tgt.amplitude_m1 = temp_tgt_ampl;154temp_tgt_ampl = temp_max_target - temp_min_target;155if (excitation == DWELL) {156push_to_tgt_buffer(min_target_cnt,temp_tgt_ampl,temp_max_tgt_time);157}158}159160} else if (((response == ANGLE && !is_positive(prev_target) && is_positive(target_rate))161|| (response == RATE && is_positive(prev_target) && !is_positive(target_rate)))162&& new_target && now > new_tgt_time_ms && max_target_cnt > 0) {163new_target = false;164new_tgt_time_ms = now + half_cycle_time_ms;165min_target_cnt++;166temp_max_target = max_target;167min_target = 0.0f;168}169170// Indicates when the measured value (output) is positive or negative half of the cycle to notify when the max or min should be sought171if (((response == ANGLE && is_positive(prev_meas) && !is_positive(measured_rate))172|| (response == RATE && !is_positive(prev_meas) && is_positive(measured_rate)))173&& !new_meas && now > new_meas_time_ms && max_target_cnt > 0) {174new_meas = true;175new_meas_time_ms = now + half_cycle_time_ms;176// reset max_meas177max_meas = 0.0f;178max_meas_cnt++;179temp_min_meas = min_meas;180if (min_meas_cnt > 0 && min_target_cnt > 0) {181sweep_meas.max_time_m1 = temp_max_meas_time;182temp_max_meas_time = max_meas_time;183sweep_meas.count_m1 = min_meas_cnt - 1;184sweep_meas.amplitude_m1 = temp_meas_ampl;185temp_meas_ampl = temp_max_meas - temp_min_meas;186if (excitation == DWELL) {187push_to_meas_buffer(min_meas_cnt,temp_meas_ampl,temp_max_meas_time);188}189if (excitation == SWEEP) {190float tgt_period = 0.001f * (temp_max_tgt_time - sweep_tgt.max_time_m1);191if (!is_zero(tgt_period)) {192curr_test_freq = M_2PI / tgt_period;193} else {194curr_test_freq = 0.0f;195}196if (!is_zero(sweep_tgt.amplitude_m1)) {197curr_test_gain = sweep_meas.amplitude_m1/sweep_tgt.amplitude_m1;198} else {199curr_test_gain = 0.0f;200}201curr_test_phase = curr_test_freq * (float)(sweep_meas.max_time_m1 - sweep_tgt.max_time_m1) * 0.001f * 360.0f / M_2PI;202cycle_complete = true;203}204}205} else if (((response == ANGLE && !is_positive(prev_meas) && is_positive(measured_rate))206|| (response == RATE && is_positive(prev_meas) && !is_positive(measured_rate)))207&& new_meas && now > new_meas_time_ms && max_meas_cnt > 0) {208new_meas = false;209new_meas_time_ms = now + half_cycle_time_ms;210min_meas_cnt++;211temp_max_meas = max_meas;212min_meas = 0.0f;213}214215if (new_target) {216if (tgt_resp > max_target) {217max_target = tgt_resp;218max_tgt_time = now;219}220} else {221if (tgt_resp < min_target) {222min_target = tgt_resp;223}224}225226if (new_meas) {227if (meas_resp > max_meas) {228max_meas = meas_resp;229max_meas_time = now;230}231} else {232if (meas_resp < min_meas) {233min_meas = meas_resp;234}235}236237if (response == ANGLE) {238if (now > (uint32_t)(input_start_time_ms + 7.0f * cycle_time_ms) && now < (uint32_t)(input_start_time_ms + 9.0f * cycle_time_ms)) {239if (measured_rate > max_meas_rate) {240max_meas_rate = measured_rate;241}242if (command > max_command) {243max_command = command;244}245}246prev_tgt_resp = tgt_resp;247prev_meas_resp = meas_resp;248}249250prev_target = target_rate;251prev_meas = measured_rate;252}253254// push measured peak info to buffer255void AC_AutoTune_FreqResp::push_to_meas_buffer(uint16_t count, float amplitude, uint32_t time_ms)256{257peak_info sample;258sample.curr_count = count;259sample.amplitude = amplitude;260sample.time_ms = time_ms;261meas_peak_info_buffer.push(sample);262}263264// pull measured peak info from buffer265void AC_AutoTune_FreqResp::pull_from_meas_buffer(uint16_t &count, float &litude, uint32_t &time_ms)266{267peak_info sample;268if (!meas_peak_info_buffer.pop(sample)) {269// no sample270return;271}272count = sample.curr_count;273amplitude = sample.amplitude;274time_ms = sample.time_ms;275}276277// push target peak info to buffer278void AC_AutoTune_FreqResp::push_to_tgt_buffer(uint16_t count, float amplitude, uint32_t time_ms)279{280peak_info sample;281sample.curr_count = count;282sample.amplitude = amplitude;283sample.time_ms = time_ms;284tgt_peak_info_buffer.push(sample);285}286287// pull target peak info from buffer288void AC_AutoTune_FreqResp::pull_from_tgt_buffer(uint16_t &count, float &litude, uint32_t &time_ms)289{290peak_info sample;291if (!tgt_peak_info_buffer.pop(sample)) {292// no sample293return;294}295count = sample.curr_count;296amplitude = sample.amplitude;297time_ms = sample.time_ms;298}299300301302