1
1
#include "board.h"
2
2
#include "mw.h"
3
3
4
- // October 2012 V2.1 -dev
4
+ // June 2013 V2.2 -dev
5
5
6
6
flags_t f ;
7
7
int16_t debug [4 ];
@@ -24,6 +24,10 @@ int16_t lookupThrottleRC[11]; // lookup table for expo & mid THROTTLE
24
24
uint16_t rssi ; // range: [0;1023]
25
25
rcReadRawDataPtr rcReadRawFunc = NULL ; // receive data from default (pwm/ppm) or additional (spek/sbus/?? receiver drivers)
26
26
27
+ static void pidMultiWii (void );
28
+ static void pidRewrite (void );
29
+ pidControllerFuncPtr pid_controller = pidMultiWii ; // which pid controller are we using, defaultMultiWii
30
+
27
31
uint8_t dynP8 [3 ], dynI8 [3 ], dynD8 [3 ];
28
32
uint8_t rcOptions [CHECKBOXITEMS ];
29
33
@@ -132,6 +136,7 @@ void annexCode(void)
132
136
prop1 = 100 - (uint16_t ) cfg .yawRate * tmp / 500 ;
133
137
}
134
138
dynP8 [axis ] = (uint16_t ) cfg .P8 [axis ] * prop1 / 100 ;
139
+ dynI8 [axis ] = (uint16_t ) cfg .I8 [axis ] * prop1 / 100 ;
135
140
dynD8 [axis ] = (uint16_t ) cfg .D8 [axis ] * prop1 / 100 ;
136
141
if (rcData [axis ] < mcfg .midrc )
137
142
rcCommand [axis ] = - rcCommand [axis ];
@@ -273,25 +278,160 @@ static void mwVario(void)
273
278
274
279
}
275
280
276
- void loop (void )
281
+ static int32_t errorGyroI [3 ] = { 0 , 0 , 0 };
282
+ static int32_t errorAngleI [2 ] = { 0 , 0 };
283
+
284
+ static void pidMultiWii (void )
277
285
{
278
- static uint8_t rcDelayCommand ; // this indicates the number of time (multiple of RC measurement at 50Hz) the sticks must be maintained to run or switch off motors
279
- static uint8_t rcSticks ; // this hold sticks position for command combos
280
- uint8_t stTmp = 0 ;
281
- uint8_t axis , i ;
286
+ int axis , prop ;
282
287
int16_t error , errorAngle ;
283
288
int16_t PTerm , ITerm , PTermACC , ITermACC = 0 , PTermGYRO = 0 , ITermGYRO = 0 , DTerm ;
284
- static int16_t errorGyroI [3 ] = { 0 , 0 , 0 };
285
- static int16_t errorAngleI [2 ] = { 0 , 0 };
286
- int16_t delta ;
287
289
static int16_t lastGyro [3 ] = { 0 , 0 , 0 };
288
290
static int16_t delta1 [3 ], delta2 [3 ];
289
291
int16_t deltaSum ;
292
+ int16_t delta ;
293
+
294
+ // **** PITCH & ROLL & YAW PID ****
295
+ prop = max (abs (rcCommand [PITCH ]), abs (rcCommand [ROLL ])); // range [0;500]
296
+ for (axis = 0 ; axis < 3 ; axis ++ ) {
297
+ if ((f .ANGLE_MODE || f .HORIZON_MODE ) && axis < 2 ) { // MODE relying on ACC
298
+ // 50 degrees max inclination
299
+ errorAngle = constrain (2 * rcCommand [axis ] + GPS_angle [axis ], -500 , +500 ) - angle [axis ] + cfg .angleTrim [axis ];
300
+ PTermACC = (int32_t )errorAngle * cfg .P8 [PIDLEVEL ] / 100 ; // 32 bits is needed for calculation: errorAngle*P8[PIDLEVEL] could exceed 32768 16 bits is ok for result
301
+ PTermACC = constrain (PTermACC , - cfg .D8 [PIDLEVEL ] * 5 , + cfg .D8 [PIDLEVEL ] * 5 );
302
+
303
+ errorAngleI [axis ] = constrain (errorAngleI [axis ] + errorAngle , -10000 , +10000 ); // WindUp
304
+ ITermACC = ((int32_t )errorAngleI [axis ] * cfg .I8 [PIDLEVEL ]) >> 12 ;
305
+ }
306
+ if (!f .ANGLE_MODE || f .HORIZON_MODE || axis == 2 ) { // MODE relying on GYRO or YAW axis
307
+ error = (int32_t )rcCommand [axis ] * 10 * 8 / cfg .P8 [axis ];
308
+ error -= gyroData [axis ];
309
+
310
+ PTermGYRO = rcCommand [axis ];
311
+
312
+ errorGyroI [axis ] = constrain (errorGyroI [axis ] + error , -16000 , +16000 ); // WindUp
313
+ if (abs (gyroData [axis ]) > 640 )
314
+ errorGyroI [axis ] = 0 ;
315
+ ITermGYRO = (errorGyroI [axis ] / 125 * cfg .I8 [axis ]) >> 6 ;
316
+ }
317
+ if (f .HORIZON_MODE && axis < 2 ) {
318
+ PTerm = ((int32_t )PTermACC * (500 - prop ) + (int32_t )PTermGYRO * prop ) / 500 ;
319
+ ITerm = ((int32_t )ITermACC * (500 - prop ) + (int32_t )ITermGYRO * prop ) / 500 ;
320
+ } else {
321
+ if (f .ANGLE_MODE && axis < 2 ) {
322
+ PTerm = PTermACC ;
323
+ ITerm = ITermACC ;
324
+ } else {
325
+ PTerm = PTermGYRO ;
326
+ ITerm = ITermGYRO ;
327
+ }
328
+ }
329
+
330
+ PTerm -= (int32_t )gyroData [axis ] * dynP8 [axis ] / 10 / 8 ; // 32 bits is needed for calculation
331
+ delta = gyroData [axis ] - lastGyro [axis ]; // 16 bits is ok here, the dif between 2 consecutive gyro reads is limited to 800
332
+ lastGyro [axis ] = gyroData [axis ];
333
+ deltaSum = delta1 [axis ] + delta2 [axis ] + delta ;
334
+ delta2 [axis ] = delta1 [axis ];
335
+ delta1 [axis ] = delta ;
336
+ DTerm = ((int32_t )deltaSum * dynD8 [axis ]) >> 5 ; // 32 bits is needed for calculation
337
+ axisPID [axis ] = PTerm + ITerm - DTerm ;
338
+ }
339
+ }
340
+
341
+ #define GYRO_I_MAX 256
342
+
343
+ static void pidRewrite (void )
344
+ {
345
+ int16_t errorAngle ;
346
+ int axis ;
347
+ int16_t delta , deltaSum ;
348
+ static int16_t delta1 [3 ], delta2 [3 ];
349
+ int16_t PTerm , ITerm , DTerm ;
350
+ static int16_t lastError [3 ] = { 0 , 0 , 0 };
351
+ int16_t AngleRateTmp , RateError ;
352
+
353
+ // ----------PID controller----------
354
+ for (axis = 0 ; axis < 3 ; axis ++ ) {
355
+ // -----Get the desired angle rate depending on flight mode
356
+ if ((f .ANGLE_MODE || f .HORIZON_MODE ) && axis < 2 ) { // MODE relying on ACC
357
+ // calculate error and limit the angle to 50 degrees max inclination
358
+ errorAngle = constrain ((rcCommand [axis ] << 1 ) + GPS_angle [axis ], -500 , +500 ) - angle [axis ] + cfg .angleTrim [axis ]; // 16 bits is ok here
359
+ }
360
+ if (axis == 2 ) { // YAW is always gyro-controlled (MAG correction is applied to rcCommand)
361
+ AngleRateTmp = (((int32_t ) (cfg .yawRate + 27 ) * rcCommand [2 ]) >> 5 );
362
+ } else {
363
+ if (!f .ANGLE_MODE ) { //control is GYRO based (ACRO and HORIZON - direct sticks control is applied to rate PID
364
+ AngleRateTmp = ((int32_t ) (cfg .rollPitchRate + 27 ) * rcCommand [axis ]) >> 4 ;
365
+ if (f .HORIZON_MODE ) {
366
+ // mix up angle error to desired AngleRateTmp to add a little auto-level feel
367
+ AngleRateTmp += ((int32_t ) errorAngle * cfg .I8 [PIDLEVEL ]) >> 8 ;
368
+ }
369
+ } else { // it's the ANGLE mode - control is angle based, so control loop is needed
370
+ AngleRateTmp = ((int32_t ) errorAngle * cfg .P8 [PIDLEVEL ]) >> 4 ;
371
+ }
372
+ }
373
+
374
+ // --------low-level gyro-based PID. ----------
375
+ // Used in stand-alone mode for ACRO, controlled by higher level regulators in other modes
376
+ // -----calculate scaled error.AngleRates
377
+ // multiplication of rcCommand corresponds to changing the sticks scaling here
378
+ RateError = AngleRateTmp - gyroData [axis ];
379
+
380
+ // -----calculate P component
381
+ PTerm = ((int32_t )RateError * cfg .P8 [axis ]) >> 7 ;
382
+ // -----calculate I component
383
+ // there should be no division before accumulating the error to integrator, because the precision would be reduced.
384
+ // Precision is critical, as I prevents from long-time drift. Thus, 32 bits integrator is used.
385
+ // Time correction (to avoid different I scaling for different builds based on average cycle time)
386
+ // is normalized to cycle time = 2048.
387
+ errorGyroI [axis ] = errorGyroI [axis ] + (((int32_t )RateError * cycleTime ) >> 11 ) * cfg .I8 [axis ];
388
+
389
+ // limit maximum integrator value to prevent WindUp - accumulating extreme values when system is saturated.
390
+ // I coefficient (I8) moved before integration to make limiting independent from PID settings
391
+ errorGyroI [axis ] = constrain (errorGyroI [axis ], (int32_t )- GYRO_I_MAX << 13 , (int32_t )+ GYRO_I_MAX << 13 );
392
+ ITerm = errorGyroI [axis ] >> 13 ;
393
+
394
+ //-----calculate D-term
395
+ delta = RateError - lastError [axis ]; // 16 bits is ok here, the dif between 2 consecutive gyro reads is limited to 800
396
+ lastError [axis ] = RateError ;
397
+
398
+ // Correct difference by cycle time. Cycle time is jittery (can be different 2 times), so calculated difference
399
+ // would be scaled by different dt each time. Division by dT fixes that.
400
+ delta = ((int32_t ) delta * ((uint16_t )0xFFFF / (cycleTime >> 4 ))) >> 6 ;
401
+ // add moving average here to reduce noise
402
+ deltaSum = delta1 [axis ] + delta2 [axis ] + delta ;
403
+ delta2 [axis ] = delta1 [axis ];
404
+ delta1 [axis ] = delta ;
405
+ DTerm = (deltaSum * cfg .D8 [axis ]) >> 8 ;
406
+
407
+ // -----calculate total PID output
408
+ axisPID [axis ] = PTerm + ITerm + DTerm ;
409
+ }
410
+ }
411
+
412
+ void setPIDController (int type )
413
+ {
414
+ switch (type ) {
415
+ case 0 :
416
+ default :
417
+ pid_controller = pidMultiWii ;
418
+ break ;
419
+ case 1 :
420
+ pid_controller = pidRewrite ;
421
+ break ;
422
+ }
423
+ }
424
+
425
+ void loop (void )
426
+ {
427
+ static uint8_t rcDelayCommand ; // this indicates the number of time (multiple of RC measurement at 50Hz) the sticks must be maintained to run or switch off motors
428
+ static uint8_t rcSticks ; // this hold sticks position for command combos
429
+ uint8_t stTmp = 0 ;
430
+ int i ;
290
431
static uint32_t rcTime = 0 ;
291
432
static int16_t initialThrottleHold ;
292
433
static uint32_t loopTime ;
293
434
uint16_t auxState = 0 ;
294
- int16_t prop ;
295
435
static uint8_t GPSNavReset = 1 ;
296
436
297
437
// this will return false if spektrum is disabled. shrug.
@@ -703,51 +843,8 @@ void loop(void)
703
843
}
704
844
}
705
845
706
- // **** PITCH & ROLL & YAW PID ****
707
- prop = max (abs (rcCommand [PITCH ]), abs (rcCommand [ROLL ])); // range [0;500]
708
- for (axis = 0 ; axis < 3 ; axis ++ ) {
709
- if ((f .ANGLE_MODE || f .HORIZON_MODE ) && axis < 2 ) { // MODE relying on ACC
710
- // 50 degrees max inclination
711
- errorAngle = constrain (2 * rcCommand [axis ] + GPS_angle [axis ], -500 , +500 ) - angle [axis ] + cfg .angleTrim [axis ];
712
- PTermACC = (int32_t )errorAngle * cfg .P8 [PIDLEVEL ] / 100 ; // 32 bits is needed for calculation: errorAngle*P8[PIDLEVEL] could exceed 32768 16 bits is ok for result
713
- PTermACC = constrain (PTermACC , - cfg .D8 [PIDLEVEL ] * 5 , + cfg .D8 [PIDLEVEL ] * 5 );
714
-
715
- errorAngleI [axis ] = constrain (errorAngleI [axis ] + errorAngle , -10000 , +10000 ); // WindUp
716
- ITermACC = ((int32_t )errorAngleI [axis ] * cfg .I8 [PIDLEVEL ]) >> 12 ;
717
- }
718
- if (!f .ANGLE_MODE || f .HORIZON_MODE || axis == 2 ) { // MODE relying on GYRO or YAW axis
719
- error = (int32_t )rcCommand [axis ] * 10 * 8 / cfg .P8 [axis ];
720
- error -= gyroData [axis ];
721
-
722
- PTermGYRO = rcCommand [axis ];
723
-
724
- errorGyroI [axis ] = constrain (errorGyroI [axis ] + error , -16000 , +16000 ); // WindUp
725
- if (abs (gyroData [axis ]) > 640 )
726
- errorGyroI [axis ] = 0 ;
727
- ITermGYRO = (errorGyroI [axis ] / 125 * cfg .I8 [axis ]) >> 6 ;
728
- }
729
- if (f .HORIZON_MODE && axis < 2 ) {
730
- PTerm = ((int32_t )PTermACC * (500 - prop ) + (int32_t )PTermGYRO * prop ) / 500 ;
731
- ITerm = ((int32_t )ITermACC * (500 - prop ) + (int32_t )ITermGYRO * prop ) / 500 ;
732
- } else {
733
- if (f .ANGLE_MODE && axis < 2 ) {
734
- PTerm = PTermACC ;
735
- ITerm = ITermACC ;
736
- } else {
737
- PTerm = PTermGYRO ;
738
- ITerm = ITermGYRO ;
739
- }
740
- }
741
-
742
- PTerm -= (int32_t )gyroData [axis ] * dynP8 [axis ] / 10 / 8 ; // 32 bits is needed for calculation
743
- delta = gyroData [axis ] - lastGyro [axis ]; // 16 bits is ok here, the dif between 2 consecutive gyro reads is limited to 800
744
- lastGyro [axis ] = gyroData [axis ];
745
- deltaSum = delta1 [axis ] + delta2 [axis ] + delta ;
746
- delta2 [axis ] = delta1 [axis ];
747
- delta1 [axis ] = delta ;
748
- DTerm = ((int32_t )deltaSum * dynD8 [axis ]) >> 5 ; // 32 bits is needed for calculation
749
- axisPID [axis ] = PTerm + ITerm - DTerm ;
750
- }
846
+ // PID - note this is function pointer set by setPIDController()
847
+ pid_controller ();
751
848
752
849
mixTable ();
753
850
writeServos ();
0 commit comments