-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathmode_systemid.cpp
335 lines (288 loc) · 12.9 KB
/
mode_systemid.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
#include "Copter.h"
#if MODE_SYSTEMID_ENABLED == ENABLED
/*
* Init and run calls for systemId, flight mode
*/
const AP_Param::GroupInfo ModeSystemId::var_info[] = {
// @Param: _AXIS
// @DisplayName: System identification axis
// @Description: Controls which axis are being excited. Set to non-zero to see more parameters
// @User: Standard
// @Values: 0:None, 1:Input Roll Angle, 2:Input Pitch Angle, 3:Input Yaw Angle, 4:Recovery Roll Angle, 5:Recovery Pitch Angle, 6:Recovery Yaw Angle, 7:Rate Roll, 8:Rate Pitch, 9:Rate Yaw, 10:Mixer Roll, 11:Mixer Pitch, 12:Mixer Yaw, 13:Mixer Thrust
AP_GROUPINFO_FLAGS("_AXIS", 1, ModeSystemId, axis, 0, AP_PARAM_FLAG_ENABLE),
// @Param: _MAGNITUDE
// @DisplayName: System identification Chirp Magnitude
// @Description: Magnitude of sweep in deg, deg/s and 0-1 for mixer outputs.
// @User: Standard
AP_GROUPINFO("_MAGNITUDE", 2, ModeSystemId, waveform_magnitude, 15),
// @Param: _F_START_HZ
// @DisplayName: System identification Start Frequency
// @Description: Frequency at the start of the sweep
// @Range: 0.01 100
// @Units: Hz
// @User: Standard
AP_GROUPINFO("_F_START_HZ", 3, ModeSystemId, frequency_start, 0.5f),
// @Param: _F_STOP_HZ
// @DisplayName: System identification Stop Frequency
// @Description: Frequency at the end of the sweep
// @Range: 0.01 100
// @Units: Hz
// @User: Standard
AP_GROUPINFO("_F_STOP_HZ", 4, ModeSystemId, frequency_stop, 40),
// @Param: _T_FADE_IN
// @DisplayName: System identification Fade in time
// @Description: Time to reach maximum amplitude of sweep
// @Range: 0 20
// @Units: s
// @User: Standard
AP_GROUPINFO("_T_FADE_IN", 5, ModeSystemId, time_fade_in, 15),
// @Param: _T_REC
// @DisplayName: System identification Total Sweep length
// @Description: Time taken to complete the sweep
// @Range: 0 255
// @Units: s
// @User: Standard
AP_GROUPINFO("_T_REC", 6, ModeSystemId, time_record, 70),
// @Param: _T_FADE_OUT
// @DisplayName: System identification Fade out time
// @Description: Time to reach zero amplitude at the end of the sweep
// @Range: 0 5
// @Units: s
// @User: Standard
AP_GROUPINFO("_T_FADE_OUT", 7, ModeSystemId, time_fade_out, 2),
AP_GROUPEND
};
ModeSystemId::ModeSystemId(void) : Mode()
{
AP_Param::setup_object_defaults(this, var_info);
}
#define SYSTEM_ID_DELAY 1.0f // speed below which it is always safe to switch to loiter
// systemId_init - initialise systemId controller
bool ModeSystemId::init(bool ignore_checks)
{
// check if enabled
if (axis == 0) {
gcs().send_text(MAV_SEVERITY_WARNING, "No axis selected, SID_AXIS = 0");
return false;
}
// if landed and the mode we're switching from does not have manual throttle and the throttle stick is too high
if (motors->armed() && copter.ap.land_complete && !copter.flightmode->has_manual_throttle()) {
return false;
}
#if FRAME_CONFIG == HELI_FRAME
copter.input_manager.set_use_stab_col(true);
#endif
att_bf_feedforward = attitude_control->get_bf_feedforward();
waveform_time = 0.0f;
time_const_freq = 2.0f / frequency_start; // Two full cycles at the starting frequency
systemid_state = SystemIDModeState::SYSTEMID_STATE_TESTING;
log_subsample = 0;
gcs().send_text(MAV_SEVERITY_INFO, "SystemID Starting: axis=%d", (unsigned)axis);
copter.Log_Write_SysID_Setup(axis, waveform_magnitude, frequency_start, frequency_stop, time_fade_in, time_const_freq, time_record, time_fade_out);
return true;
}
// systemId_run - runs the systemId controller
// should be called at 100hz or more
void ModeSystemId::run()
{
// apply simple mode transform to pilot inputs
update_simple_mode();
// convert pilot input to lean angles
float target_roll, target_pitch;
get_pilot_desired_lean_angles(target_roll, target_pitch, copter.aparm.angle_max, copter.aparm.angle_max);
// get pilot's desired yaw rate
float target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
if (!motors->armed()) {
// Motors should be Stopped
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN);
// Tradheli doesn't set spool state to ground idle when throttle stick is zero. Ground idle only set when
// motor interlock is disabled.
} else if (copter.ap.throttle_zero && !copter.is_tradheli()) {
// Attempting to Land
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
} else {
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
}
switch (motors->get_spool_state()) {
case AP_Motors::SpoolState::SHUT_DOWN:
// Motors Stopped
attitude_control->set_yaw_target_to_current_heading();
attitude_control->reset_rate_controller_I_terms();
break;
case AP_Motors::SpoolState::GROUND_IDLE:
// Landed
// Tradheli initializes targets when going from disarmed to armed state.
// init_targets_on_arming is always set true for multicopter.
if (motors->init_targets_on_arming()) {
attitude_control->set_yaw_target_to_current_heading();
attitude_control->reset_rate_controller_I_terms();
}
break;
case AP_Motors::SpoolState::THROTTLE_UNLIMITED:
// clear landing flag above zero throttle
if (!motors->limit.throttle_lower) {
set_land_complete(false);
}
break;
case AP_Motors::SpoolState::SPOOLING_UP:
case AP_Motors::SpoolState::SPOOLING_DOWN:
// do nothing
break;
}
// get pilot's desired throttle
#if FRAME_CONFIG == HELI_FRAME
float pilot_throttle_scaled = copter.input_manager.get_pilot_desired_collective(channel_throttle->get_control_in());
#else
float pilot_throttle_scaled = get_pilot_desired_throttle();
#endif
if ((systemid_state == SystemIDModeState::SYSTEMID_STATE_TESTING) &&
(!is_positive(frequency_start) || !is_positive(frequency_stop) || is_negative(time_fade_in) || !is_positive(time_record) || is_negative(time_fade_out) || (time_record <= time_const_freq))) {
systemid_state = SystemIDModeState::SYSTEMID_STATE_STOPPED;
gcs().send_text(MAV_SEVERITY_INFO, "SystemID Parameter Error");
}
waveform_time += G_Dt;
waveform_sample = waveform(waveform_time - SYSTEM_ID_DELAY);
switch (systemid_state) {
case SystemIDModeState::SYSTEMID_STATE_STOPPED:
break;
case SystemIDModeState::SYSTEMID_STATE_TESTING:
attitude_control->bf_feedforward(att_bf_feedforward);
if (copter.ap.land_complete) {
systemid_state = SystemIDModeState::SYSTEMID_STATE_STOPPED;
gcs().send_text(MAV_SEVERITY_INFO, "SystemID Stopped: Landed");
break;
}
if (attitude_control->lean_angle()*100 > attitude_control->lean_angle_max()) {
systemid_state = SystemIDModeState::SYSTEMID_STATE_STOPPED;
gcs().send_text(MAV_SEVERITY_INFO, "SystemID Stopped: lean=%f max=%f", (double)attitude_control->lean_angle(), (double)attitude_control->lean_angle_max());
break;
}
if (waveform_time > SYSTEM_ID_DELAY + time_fade_in + time_const_freq + time_record + time_fade_out) {
systemid_state = SystemIDModeState::SYSTEMID_STATE_STOPPED;
gcs().send_text(MAV_SEVERITY_INFO, "SystemID Finished");
break;
}
switch ((AxisType)axis.get()) {
case AxisType::NONE:
systemid_state = SystemIDModeState::SYSTEMID_STATE_STOPPED;
gcs().send_text(MAV_SEVERITY_INFO, "SystemID Stopped: axis = 0");
break;
case AxisType::INPUT_ROLL:
target_roll += waveform_sample*100.0f;
break;
case AxisType::INPUT_PITCH:
target_pitch += waveform_sample*100.0f;
break;
case AxisType::INPUT_YAW:
target_yaw_rate += waveform_sample*100.0f;
break;
case AxisType::RECOVER_ROLL:
target_roll += waveform_sample*100.0f;
attitude_control->bf_feedforward(false);
break;
case AxisType::RECOVER_PITCH:
target_pitch += waveform_sample*100.0f;
attitude_control->bf_feedforward(false);
break;
case AxisType::RECOVER_YAW:
target_yaw_rate += waveform_sample*100.0f;
attitude_control->bf_feedforward(false);
break;
case AxisType::RATE_ROLL:
attitude_control->rate_bf_roll_sysid(radians(waveform_sample));
break;
case AxisType::RATE_PITCH:
attitude_control->rate_bf_pitch_sysid(radians(waveform_sample));
break;
case AxisType::RATE_YAW:
attitude_control->rate_bf_yaw_sysid(radians(waveform_sample));
break;
case AxisType::MIX_ROLL:
attitude_control->actuator_roll_sysid(waveform_sample);
break;
case AxisType::MIX_PITCH:
attitude_control->actuator_pitch_sysid(waveform_sample);
break;
case AxisType::MIX_YAW:
attitude_control->actuator_yaw_sysid(waveform_sample);
break;
case AxisType::MIX_THROTTLE:
pilot_throttle_scaled += waveform_sample;
break;
}
break;
}
// call attitude controller
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
// output pilot's throttle
if (copter.is_tradheli()) {
attitude_control->set_throttle_out(pilot_throttle_scaled, false, g.throttle_filt);
} else {
attitude_control->set_throttle_out(pilot_throttle_scaled, true, g.throttle_filt);
}
if (log_subsample <= 0) {
log_data();
if (copter.should_log(MASK_LOG_ATTITUDE_FAST) && copter.should_log(MASK_LOG_ATTITUDE_MED)) {
log_subsample = 1;
} else if (copter.should_log(MASK_LOG_ATTITUDE_FAST)) {
log_subsample = 2;
} else if (copter.should_log(MASK_LOG_ATTITUDE_MED)) {
log_subsample = 4;
} else {
log_subsample = 8;
}
}
log_subsample -= 1;
}
// log system id and attitude
void ModeSystemId::log_data()
{
uint8_t index = copter.ahrs.get_primary_gyro_index();
Vector3f delta_angle;
copter.ins.get_delta_angle(index, delta_angle);
float delta_angle_dt = copter.ins.get_delta_angle_dt(index);
index = copter.ahrs.get_primary_accel_index();
Vector3f delta_velocity;
copter.ins.get_delta_velocity(index, delta_velocity);
float delta_velocity_dt = copter.ins.get_delta_velocity_dt(index);
if (is_positive(delta_angle_dt) && is_positive(delta_velocity_dt)) {
copter.Log_Write_SysID_Data(waveform_time, waveform_sample, waveform_freq_rads / (2 * M_PI), degrees(delta_angle.x / delta_angle_dt), degrees(delta_angle.y / delta_angle_dt), degrees(delta_angle.z / delta_angle_dt), delta_velocity.x / delta_velocity_dt, delta_velocity.y / delta_velocity_dt, delta_velocity.z / delta_velocity_dt);
}
// Full rate logging of attitude, rate and pid loops
copter.Log_Write_Attitude();
}
// init_test - initialises the test
float ModeSystemId::waveform(float time)
{
float wMin = 2 * M_PI * frequency_start;
float wMax = 2 * M_PI * frequency_stop;
float window;
float output;
float B = logf(wMax / wMin);
if (time <= 0.0f) {
window = 0.0f;
} else if (time <= time_fade_in) {
window = 0.5 - 0.5 * cosf(M_PI * time / time_fade_in);
} else if (time <= time_record - time_fade_out) {
window = 1.0;
} else if (time <= time_record) {
window = 0.5 - 0.5 * cosf(M_PI * (time - (time_record - time_fade_out)) / time_fade_out + M_PI);
} else {
window = 0.0;
}
if (time <= 0.0f) {
waveform_freq_rads = wMin;
output = 0.0f;
} else if (time <= time_const_freq) {
waveform_freq_rads = wMin;
output = window * waveform_magnitude * sinf(wMin * time - wMin * time_const_freq);
} else if (time <= time_record) {
waveform_freq_rads = wMin * expf(B * (time - time_const_freq) / (time_record - time_const_freq));
output = window * waveform_magnitude * sinf((wMin * (time_record - time_const_freq) / B) * (expf(B * (time - time_const_freq) / (time_record - time_const_freq)) - 1));
} else {
waveform_freq_rads = wMax;
output = 0.0f;
}
return output;
}
#endif