CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AC_AutoTune/AC_AutoTune_FreqResp.cpp
Views: 1798
1
/*
2
This 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.
3
*/
4
5
#include <AP_HAL/AP_HAL.h>
6
#include "AC_AutoTune_FreqResp.h"
7
8
// Initialize the Frequency Response Object. Must be called before running dwell or frequency sweep tests
9
void AC_AutoTune_FreqResp::init(InputType input_type, ResponseType response_type, uint8_t cycles)
10
{
11
excitation = input_type;
12
response = response_type;
13
max_target_cnt = 0;
14
min_target_cnt = 0;
15
max_meas_cnt = 0;
16
min_meas_cnt = 0;
17
input_start_time_ms = 0;
18
new_tgt_time_ms = 0;
19
new_meas_time_ms = 0;
20
new_target = false;
21
new_meas = false;
22
curr_test_freq = 0.0f;
23
curr_test_gain = 0.0f;
24
curr_test_phase = 0.0f;
25
max_accel = 0.0f;
26
max_meas_rate = 0.0f;
27
max_command = 0.0f;
28
dwell_cycles = cycles;
29
meas_peak_info_buffer.clear();
30
tgt_peak_info_buffer.clear();
31
cycle_complete = false;
32
}
33
34
// update_angle - this function receives time history data during a dwell and frequency sweep tests for angle_p tuning
35
// and determines the gain, phase, and max acceleration of the response to the input. For dwell tests once the designated number
36
// of cycles are complete, the average of the gain, phase, and max acceleration are determined over the last 5 cycles and the
37
// cycles_complete flag is set. For frequency sweep tests, phase and gain are determined for every cycle and cycle_complete flag is set
38
// to indicate when to pull the phase and gain data. The flag is reset to enable the next cycle to be analyzed.
39
void AC_AutoTune_FreqResp::update(float command, float tgt_resp, float meas_resp, float tgt_freq)
40
{
41
42
uint32_t now = AP_HAL::millis();
43
float dt = 0.0025;
44
uint32_t half_cycle_time_ms = 0;
45
uint32_t cycle_time_ms = 0;
46
47
if (cycle_complete) {
48
return;
49
}
50
51
if (!is_zero(tgt_freq)) {
52
half_cycle_time_ms = (uint32_t)(300 * M_2PI / tgt_freq);
53
cycle_time_ms = (uint32_t)(1000 * M_2PI / tgt_freq);
54
}
55
56
if (input_start_time_ms == 0) {
57
input_start_time_ms = now;
58
if (response == ANGLE) {
59
prev_tgt_resp = tgt_resp;
60
prev_meas_resp = meas_resp;
61
prev_target = 0.0f;
62
prev_meas = 0.0f;
63
}
64
}
65
66
if (response == ANGLE) {
67
target_rate = (tgt_resp - prev_tgt_resp) / dt;
68
measured_rate = (meas_resp - prev_meas_resp) / dt;
69
} else {
70
target_rate = tgt_resp;
71
measured_rate = meas_resp;
72
}
73
74
// cycles are complete! determine gain and phase and exit
75
if (max_meas_cnt > dwell_cycles + 1 && max_target_cnt > dwell_cycles + 1 && excitation == DWELL) {
76
float delta_time = 0.0f;
77
float sum_gain = 0.0f;
78
uint8_t cnt = 0;
79
uint8_t gcnt = 0;
80
uint16_t meas_cnt, tgt_cnt;
81
float meas_ampl = 0.0f;
82
float tgt_ampl = 0.0f;
83
uint32_t meas_time = 0;
84
uint32_t tgt_time = 0;
85
for (uint8_t i = 0; i < dwell_cycles; i++) {
86
meas_cnt=0;
87
tgt_cnt=0;
88
pull_from_meas_buffer(meas_cnt, meas_ampl, meas_time);
89
pull_from_tgt_buffer(tgt_cnt, tgt_ampl, tgt_time);
90
push_to_meas_buffer(0, 0.0f, 0);
91
push_to_tgt_buffer(0, 0.0f, 0);
92
93
if (meas_cnt == tgt_cnt && meas_cnt != 0) {
94
if (tgt_ampl > 0.0f) {
95
sum_gain += meas_ampl / tgt_ampl;
96
gcnt++;
97
}
98
float d_time = (float)(meas_time - tgt_time);
99
if (d_time < 2.0f * (float)cycle_time_ms) {
100
delta_time += d_time;
101
cnt++;
102
}
103
} else if (meas_cnt > tgt_cnt) {
104
pull_from_tgt_buffer(tgt_cnt, tgt_ampl, tgt_time);
105
push_to_tgt_buffer(0, 0.0f, 0);
106
} else if (meas_cnt < tgt_cnt) {
107
pull_from_meas_buffer(meas_cnt, meas_ampl, meas_time);
108
push_to_meas_buffer(0, 0.0f, 0);
109
}
110
}
111
if (gcnt > 0) {
112
curr_test_gain = sum_gain / gcnt;
113
}
114
if (cnt > 0) {
115
delta_time = delta_time / cnt;
116
}
117
curr_test_phase = tgt_freq * delta_time * 0.001f * 360.0f / M_2PI;
118
if (curr_test_phase > 360.0f) {
119
curr_test_phase = curr_test_phase - 360.0f;
120
}
121
122
// determine max accel for angle response type test
123
float dwell_max_accel;
124
if (response == ANGLE) {
125
dwell_max_accel = tgt_freq * max_meas_rate * 5730.0f;
126
if (!is_zero(max_command)) {
127
// normalize accel for input size
128
dwell_max_accel = dwell_max_accel / (2.0f * max_command);
129
}
130
if (dwell_max_accel > max_accel) {
131
max_accel = dwell_max_accel;
132
}
133
}
134
135
curr_test_freq = tgt_freq;
136
cycle_complete = true;
137
return;
138
}
139
140
// Indicates when the target(input) is positive or negative half of the cycle to notify when the max or min should be sought
141
if (((response == ANGLE && is_positive(prev_target) && !is_positive(target_rate))
142
|| (response == RATE && !is_positive(prev_target) && is_positive(target_rate)))
143
&& !new_target && now > new_tgt_time_ms) {
144
new_target = true;
145
new_tgt_time_ms = now + half_cycle_time_ms;
146
// reset max_target
147
max_target = 0.0f;
148
max_target_cnt++;
149
temp_min_target = min_target;
150
if (min_target_cnt > 0) {
151
sweep_tgt.max_time_m1 = temp_max_tgt_time;
152
temp_max_tgt_time = max_tgt_time;
153
sweep_tgt.count_m1 = min_target_cnt - 1;
154
sweep_tgt.amplitude_m1 = temp_tgt_ampl;
155
temp_tgt_ampl = temp_max_target - temp_min_target;
156
if (excitation == DWELL) {
157
push_to_tgt_buffer(min_target_cnt,temp_tgt_ampl,temp_max_tgt_time);
158
}
159
}
160
161
} else if (((response == ANGLE && !is_positive(prev_target) && is_positive(target_rate))
162
|| (response == RATE && is_positive(prev_target) && !is_positive(target_rate)))
163
&& new_target && now > new_tgt_time_ms && max_target_cnt > 0) {
164
new_target = false;
165
new_tgt_time_ms = now + half_cycle_time_ms;
166
min_target_cnt++;
167
temp_max_target = max_target;
168
min_target = 0.0f;
169
}
170
171
// Indicates when the measured value (output) is positive or negative half of the cycle to notify when the max or min should be sought
172
if (((response == ANGLE && is_positive(prev_meas) && !is_positive(measured_rate))
173
|| (response == RATE && !is_positive(prev_meas) && is_positive(measured_rate)))
174
&& !new_meas && now > new_meas_time_ms && max_target_cnt > 0) {
175
new_meas = true;
176
new_meas_time_ms = now + half_cycle_time_ms;
177
// reset max_meas
178
max_meas = 0.0f;
179
max_meas_cnt++;
180
temp_min_meas = min_meas;
181
if (min_meas_cnt > 0 && min_target_cnt > 0) {
182
sweep_meas.max_time_m1 = temp_max_meas_time;
183
temp_max_meas_time = max_meas_time;
184
sweep_meas.count_m1 = min_meas_cnt - 1;
185
sweep_meas.amplitude_m1 = temp_meas_ampl;
186
temp_meas_ampl = temp_max_meas - temp_min_meas;
187
if (excitation == DWELL) {
188
push_to_meas_buffer(min_meas_cnt,temp_meas_ampl,temp_max_meas_time);
189
}
190
if (excitation == SWEEP) {
191
float tgt_period = 0.001f * (temp_max_tgt_time - sweep_tgt.max_time_m1);
192
if (!is_zero(tgt_period)) {
193
curr_test_freq = M_2PI / tgt_period;
194
} else {
195
curr_test_freq = 0.0f;
196
}
197
if (!is_zero(sweep_tgt.amplitude_m1)) {
198
curr_test_gain = sweep_meas.amplitude_m1/sweep_tgt.amplitude_m1;
199
} else {
200
curr_test_gain = 0.0f;
201
}
202
curr_test_phase = curr_test_freq * (float)(sweep_meas.max_time_m1 - sweep_tgt.max_time_m1) * 0.001f * 360.0f / M_2PI;
203
cycle_complete = true;
204
}
205
}
206
} else if (((response == ANGLE && !is_positive(prev_meas) && is_positive(measured_rate))
207
|| (response == RATE && is_positive(prev_meas) && !is_positive(measured_rate)))
208
&& new_meas && now > new_meas_time_ms && max_meas_cnt > 0) {
209
new_meas = false;
210
new_meas_time_ms = now + half_cycle_time_ms;
211
min_meas_cnt++;
212
temp_max_meas = max_meas;
213
min_meas = 0.0f;
214
}
215
216
if (new_target) {
217
if (tgt_resp > max_target) {
218
max_target = tgt_resp;
219
max_tgt_time = now;
220
}
221
} else {
222
if (tgt_resp < min_target) {
223
min_target = tgt_resp;
224
}
225
}
226
227
if (new_meas) {
228
if (meas_resp > max_meas) {
229
max_meas = meas_resp;
230
max_meas_time = now;
231
}
232
} else {
233
if (meas_resp < min_meas) {
234
min_meas = meas_resp;
235
}
236
}
237
238
if (response == ANGLE) {
239
if (now > (uint32_t)(input_start_time_ms + 7.0f * cycle_time_ms) && now < (uint32_t)(input_start_time_ms + 9.0f * cycle_time_ms)) {
240
if (measured_rate > max_meas_rate) {
241
max_meas_rate = measured_rate;
242
}
243
if (command > max_command) {
244
max_command = command;
245
}
246
}
247
prev_tgt_resp = tgt_resp;
248
prev_meas_resp = meas_resp;
249
}
250
251
prev_target = target_rate;
252
prev_meas = measured_rate;
253
}
254
255
// push measured peak info to buffer
256
void AC_AutoTune_FreqResp::push_to_meas_buffer(uint16_t count, float amplitude, uint32_t time_ms)
257
{
258
peak_info sample;
259
sample.curr_count = count;
260
sample.amplitude = amplitude;
261
sample.time_ms = time_ms;
262
meas_peak_info_buffer.push(sample);
263
}
264
265
// pull measured peak info from buffer
266
void AC_AutoTune_FreqResp::pull_from_meas_buffer(uint16_t &count, float &amplitude, uint32_t &time_ms)
267
{
268
peak_info sample;
269
if (!meas_peak_info_buffer.pop(sample)) {
270
// no sample
271
return;
272
}
273
count = sample.curr_count;
274
amplitude = sample.amplitude;
275
time_ms = sample.time_ms;
276
}
277
278
// push target peak info to buffer
279
void AC_AutoTune_FreqResp::push_to_tgt_buffer(uint16_t count, float amplitude, uint32_t time_ms)
280
{
281
peak_info sample;
282
sample.curr_count = count;
283
sample.amplitude = amplitude;
284
sample.time_ms = time_ms;
285
tgt_peak_info_buffer.push(sample);
286
}
287
288
// pull target peak info from buffer
289
void AC_AutoTune_FreqResp::pull_from_tgt_buffer(uint16_t &count, float &amplitude, uint32_t &time_ms)
290
{
291
peak_info sample;
292
if (!tgt_peak_info_buffer.pop(sample)) {
293
// no sample
294
return;
295
}
296
count = sample.curr_count;
297
amplitude = sample.amplitude;
298
time_ms = sample.time_ms;
299
}
300
301
302