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_Autorotation/AC_Autorotation.cpp
Views: 1798
1
#include "AC_Autorotation.h"
2
#include <AP_Logger/AP_Logger.h>
3
#include <AP_RPM/AP_RPM.h>
4
#include <AP_AHRS/AP_AHRS.h>
5
6
// Autorotation controller defaults
7
// Head Speed (HS) controller specific default definitions
8
#define HS_CONTROLLER_COLLECTIVE_CUTOFF_FREQ 2.0f // low-pass filter on accel error (unit: hz)
9
#define HS_CONTROLLER_HEADSPEED_P 0.7f // Default P gain for head speed controller (unit: -)
10
#define HS_CONTROLLER_ENTRY_COL_FILTER 0.7f // Default low pass filter frequency during the entry phase (unit: Hz)
11
#define HS_CONTROLLER_GLIDE_COL_FILTER 0.1f // Default low pass filter frequency during the glide phase (unit: Hz)
12
13
// Speed Height controller specific default definitions for autorotation use
14
#define FWD_SPD_CONTROLLER_GND_SPEED_TARGET 1100 // Default target ground speed for speed height controller (unit: cm/s)
15
#define FWD_SPD_CONTROLLER_MAX_ACCEL 60 // Default acceleration limit for speed height controller (unit: cm/s/s)
16
#define AP_FW_VEL_P 0.9f
17
#define AP_FW_VEL_FF 0.15f
18
19
20
const AP_Param::GroupInfo AC_Autorotation::var_info[] = {
21
22
// @Param: ENABLE
23
// @DisplayName: Enable settings for RSC Setpoint
24
// @Description: Allows you to enable (1) or disable (0) the autonomous autorotation capability.
25
// @Values: 0:Disabled,1:Enabled
26
// @User: Advanced
27
AP_GROUPINFO_FLAGS("ENABLE", 1, AC_Autorotation, _param_enable, 0, AP_PARAM_FLAG_ENABLE),
28
29
// @Param: HS_P
30
// @DisplayName: P gain for head speed controller
31
// @Description: Increase value to increase sensitivity of head speed controller during autonomous autorotation.
32
// @Range: 0.3 1
33
// @Increment: 0.01
34
// @User: Advanced
35
AP_SUBGROUPINFO(_p_hs, "HS_", 2, AC_Autorotation, AC_P),
36
37
// @Param: HS_SET_PT
38
// @DisplayName: Target Head Speed
39
// @Description: The target head speed in RPM during autorotation. Start by setting to desired hover speed and tune from there as necessary.
40
// @Units: RPM
41
// @Range: 1000 2800
42
// @Increment: 1
43
// @User: Advanced
44
AP_GROUPINFO("HS_SET_PT", 3, AC_Autorotation, _param_head_speed_set_point, 1500),
45
46
// @Param: TARG_SP
47
// @DisplayName: Target Glide Ground Speed
48
// @Description: Target ground speed in cm/s for the autorotation controller to try and achieve/ maintain during the glide phase.
49
// @Units: cm/s
50
// @Range: 800 2000
51
// @Increment: 50
52
// @User: Advanced
53
AP_GROUPINFO("TARG_SP", 4, AC_Autorotation, _param_target_speed, FWD_SPD_CONTROLLER_GND_SPEED_TARGET),
54
55
// @Param: COL_FILT_E
56
// @DisplayName: Entry Phase Collective Filter
57
// @Description: Cut-off frequency for collective low pass filter. For the entry phase. Acts as a following trim. Must be higher than AROT_COL_FILT_G.
58
// @Units: Hz
59
// @Range: 0.2 0.5
60
// @Increment: 0.01
61
// @User: Advanced
62
AP_GROUPINFO("COL_FILT_E", 5, AC_Autorotation, _param_col_entry_cutoff_freq, HS_CONTROLLER_ENTRY_COL_FILTER),
63
64
// @Param: COL_FILT_G
65
// @DisplayName: Glide Phase Collective Filter
66
// @Description: Cut-off frequency for collective low pass filter. For the glide phase. Acts as a following trim. Must be lower than AROT_COL_FILT_E.
67
// @Units: Hz
68
// @Range: 0.03 0.15
69
// @Increment: 0.01
70
// @User: Advanced
71
AP_GROUPINFO("COL_FILT_G", 6, AC_Autorotation, _param_col_glide_cutoff_freq, HS_CONTROLLER_GLIDE_COL_FILTER),
72
73
// @Param: AS_ACC_MAX
74
// @DisplayName: Forward Acceleration Limit
75
// @Description: Maximum forward acceleration to apply in speed controller.
76
// @Units: cm/s/s
77
// @Range: 30 60
78
// @Increment: 10
79
// @User: Advanced
80
AP_GROUPINFO("AS_ACC_MAX", 7, AC_Autorotation, _param_accel_max, FWD_SPD_CONTROLLER_MAX_ACCEL),
81
82
// @Param: HS_SENSOR
83
// @DisplayName: Main Rotor RPM Sensor
84
// @Description: Allocate the RPM sensor instance to use for measuring head speed. RPM1 = 0. RPM2 = 1.
85
// @Units: s
86
// @Range: 0.5 3
87
// @Increment: 0.1
88
// @User: Advanced
89
AP_GROUPINFO("HS_SENSOR", 8, AC_Autorotation, _param_rpm_instance, 0),
90
91
// @Param: FW_V_P
92
// @DisplayName: Velocity (horizontal) P gain
93
// @Description: Velocity (horizontal) P gain. Determines the proportion of the target acceleration based on the velocity error.
94
// @Range: 0.1 6.0
95
// @Increment: 0.1
96
// @User: Advanced
97
AP_SUBGROUPINFO(_p_fw_vel, "FW_V_", 9, AC_Autorotation, AC_P),
98
99
// @Param: FW_V_FF
100
// @DisplayName: Velocity (horizontal) feed forward
101
// @Description: Velocity (horizontal) input filter. Corrects the target acceleration proportionally to the desired velocity.
102
// @Range: 0 1
103
// @Increment: 0.01
104
// @User: Advanced
105
AP_GROUPINFO("FW_V_FF", 10, AC_Autorotation, _param_fwd_k_ff, AP_FW_VEL_FF),
106
107
AP_GROUPEND
108
};
109
110
// Constructor
111
AC_Autorotation::AC_Autorotation() :
112
_p_hs(HS_CONTROLLER_HEADSPEED_P),
113
_p_fw_vel(AP_FW_VEL_P)
114
{
115
AP_Param::setup_object_defaults(this, var_info);
116
}
117
118
// Initialisation of head speed controller
119
void AC_Autorotation::init_hs_controller()
120
{
121
// Set initial collective position to be the collective position on initialisation
122
_collective_out = 0.4f;
123
124
// Reset feed forward filter
125
col_trim_lpf.reset(_collective_out);
126
127
// Reset flags
128
_flags.bad_rpm = false;
129
130
// Reset RPM health monitoring
131
_unhealthy_rpm_counter = 0;
132
_healthy_rpm_counter = 0;
133
134
// Protect against divide by zero
135
_param_head_speed_set_point.set(MAX(_param_head_speed_set_point,500));
136
}
137
138
139
bool AC_Autorotation::update_hs_glide_controller(float dt)
140
{
141
// Reset rpm health flag
142
_flags.bad_rpm = false;
143
_flags.bad_rpm_warning = false;
144
145
// Get current rpm and update healthy signal counters
146
_current_rpm = get_rpm(true);
147
148
if (_unhealthy_rpm_counter <=30) {
149
// Normalised head speed
150
float head_speed_norm = _current_rpm / _param_head_speed_set_point;
151
152
// Set collective trim low pass filter cut off frequency
153
col_trim_lpf.set_cutoff_frequency(_col_cutoff_freq);
154
155
// Calculate the head speed error. Current rpm is normalised by the set point head speed.
156
// Target head speed is defined as a percentage of the set point.
157
_head_speed_error = head_speed_norm - _target_head_speed;
158
159
_p_term_hs = _p_hs.get_p(_head_speed_error);
160
161
// Adjusting collective trim using feed forward (not yet been updated, so this value is the previous time steps collective position)
162
_ff_term_hs = col_trim_lpf.apply(_collective_out, dt);
163
164
// Calculate collective position to be set
165
_collective_out = _p_term_hs + _ff_term_hs;
166
167
} else {
168
// RPM sensor is bad set collective to minimum
169
_collective_out = -1.0f;
170
171
_flags.bad_rpm_warning = true;
172
}
173
174
// Send collective to setting to motors output library
175
set_collective(HS_CONTROLLER_COLLECTIVE_CUTOFF_FREQ);
176
177
return _flags.bad_rpm_warning;
178
}
179
180
181
// Function to set collective and collective filter in motor library
182
void AC_Autorotation::set_collective(float collective_filter_cutoff) const
183
{
184
AP_Motors *motors = AP::motors();
185
if (motors) {
186
motors->set_throttle_filter_cutoff(collective_filter_cutoff);
187
motors->set_throttle(_collective_out);
188
}
189
}
190
191
192
//function that gets rpm and does rpm signal checking to ensure signal is reliable
193
//before using it in the controller
194
float AC_Autorotation::get_rpm(bool update_counter)
195
{
196
float current_rpm = 0.0f;
197
198
#if AP_RPM_ENABLED
199
// Get singleton for RPM library
200
const AP_RPM *rpm = AP_RPM::get_singleton();
201
202
//Get current rpm, checking to ensure no nullptr
203
if (rpm != nullptr) {
204
//Check requested rpm instance to ensure either 0 or 1. Always defaults to 0.
205
if ((_param_rpm_instance > 1) || (_param_rpm_instance < 0)) {
206
_param_rpm_instance.set(0);
207
}
208
209
//Get RPM value
210
uint8_t instance = _param_rpm_instance;
211
212
//Check RPM sensor is returning a healthy status
213
if (!rpm->get_rpm(instance, current_rpm) || current_rpm <= -1) {
214
//unhealthy, rpm unreliable
215
_flags.bad_rpm = true;
216
}
217
218
} else {
219
_flags.bad_rpm = true;
220
}
221
#else
222
_flags.bad_rpm = true;
223
#endif
224
225
if (_flags.bad_rpm) {
226
//count unhealthy rpm updates and reset healthy rpm counter
227
_unhealthy_rpm_counter++;
228
_healthy_rpm_counter = 0;
229
230
} else if (!_flags.bad_rpm && _unhealthy_rpm_counter > 0) {
231
//poor rpm reading may have cleared. Wait 10 update cycles to clear.
232
_healthy_rpm_counter++;
233
234
if (_healthy_rpm_counter >= 10) {
235
//poor rpm health has cleared, reset counters
236
_unhealthy_rpm_counter = 0;
237
_healthy_rpm_counter = 0;
238
}
239
}
240
return current_rpm;
241
}
242
243
244
#if HAL_LOGGING_ENABLED
245
void AC_Autorotation::Log_Write_Autorotation(void) const
246
{
247
// @LoggerMessage: AROT
248
// @Vehicles: Copter
249
// @Description: Helicopter AutoRotation information
250
// @Field: TimeUS: Time since system startup
251
// @Field: P: P-term for headspeed controller response
252
// @Field: hserr: head speed error; difference between current and desired head speed
253
// @Field: ColOut: Collective Out
254
// @Field: FFCol: FF-term for headspeed controller response
255
// @Field: CRPM: current headspeed RPM
256
// @Field: SpdF: current forward speed
257
// @Field: CmdV: desired forward speed
258
// @Field: p: p-term of velocity response
259
// @Field: ff: ff-term of velocity response
260
// @Field: AccO: forward acceleration output
261
// @Field: AccT: forward acceleration target
262
// @Field: PitT: pitch target
263
264
//Write to data flash log
265
AP::logger().WriteStreaming("AROT",
266
"TimeUS,P,hserr,ColOut,FFCol,CRPM,SpdF,CmdV,p,ff,AccO,AccT,PitT",
267
"Qffffffffffff",
268
AP_HAL::micros64(),
269
(double)_p_term_hs,
270
(double)_head_speed_error,
271
(double)_collective_out,
272
(double)_ff_term_hs,
273
(double)_current_rpm,
274
(double)_speed_forward,
275
(double)_cmd_vel,
276
(double)_vel_p,
277
(double)_vel_ff,
278
(double)_accel_out,
279
(double)_accel_target,
280
(double)_pitch_target);
281
}
282
#endif // HAL_LOGGING_ENABLED
283
284
// Initialise forward speed controller
285
void AC_Autorotation::init_fwd_spd_controller(void)
286
{
287
// Reset I term and acceleration target
288
_accel_target = 0.0f;
289
290
// Ensure parameter acceleration doesn't exceed hard-coded limit
291
_accel_max = MIN(_param_accel_max, 60.0f);
292
293
// Reset cmd vel and last accel to sensible values
294
_cmd_vel = calc_speed_forward(); //(cm/s)
295
_accel_out_last = _cmd_vel*_param_fwd_k_ff;
296
}
297
298
299
// set_dt - sets time delta in seconds for all controllers
300
void AC_Autorotation::set_dt(float delta_sec)
301
{
302
_dt = delta_sec;
303
}
304
305
306
// update speed controller
307
void AC_Autorotation::update_forward_speed_controller(void)
308
{
309
// Specify forward velocity component and determine delta velocity with respect to time
310
_speed_forward = calc_speed_forward(); //(cm/s)
311
312
_delta_speed_fwd = _speed_forward - _speed_forward_last; //(cm/s)
313
_speed_forward_last = _speed_forward; //(cm/s)
314
315
// Limiting the target velocity based on the max acceleration limit
316
if (_cmd_vel < _vel_target) {
317
_cmd_vel += _accel_max * _dt;
318
if (_cmd_vel > _vel_target) {
319
_cmd_vel = _vel_target;
320
}
321
} else {
322
_cmd_vel -= _accel_max * _dt;
323
if (_cmd_vel < _vel_target) {
324
_cmd_vel = _vel_target;
325
}
326
}
327
328
// get p
329
_vel_p = _p_fw_vel.get_p(_cmd_vel-_speed_forward);
330
331
// get ff
332
_vel_ff = _cmd_vel*_param_fwd_k_ff;
333
334
//calculate acceleration target based on PI controller
335
_accel_target = _vel_ff + _vel_p;
336
337
// filter correction acceleration
338
_accel_target_filter.set_cutoff_frequency(10.0f);
339
_accel_target_filter.apply(_accel_target, _dt);
340
341
//Limits the maximum change in pitch attitude based on acceleration
342
if (_accel_target > _accel_out_last + _accel_max) {
343
_accel_target = _accel_out_last + _accel_max;
344
} else if (_accel_target < _accel_out_last - _accel_max) {
345
_accel_target = _accel_out_last - _accel_max;
346
}
347
348
//Limiting acceleration based on velocity gained during the previous time step
349
if (fabsf(_delta_speed_fwd) > _accel_max * _dt) {
350
_flag_limit_accel = true;
351
} else {
352
_flag_limit_accel = false;
353
}
354
355
if ((_flag_limit_accel && fabsf(_accel_target) < fabsf(_accel_out_last)) || !_flag_limit_accel) {
356
_accel_out = _accel_target;
357
} else {
358
_accel_out = _accel_out_last;
359
}
360
_accel_out_last = _accel_out;
361
362
// update angle targets that will be passed to stabilize controller
363
_pitch_target = accel_to_angle(-_accel_out*0.01) * 100;
364
365
}
366
367
368
// Determine the forward ground speed component from measured components
369
float AC_Autorotation::calc_speed_forward(void)
370
{
371
auto &ahrs = AP::ahrs();
372
Vector2f groundspeed_vector = ahrs.groundspeed_vector();
373
float speed_forward = (groundspeed_vector.x*ahrs.cos_yaw() + groundspeed_vector.y*ahrs.sin_yaw())* 100; //(c/s)
374
return speed_forward;
375
}
376
377
378