/
position_controller_pid.c
495 lines (446 loc) · 13.9 KB
/
position_controller_pid.c
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
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
/**
* || ____ _ __
* +------+ / __ )(_) /_______________ _____ ___
* | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \
* +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/
* || || /_____/_/\__/\___/_/ \__,_/ /___/\___/
*
* Crazyflie Firmware
*
* Copyright (C) 2016 Bitcraze AB
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, in version 3.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
* position_estimator_pid.c: PID-based implementation of the position controller
*/
#include <math.h>
#include "num.h"
#include "commander.h"
#include "log.h"
#include "param.h"
#include "pid.h"
#include "num.h"
#include "position_controller.h"
struct pidInit_s {
float kp;
float ki;
float kd;
};
struct pidAxis_s {
PidObject pid;
struct pidInit_s init;
stab_mode_t previousMode;
float setpoint;
float output;
};
struct this_s {
struct pidAxis_s pidVX;
struct pidAxis_s pidVY;
struct pidAxis_s pidVZ;
struct pidAxis_s pidX;
struct pidAxis_s pidY;
struct pidAxis_s pidZ;
uint16_t thrustBase; // approximate throttle needed when in perfect hover. More weight/older battery can use a higher value
uint16_t thrustMin; // Minimum thrust value to output
};
// Maximum roll/pitch angle permited
static float rpLimit = 20;
static float rpLimitOverhead = 1.10f;
// Velocity maximums
static float xyVelMax = 1.0f;
static float zVelMax = 1.0f;
static float velMaxOverhead = 1.10f;
static const float thrustScale = 1000.0f;
#define DT (float)(1.0f/POSITION_RATE)
#define POSITION_LPF_CUTOFF_FREQ 20.0f
#define ZVELOCITY_LPF_CUTOFF_FREQ 0.7f
#define POSITION_LPF_ENABLE true
#ifndef UNIT_TEST
static struct this_s this = {
.pidVX = {
.init = {
.kp = 25.0f,
.ki = 1.0f,
.kd = 0.0f,
},
.pid.dt = DT,
},
.pidVY = {
.init = {
.kp = 25.0f,
.ki = 1.0f,
.kd = 0.0f,
},
.pid.dt = DT,
},
#ifdef IMPROVED_BARO_Z_HOLD
.pidVZ = {
.init = {
.kp = 3.0f,
.ki = 1.0f,
.kd = 1.5f, //kd can be lowered for improved stability, but results in slower response time.
},
.pid.dt = DT,
},
#else
.pidVZ = {
.init = {
.kp = 25.0f,
.ki = 15.0f,
.kd = 0,
},
.pid.dt = DT,
},
#endif
.pidX = {
.init = {
.kp = 2.0f,
.ki = 0,
.kd = 0,
},
.pid.dt = DT,
},
.pidY = {
.init = {
.kp = 2.0f,
.ki = 0,
.kd = 0,
},
.pid.dt = DT,
},
.pidZ = {
.init = {
.kp = 2.0f,
.ki = 0.5,
.kd = 0,
},
.pid.dt = DT,
},
#ifdef IMPROVED_BARO_Z_HOLD
.thrustBase = 38000,
#else
.thrustBase = 36000,
#endif
.thrustMin = 20000,
};
#endif
void positionControllerInit()
{
pidInit(&this.pidX.pid, this.pidX.setpoint, this.pidX.init.kp, this.pidX.init.ki, this.pidX.init.kd,
this.pidX.pid.dt, POSITION_RATE, POSITION_LPF_CUTOFF_FREQ, POSITION_LPF_ENABLE);
pidInit(&this.pidY.pid, this.pidY.setpoint, this.pidY.init.kp, this.pidY.init.ki, this.pidY.init.kd,
this.pidY.pid.dt, POSITION_RATE, POSITION_LPF_CUTOFF_FREQ, POSITION_LPF_ENABLE);
pidInit(&this.pidZ.pid, this.pidZ.setpoint, this.pidZ.init.kp, this.pidZ.init.ki, this.pidZ.init.kd,
this.pidZ.pid.dt, POSITION_RATE, POSITION_LPF_CUTOFF_FREQ, POSITION_LPF_ENABLE);
pidInit(&this.pidVX.pid, this.pidVX.setpoint, this.pidVX.init.kp, this.pidVX.init.ki, this.pidVX.init.kd,
this.pidVX.pid.dt, POSITION_RATE, POSITION_LPF_CUTOFF_FREQ, POSITION_LPF_ENABLE);
pidInit(&this.pidVY.pid, this.pidVY.setpoint, this.pidVY.init.kp, this.pidVY.init.ki, this.pidVY.init.kd,
this.pidVY.pid.dt, POSITION_RATE, POSITION_LPF_CUTOFF_FREQ, POSITION_LPF_ENABLE);
#ifdef IMPROVED_BARO_Z_HOLD
pidInit(&this.pidVZ.pid, this.pidVZ.setpoint, this.pidVZ.init.kp, this.pidVZ.init.ki, this.pidVZ.init.kd,
this.pidVZ.pid.dt, POSITION_RATE, ZVELOCITY_LPF_CUTOFF_FREQ, POSITION_LPF_ENABLE);
#else
pidInit(&this.pidVZ.pid, this.pidVZ.setpoint, this.pidVZ.init.kp, this.pidVZ.init.ki, this.pidVZ.init.kd,
this.pidVZ.pid.dt, POSITION_RATE, POSITION_LPF_CUTOFF_FREQ, POSITION_LPF_ENABLE);
#endif
}
static float runPid(float input, struct pidAxis_s *axis, float setpoint, float dt) {
axis->setpoint = setpoint;
pidSetDesired(&axis->pid, axis->setpoint);
return pidUpdate(&axis->pid, input, true);
}
void positionController(float* thrust, attitude_t *attitude, setpoint_t *setpoint,
const state_t *state)
{
this.pidX.pid.outputLimit = xyVelMax * velMaxOverhead;
this.pidY.pid.outputLimit = xyVelMax * velMaxOverhead;
// The ROS landing detector will prematurely trip if
// this value is below 0.5
this.pidZ.pid.outputLimit = fmaxf(zVelMax, 0.5f) * velMaxOverhead;
float cosyaw = cosf(state->attitude.yaw * (float)M_PI / 180.0f);
float sinyaw = sinf(state->attitude.yaw * (float)M_PI / 180.0f);
float bodyvx = setpoint->velocity.x;
float bodyvy = setpoint->velocity.y;
// X, Y
if (setpoint->mode.x == modeAbs) {
setpoint->velocity.x = runPid(state->position.x, &this.pidX, setpoint->position.x, DT);
} else if (setpoint->velocity_body) {
setpoint->velocity.x = bodyvx * cosyaw - bodyvy * sinyaw;
}
if (setpoint->mode.y == modeAbs) {
setpoint->velocity.y = runPid(state->position.y, &this.pidY, setpoint->position.y, DT);
} else if (setpoint->velocity_body) {
setpoint->velocity.y = bodyvy * cosyaw + bodyvx * sinyaw;
}
if (setpoint->mode.z == modeAbs) {
setpoint->velocity.z = runPid(state->position.z, &this.pidZ, setpoint->position.z, DT);
}
velocityController(thrust, attitude, setpoint, state);
}
void velocityController(float* thrust, attitude_t *attitude, setpoint_t *setpoint,
const state_t *state)
{
this.pidVX.pid.outputLimit = rpLimit * rpLimitOverhead;
this.pidVY.pid.outputLimit = rpLimit * rpLimitOverhead;
// Set the output limit to the maximum thrust range
this.pidVZ.pid.outputLimit = (UINT16_MAX / 2 / thrustScale);
//this.pidVZ.pid.outputLimit = (this.thrustBase - this.thrustMin) / thrustScale;
// Roll and Pitch
float rollRaw = runPid(state->velocity.x, &this.pidVX, setpoint->velocity.x, DT);
float pitchRaw = runPid(state->velocity.y, &this.pidVY, setpoint->velocity.y, DT);
float yawRad = state->attitude.yaw * (float)M_PI / 180;
attitude->pitch = -(rollRaw * cosf(yawRad)) - (pitchRaw * sinf(yawRad));
attitude->roll = -(pitchRaw * cosf(yawRad)) + (rollRaw * sinf(yawRad));
attitude->roll = constrain(attitude->roll, -rpLimit, rpLimit);
attitude->pitch = constrain(attitude->pitch, -rpLimit, rpLimit);
// Thrust
float thrustRaw = runPid(state->velocity.z, &this.pidVZ, setpoint->velocity.z, DT);
// Scale the thrust and add feed forward term
*thrust = thrustRaw*thrustScale + this.thrustBase;
// Check for minimum thrust
if (*thrust < this.thrustMin) {
*thrust = this.thrustMin;
}
}
void positionControllerResetAllPID()
{
pidReset(&this.pidX.pid);
pidReset(&this.pidY.pid);
pidReset(&this.pidZ.pid);
pidReset(&this.pidVX.pid);
pidReset(&this.pidVY.pid);
pidReset(&this.pidVZ.pid);
}
void positionControllerResetAllfilters() {
filterReset(&this.pidX.pid, POSITION_RATE, POSITION_LPF_CUTOFF_FREQ, POSITION_LPF_ENABLE);
filterReset(&this.pidY.pid, POSITION_RATE, POSITION_LPF_CUTOFF_FREQ, POSITION_LPF_ENABLE);
filterReset(&this.pidZ.pid, POSITION_RATE, POSITION_LPF_CUTOFF_FREQ, POSITION_LPF_ENABLE);
filterReset(&this.pidVX.pid, POSITION_RATE, POSITION_LPF_CUTOFF_FREQ, POSITION_LPF_ENABLE);
filterReset(&this.pidVY.pid, POSITION_RATE, POSITION_LPF_CUTOFF_FREQ, POSITION_LPF_ENABLE);
#ifdef IMPROVED_BARO_Z_HOLD
filterReset(&this.pidVZ.pid, POSITION_RATE, ZVELOCITY_LPF_CUTOFF_FREQ, POSITION_LPF_ENABLE);
#else
filterReset(&this.pidVZ.pid, POSITION_RATE, POSITION_LPF_CUTOFF_FREQ, POSITION_LPF_ENABLE);
#endif
}
/**
* Log variables of the PID position controller
*
* Note: rename to posCtrlPID ?
*/
LOG_GROUP_START(posCtl)
/**
* @brief PID controller target desired velocity x [m/s]
*
* Note: Same as stabilizer log
*/
LOG_ADD(LOG_FLOAT, targetVX, &this.pidVX.pid.desired)
/**
* @brief PID controller target desired velocity y [m/s]
*
* Note: Same as stabilizer log
*/
LOG_ADD(LOG_FLOAT, targetVY, &this.pidVY.pid.desired)
/**
* @brief PID controller target desired velocity z [m/s]
*
* Note: Same as stabilizer log
*/
LOG_ADD(LOG_FLOAT, targetVZ, &this.pidVZ.pid.desired)
/**
* @brief PID controller target desired position x [m]
*
* Note: Same as stabilizer log
*/
LOG_ADD(LOG_FLOAT, targetX, &this.pidX.pid.desired)
/**
* @brief PID controller target desired position y [m]
*
* Note: Same as stabilizer log
*/
LOG_ADD(LOG_FLOAT, targetY, &this.pidY.pid.desired)
/**
* @brief PID controller target desired position z [m]
*
* Note: Same as stabilizer log
*/
LOG_ADD(LOG_FLOAT, targetZ, &this.pidZ.pid.desired)
/**
* @brief PID proportional output position x
*/
LOG_ADD(LOG_FLOAT, Xp, &this.pidX.pid.outP)
/**
* @brief PID Integral output position x
*/
LOG_ADD(LOG_FLOAT, Xi, &this.pidX.pid.outI)
/**
* @brief PID Derivative output position x
*/
LOG_ADD(LOG_FLOAT, Xd, &this.pidX.pid.outD)
/**
* @brief PID proportional output position y
*/
LOG_ADD(LOG_FLOAT, Yp, &this.pidY.pid.outP)
/**
* @brief PID Integral output position y
*/
LOG_ADD(LOG_FLOAT, Yi, &this.pidY.pid.outI)
/**
* @brief PID Derivative output position y
*/
LOG_ADD(LOG_FLOAT, Yd, &this.pidY.pid.outD)
/**
* @brief PID proportional output position z
*/
LOG_ADD(LOG_FLOAT, Zp, &this.pidZ.pid.outP)
/**
* @brief PID Integral output position z
*/
LOG_ADD(LOG_FLOAT, Zi, &this.pidZ.pid.outI)
/**
* @brief PID derivative output position z
*/
LOG_ADD(LOG_FLOAT, Zd, &this.pidZ.pid.outD)
/**
* @brief PID proportional output velocity x
*/
LOG_ADD(LOG_FLOAT, VXp, &this.pidVX.pid.outP)
/**
* @brief PID integral output velocity x
*/
LOG_ADD(LOG_FLOAT, VXi, &this.pidVX.pid.outI)
/**
* @brief PID derivative output velocity x
*/
LOG_ADD(LOG_FLOAT, VXd, &this.pidVX.pid.outD)
/**
* @brief PID proportional output velocity z
*/
LOG_ADD(LOG_FLOAT, VZp, &this.pidVZ.pid.outP)
/**
* @brief PID integral output velocity z
*/
LOG_ADD(LOG_FLOAT, VZi, &this.pidVZ.pid.outI)
/**
* @brief PID intrgral output velocity z
*/
LOG_ADD(LOG_FLOAT, VZd, &this.pidVZ.pid.outD)
LOG_GROUP_STOP(posCtl)
/**
* Tuning settings for the gains of the PID
* controller for the velocity of the Crazyflie ¨
* in the X, Y and Z direction in the body fixed
* coordinate system.
*/
PARAM_GROUP_START(velCtlPid)
/**
* @brief Proportional gain for the velocity PID in the body X direction
*/
PARAM_ADD(PARAM_FLOAT, vxKp, &this.pidVX.pid.kp)
/**
* @brief Integral gain for the velocity PID in the body X direction
*/
PARAM_ADD(PARAM_FLOAT, vxKi, &this.pidVX.pid.ki)
/**
* @brief Derivative gain for the velocity PID in the body X direction
*/
PARAM_ADD(PARAM_FLOAT, vxKd, &this.pidVX.pid.kd)
/**
* @brief Proportional gain for the velocity PID in the body Y direction
*/
PARAM_ADD(PARAM_FLOAT, vyKp, &this.pidVY.pid.kp)
/**
* @brief Integral gain for the velocity PID in the body Y direction
*/
PARAM_ADD(PARAM_FLOAT, vyKi, &this.pidVY.pid.ki)
/**
* @brief Derivative gain for the velocity PID in the body Y direction
*/
PARAM_ADD(PARAM_FLOAT, vyKd, &this.pidVY.pid.kd)
/**
* @brief Proportional gain for the velocity PID in the body Z direction
*/
PARAM_ADD(PARAM_FLOAT, vzKp, &this.pidVZ.pid.kp)
/**
* @brief Integral gain for the velocity PID in the body Z direction
*/
PARAM_ADD(PARAM_FLOAT, vzKi, &this.pidVZ.pid.ki)
/**
* @brief Derivative gain for the velocity PID in the body Z direction
*/
PARAM_ADD(PARAM_FLOAT, vzKd, &this.pidVZ.pid.kd)
PARAM_GROUP_STOP(velCtlPid)
/**
* Tuning settings for the gains of the PID
* controller for the position of the Crazyflie ¨
* in the X, Y and Z direction in the global
* coordinate system.
*/
PARAM_GROUP_START(posCtlPid)
/**
* @brief Proportional gain for the position PID in the global X direction
*/
PARAM_ADD(PARAM_FLOAT, xKp, &this.pidX.pid.kp)
/**
* @brief Proportional gain for the position PID in the global X direction
*/
PARAM_ADD(PARAM_FLOAT, xKi, &this.pidX.pid.ki)
/**
* @brief Derivative gain for the position PID in the global X direction
*/
PARAM_ADD(PARAM_FLOAT, xKd, &this.pidX.pid.kd)
/**
* @brief Proportional gain for the position PID in the global Y direction
*/
PARAM_ADD(PARAM_FLOAT, yKp, &this.pidY.pid.kp)
/**
* @brief Integral gain for the position PID in the global Y direction
*/
PARAM_ADD(PARAM_FLOAT, yKi, &this.pidY.pid.ki)
/**
* @brief Derivative gain for the position PID in the global Y direction
*/
PARAM_ADD(PARAM_FLOAT, yKd, &this.pidY.pid.kd)
/**
* @brief Proportional gain for the position PID in the global Z direction
*/
PARAM_ADD(PARAM_FLOAT, zKp, &this.pidZ.pid.kp)
/**
* @brief Integral gain for the position PID in the global Z direction
*/
PARAM_ADD(PARAM_FLOAT, zKi, &this.pidZ.pid.ki)
/**
* @brief Derivative gain for the position PID in the global Z direction
*/
PARAM_ADD(PARAM_FLOAT, zKd, &this.pidZ.pid.kd)
/**
* @brief Approx. thrust needed for hover
*/
PARAM_ADD(PARAM_UINT16, thrustBase, &this.thrustBase)
/**
* @brief Min. thrust value to output
*/
PARAM_ADD(PARAM_UINT16, thrustMin, &this.thrustMin)
/**
* @brief Roll/Pitch absolute limit
*/
PARAM_ADD(PARAM_FLOAT, rpLimit, &rpLimit)
/**
* @brief Maximum X/Y velocity
*/
PARAM_ADD(PARAM_FLOAT, xyVelMax, &xyVelMax)
/**
* @brief Maximum Z Velocity
*/
PARAM_ADD(PARAM_FLOAT, zVelMax, &zVelMax)
PARAM_GROUP_STOP(posCtlPid)