mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AC_AutoTune: adding comments to FreqResp Library
This commit is contained in:
parent
c757de153d
commit
6cdf3b9109
@ -13,6 +13,7 @@ float AC_AutoTune_FreqResp::update()
|
||||
return dummy;
|
||||
}
|
||||
|
||||
// Initialize the Frequency Response methods. Must be called before running dwell or frequency sweep tests
|
||||
void AC_AutoTune_FreqResp::init(InputType input_type)
|
||||
{
|
||||
excitation = input_type;
|
||||
@ -36,9 +37,12 @@ void AC_AutoTune_FreqResp::init(InputType input_type)
|
||||
cycle_complete = false;
|
||||
}
|
||||
|
||||
// determine_gain - this function receives time history data during a dwell test input and determines the gain and phase of the response to the input.
|
||||
// Once the designated number of cycles are complete, the average of the gain and phase are determined over the last 5 cycles and the cycles_complete flag
|
||||
// is set. This function must be reset using the reset flag prior to the next dwell.
|
||||
// determine_gain - this function receives time history data during a dwell and frequency sweep tests for max gain,
|
||||
// rate P and rate D tuning 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 cycles_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.
|
||||
void AC_AutoTune_FreqResp::determine_gain(float tgt_rate, float meas_rate, float tgt_freq)
|
||||
{
|
||||
uint32_t now = AP_HAL::millis();
|
||||
@ -205,9 +209,11 @@ void AC_AutoTune_FreqResp::determine_gain(float tgt_rate, float meas_rate, float
|
||||
prev_meas = meas_rate;
|
||||
}
|
||||
|
||||
// determine_gain_angle - this function receives time history data during a dwell test input and determines the gain and phase of the response to the input.
|
||||
// Once the designated number of cycles are complete, the average of the gain and phase are determined over the last 5 cycles and the cycles_complete flag
|
||||
// is set. This function must be reset using the reset flag prior to the next dwell.
|
||||
// determine_gain_angle - this function receives time history data during a dwell and frequency sweep tests for angle_p tuning
|
||||
// and determines the gain, phase, and max acceleration of the response to the input. For dwell tests once the designated number
|
||||
// of cycles are complete, the average of the gain, phase, and max acceleration are determined over the last 5 cycles and the
|
||||
// cycles_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.
|
||||
void AC_AutoTune_FreqResp::determine_gain_angle(float command, float tgt_angle, float meas_angle, float tgt_freq)
|
||||
{
|
||||
|
||||
@ -402,7 +408,7 @@ void AC_AutoTune_FreqResp::determine_gain_angle(float command, float tgt_angle,
|
||||
prev_meas_angle = meas_angle;
|
||||
}
|
||||
|
||||
// push to peak info buffer
|
||||
// push measured peak info to buffer
|
||||
void AC_AutoTune_FreqResp::push_to_meas_buffer(uint16_t count, float amplitude, uint32_t time_ms)
|
||||
{
|
||||
peak_info sample;
|
||||
@ -412,7 +418,7 @@ void AC_AutoTune_FreqResp::push_to_meas_buffer(uint16_t count, float amplitude,
|
||||
meas_peak_info_buffer->push(sample);
|
||||
}
|
||||
|
||||
// pull from peak info buffer
|
||||
// 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;
|
||||
@ -425,7 +431,7 @@ void AC_AutoTune_FreqResp::pull_from_meas_buffer(uint16_t &count, float &litu
|
||||
time_ms = sample.time_ms;
|
||||
}
|
||||
|
||||
// push to peak info buffer
|
||||
// push target peak info to buffer
|
||||
void AC_AutoTune_FreqResp::push_to_tgt_buffer(uint16_t count, float amplitude, uint32_t time_ms)
|
||||
{
|
||||
peak_info sample;
|
||||
@ -436,7 +442,7 @@ void AC_AutoTune_FreqResp::push_to_tgt_buffer(uint16_t count, float amplitude, u
|
||||
|
||||
}
|
||||
|
||||
// pull from peak info buffer
|
||||
// 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;
|
||||
|
Loading…
Reference in New Issue
Block a user