-
Notifications
You must be signed in to change notification settings - Fork 462
/
MultiWii.cpp
1537 lines (1408 loc) · 55.5 KB
/
MultiWii.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
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
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
/*
MultiWiiCopter by Alexandre Dubus
www.multiwii.com
March 2015 V2.4
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, either version 3 of the License, or
any later version. see <http://www.gnu.org/licenses/>
*/
#include <avr/io.h>
#include "Arduino.h"
#include "config.h"
#include "def.h"
#include "types.h"
#include "MultiWii.h"
#include "Alarms.h"
#include "EEPROM.h"
#include "IMU.h"
#include "LCD.h"
#include "Output.h"
#include "RX.h"
#include "Sensors.h"
#include "Serial.h"
#include "GPS.h"
#include "Protocol.h"
#include "Telemetry.h"
#include <avr/pgmspace.h>
/*********** RC alias *****************/
const char pidnames[] PROGMEM =
"ROLL;"
"PITCH;"
"YAW;"
"ALT;"
"Pos;"
"PosR;"
"NavR;"
"LEVEL;"
"MAG;"
"VEL;"
;
const char boxnames[] PROGMEM = // names for dynamic generation of config GUI
"ARM;"
#if ACC
"ANGLE;"
"HORIZON;"
#endif
#if BARO && (!defined(SUPPRESS_BARO_ALTHOLD))
"BARO;"
#endif
#ifdef VARIOMETER
"VARIO;"
#endif
"MAG;"
#if defined(HEADFREE)
"HEADFREE;"
"HEADADJ;"
#endif
#if defined(SERVO_TILT) || defined(GIMBAL)|| defined(SERVO_MIX_TILT)
"CAMSTAB;"
#endif
#if defined(CAMTRIG)
"CAMTRIG;"
#endif
#if GPS
"GPS HOME;"
"GPS HOLD;"
#endif
#if defined(FIXEDWING) || defined(HELICOPTER)
"PASSTHRU;"
#endif
#if defined(BUZZER)
"BEEPER;"
#endif
#if defined(LED_FLASHER)
"LEDMAX;"
"LEDLOW;"
#endif
#if defined(LANDING_LIGHTS_DDR)
"LLIGHTS;"
#endif
#ifdef INFLIGHT_ACC_CALIBRATION
"CALIB;"
#endif
#ifdef GOVERNOR_P
"GOVERNOR;"
#endif
#ifdef OSD_SWITCH
"OSD SW;"
#endif
#if GPS
"MISSION;"
"LAND;"
#endif
;
const uint8_t boxids[] PROGMEM = {// permanent IDs associated to boxes. This way, you can rely on an ID number to identify a BOX function.
0, //"ARM;"
#if ACC
1, //"ANGLE;"
2, //"HORIZON;"
#endif
#if BARO && (!defined(SUPPRESS_BARO_ALTHOLD))
3, //"BARO;"
#endif
#ifdef VARIOMETER
4, //"VARIO;"
#endif
5, //"MAG;"
#if defined(HEADFREE)
6, //"HEADFREE;"
7, //"HEADADJ;"
#endif
#if defined(SERVO_TILT) || defined(GIMBAL)|| defined(SERVO_MIX_TILT)
8, //"CAMSTAB;"
#endif
#if defined(CAMTRIG)
9, //"CAMTRIG;"
#endif
#if GPS
10, //"GPS HOME;"
11, //"GPS HOLD;"
#endif
#if defined(FIXEDWING) || defined(HELICOPTER)
12, //"PASSTHRU;"
#endif
#if defined(BUZZER)
13, //"BEEPER;"
#endif
#if defined(LED_FLASHER)
14, //"LEDMAX;"
15, //"LEDLOW;"
#endif
#if defined(LANDING_LIGHTS_DDR)
16, //"LLIGHTS;"
#endif
#ifdef INFLIGHT_ACC_CALIBRATION
17, //"CALIB;"
#endif
#ifdef GOVERNOR_P
18, //"GOVERNOR;"
#endif
#ifdef OSD_SWITCH
19, //"OSD_SWITCH;"
#endif
#if GPS
20, //"MISSION;"
21, //"LAND;"
#endif
};
uint32_t currentTime = 0;
uint16_t previousTime = 0;
uint16_t cycleTime = 0; // this is the number in micro second to achieve a full loop, it can differ a little and is taken into account in the PID loop
uint16_t calibratingA = 0; // the calibration is done in the main loop. Calibrating decreases at each cycle down to 0, then we enter in a normal mode.
uint16_t calibratingB = 0; // baro calibration = get new ground pressure value
uint16_t calibratingG;
int16_t magHold,headFreeModeHold; // [-180;+180]
uint8_t vbatMin = VBATNOMINAL; // lowest battery voltage in 0.1V steps
uint8_t rcOptions[CHECKBOXITEMS];
int32_t AltHold; // in cm
int16_t sonarAlt;
int16_t BaroPID = 0;
int16_t errorAltitudeI = 0;
// **************
// gyro+acc IMU
// **************
int16_t gyroZero[3] = {0,0,0};
imu_t imu;
analog_t analog;
alt_t alt;
att_t att;
#if defined(ARMEDTIMEWARNING)
uint32_t ArmedTimeWarningMicroSeconds = 0;
#endif
int16_t debug[4];
flags_struct_t f;
//for log
#if defined(LOG_VALUES) || defined(LCD_TELEMETRY)
uint16_t cycleTimeMax = 0; // highest ever cycle timen
uint16_t cycleTimeMin = 65535; // lowest ever cycle timen
int32_t BAROaltMax; // maximum value
uint16_t GPS_speedMax = 0; // maximum speed from gps
#ifdef POWERMETER_HARD
uint16_t powerValueMaxMAH = 0;
#endif
#if defined(WATTS)
uint16_t wattsMax = 0;
#endif
#endif
#if defined(LOG_VALUES) || defined(LCD_TELEMETRY) || defined(ARMEDTIMEWARNING) || defined(LOG_PERMANENT) || defined (TELEMETRY)
uint32_t armedTime = 0;
#endif
int16_t i2c_errors_count = 0;
#if defined(THROTTLE_ANGLE_CORRECTION)
int16_t throttleAngleCorrection = 0; // correction of throttle in lateral wind,
int8_t cosZ = 100; // cos(angleZ)*100
#endif
// **********************
//Automatic ACC Offset Calibration
// **********************
#if defined(INFLIGHT_ACC_CALIBRATION)
uint16_t InflightcalibratingA = 0;
int16_t AccInflightCalibrationArmed;
uint16_t AccInflightCalibrationMeasurementDone = 0;
uint16_t AccInflightCalibrationSavetoEEProm = 0;
uint16_t AccInflightCalibrationActive = 0;
#endif
// **********************
// power meter
// **********************
#if defined(POWERMETER) || ( defined(LOG_VALUES) && (LOG_VALUES >= 3) )
uint32_t pMeter[PMOTOR_SUM + 1]; // we use [0:7] for eight motors,one extra for sum
uint8_t pMeterV; // dummy to satisfy the paramStruct logic in ConfigurationLoop()
uint32_t pAlarm; // we scale the eeprom value from [0:255] to this value we can directly compare to the sum in pMeter[6]
uint16_t powerValue = 0; // last known current
#endif
uint16_t intPowerTrigger1;
// **********************
// telemetry
// **********************
#if defined(LCD_TELEMETRY)
uint8_t telemetry = 0;
uint8_t telemetry_auto = 0;
int16_t annex650_overrun_count = 0;
#endif
#ifdef LCD_TELEMETRY_STEP
char telemetryStepSequence [] = LCD_TELEMETRY_STEP;
uint8_t telemetryStepIndex = 0;
#endif
// ******************
// rc functions
// ******************
#define ROL_LO (1<<(2*ROLL))
#define ROL_CE (3<<(2*ROLL))
#define ROL_HI (2<<(2*ROLL))
#define PIT_LO (1<<(2*PITCH))
#define PIT_CE (3<<(2*PITCH))
#define PIT_HI (2<<(2*PITCH))
#define YAW_LO (1<<(2*YAW))
#define YAW_CE (3<<(2*YAW))
#define YAW_HI (2<<(2*YAW))
#define THR_LO (1<<(2*THROTTLE))
#define THR_CE (3<<(2*THROTTLE))
#define THR_HI (2<<(2*THROTTLE))
int16_t failsafeEvents = 0;
volatile int16_t failsafeCnt = 0;
int16_t rcData[RC_CHANS]; // interval [1000;2000]
int16_t rcSerial[8]; // interval [1000;2000] - is rcData coming from MSP
int16_t rcCommand[4]; // interval [1000;2000] for THROTTLE and [-500;+500] for ROLL/PITCH/YAW
uint8_t rcSerialCount = 0; // a counter to select legacy RX when there is no more MSP rc serial data
int16_t lookupPitchRollRC[5];// lookup table for expo & RC rate PITCH+ROLL
uint16_t lookupThrottleRC[11];// lookup table for expo & mid THROTTLE
#if defined(SERIAL_RX)
volatile uint8_t spekFrameFlags;
volatile uint32_t spekTimeLast;
uint8_t spekFrameDone;
#endif
#if defined(OPENLRSv2MULTI)
uint8_t pot_P,pot_I; // OpenLRS onboard potentiometers for P and I trim or other usages
#endif
// *************************
// motor and servo functions
// *************************
int16_t axisPID[3];
int16_t motor[8];
int16_t servo[8] = {1500,1500,1500,1500,1500,1500,1500,1000};
// ************************
// EEPROM Layout definition
// ************************
static uint8_t dynP8[2], dynD8[2];
global_conf_t global_conf;
conf_t conf;
#ifdef LOG_PERMANENT
plog_t plog;
#endif
// **********************
// GPS common variables, no need to put them in defines, since compiller will optimize out unused variables
// **********************
#if GPS
gps_conf_struct GPS_conf;
#endif
int16_t GPS_angle[2] = { 0, 0}; // the angles that must be applied for GPS correction
int32_t GPS_coord[2];
int32_t GPS_home[2];
int32_t GPS_hold[2];
int32_t GPS_prev[2]; //previous pos
int32_t GPS_poi[2];
uint8_t GPS_numSat;
uint16_t GPS_distanceToHome; // distance to home - unit: meter
int16_t GPS_directionToHome; // direction to home - unit: degree
int32_t GPS_directionToPoi;
uint16_t GPS_altitude; // GPS altitude - unit: meter
uint16_t GPS_speed; // GPS speed - unit: cm/s
uint8_t GPS_update = 0; // a binary toogle to distinct a GPS position update
uint16_t GPS_ground_course = 0; // - unit: degree*10
//uint8_t GPS_mode = GPS_MODE_NONE; // contains the current selected gps flight mode --> moved to the f. structure
uint8_t NAV_state = 0; // NAV_STATE_NONE; /// State of the nav engine
uint8_t NAV_error = 0; // NAV_ERROR_NONE;
uint8_t prv_gps_modes = 0; /// GPS_checkbox items packed into 1 byte for checking GPS mode changes
uint32_t nav_timer_stop = 0; /// common timer used in navigation (contains the desired stop time in millis()
uint16_t nav_hold_time; /// time in seconds to hold position
uint8_t NAV_paused_at = 0; // This contains the mission step where poshold paused the runing mission.
uint8_t next_step = 1; /// The mission step which is upcoming it equals with the mission_step stored in EEPROM
int16_t jump_times = -10;
#if GPS
mission_step_struct mission_step;
#endif
// The desired bank towards North (Positive) or South (Negative) : latitude
// The desired bank towards East (Positive) or West (Negative) : longitude
int16_t nav[2];
int16_t nav_rated[2]; //Adding a rate controller to the navigation to make it smoother
// The orginal altitude used as base our new altitude during nav
int32_t original_altitude;
//This is the target what we want to reach
int32_t target_altitude;
//This is the interim value which is feeded into the althold controller
int32_t alt_to_hold;
uint32_t alt_change_timer;
int8_t alt_change_flag;
uint32_t alt_change;
uint8_t alarmArray[ALRM_FAC_SIZE]; // array
#if BARO
int32_t baroPressure;
int16_t baroTemperature;
int32_t baroPressureSum;
#endif
void annexCode() { // this code is excetuted at each loop and won't interfere with control loop if it lasts less than 650 microseconds
static uint32_t calibratedAccTime;
uint16_t tmp,tmp2;
uint8_t axis,prop1,prop2;
// PITCH & ROLL only dynamic PID adjustemnt, depending on throttle value (or collective.pitch value for heli)
#ifdef HELICOPTER
#define DYN_THR_PID_CHANNEL COLLECTIVE_PITCH
#else
#define DYN_THR_PID_CHANNEL THROTTLE
#endif
prop2 = 128; // prop2 was 100, is 128 now
if (rcData[DYN_THR_PID_CHANNEL]>1500) { // breakpoint is fix: 1500
if (rcData[DYN_THR_PID_CHANNEL]<2000) {
prop2 -= ((uint16_t)conf.dynThrPID*(rcData[DYN_THR_PID_CHANNEL]-1500)>>9); // /512 instead of /500
} else {
prop2 -= conf.dynThrPID;
}
}
for(axis=0;axis<3;axis++) {
tmp = min(abs(rcData[axis]-MIDRC),500);
#if defined(DEADBAND)
if (tmp>DEADBAND) { tmp -= DEADBAND; }
else { tmp=0; }
#endif
if(axis!=2) { //ROLL & PITCH
tmp2 = tmp>>7; // 500/128 = 3.9 => range [0;3]
rcCommand[axis] = lookupPitchRollRC[tmp2] + ((tmp-(tmp2<<7)) * (lookupPitchRollRC[tmp2+1]-lookupPitchRollRC[tmp2])>>7);
prop1 = 128-((uint16_t)conf.rollPitchRate*tmp>>9); // prop1 was 100, is 128 now -- and /512 instead of /500
prop1 = (uint16_t)prop1*prop2>>7; // prop1: max is 128 prop2: max is 128 result prop1: max is 128
dynP8[axis] = (uint16_t)conf.pid[axis].P8*prop1>>7; // was /100, is /128 now
dynD8[axis] = (uint16_t)conf.pid[axis].D8*prop1>>7; // was /100, is /128 now
} else { // YAW
rcCommand[axis] = tmp;
}
if (rcData[axis]<MIDRC) rcCommand[axis] = -rcCommand[axis];
}
tmp = constrain(rcData[THROTTLE],MINCHECK,2000);
tmp = (uint32_t)(tmp-MINCHECK)*2559/(2000-MINCHECK); // [MINCHECK;2000] -> [0;2559]
tmp2 = tmp/256; // range [0;9]
rcCommand[THROTTLE] = lookupThrottleRC[tmp2] + (tmp-tmp2*256) * (lookupThrottleRC[tmp2+1]-lookupThrottleRC[tmp2]) / 256; // [0;2559] -> expo -> [conf.minthrottle;MAXTHROTTLE]
#if defined(HEADFREE)
if(f.HEADFREE_MODE) { //to optimize
float radDiff = (att.heading - headFreeModeHold) * 0.0174533f; // where PI/180 ~= 0.0174533
float cosDiff = cos(radDiff);
float sinDiff = sin(radDiff);
int16_t rcCommand_PITCH = rcCommand[PITCH]*cosDiff + rcCommand[ROLL]*sinDiff;
rcCommand[ROLL] = rcCommand[ROLL]*cosDiff - rcCommand[PITCH]*sinDiff;
rcCommand[PITCH] = rcCommand_PITCH;
}
#endif
// query at most one multiplexed analog channel per MWii cycle
static uint8_t analogReader =0;
switch (analogReader++ % (3+VBAT_CELLS_NUM)) {
case 0:
{
#if defined(POWERMETER_HARD)
static uint32_t lastRead = currentTime;
static uint8_t ind = 0;
static uint16_t pvec[PSENSOR_SMOOTH], psum;
uint16_t p = analogRead(PSENSORPIN);
//LCDprintInt16(p); LCDcrlf();
//debug[0] = p;
#if PSENSOR_SMOOTH != 1
psum += p;
psum -= pvec[ind];
pvec[ind++] = p;
ind %= PSENSOR_SMOOTH;
p = psum / PSENSOR_SMOOTH;
#endif
powerValue = ( conf.psensornull > p ? conf.psensornull - p : p - conf.psensornull); // do not use abs(), it would induce implicit cast to uint and overrun
analog.amperage = ((uint32_t)powerValue * conf.pint2ma) / 100; // [100mA] //old (will overflow for 65A: powerValue * conf.pint2ma; // [1mA]
pMeter[PMOTOR_SUM] += ((currentTime-lastRead) * (uint32_t)((uint32_t)powerValue*conf.pint2ma))/100000; // [10 mA * msec]
lastRead = currentTime;
#endif // POWERMETER_HARD
break;
}
case 1:
{
#if defined(VBAT) && !defined(VBAT_CELLS)
static uint8_t ind = 0;
static uint16_t vvec[VBAT_SMOOTH], vsum;
uint16_t v = analogRead(V_BATPIN);
#if VBAT_SMOOTH == 1
analog.vbat = (v*VBAT_PRESCALER) / conf.vbatscale + VBAT_OFFSET; // result is Vbatt in 0.1V steps
#else
vsum += v;
vsum -= vvec[ind];
vvec[ind++] = v;
ind %= VBAT_SMOOTH;
#if VBAT_SMOOTH == VBAT_PRESCALER
analog.vbat = vsum / conf.vbatscale + VBAT_OFFSET; // result is Vbatt in 0.1V steps
#elif VBAT_SMOOTH < VBAT_PRESCALER
analog.vbat = (vsum * (VBAT_PRESCALER/VBAT_SMOOTH)) / conf.vbatscale + VBAT_OFFSET; // result is Vbatt in 0.1V steps
#else
analog.vbat = ((vsum /VBAT_SMOOTH) * VBAT_PRESCALER) / conf.vbatscale + VBAT_OFFSET; // result is Vbatt in 0.1V steps
#endif
#endif
#endif // VBAT
break;
}
case 2:
{
#if defined(RX_RSSI)
static uint8_t ind = 0;
static uint16_t rvec[RSSI_SMOOTH], rsum, r;
// http://www.multiwii.com/forum/viewtopic.php?f=8&t=5530
#if defined(RX_RSSI_CHAN)
uint16_t rssi_Input = constrain(rcData[RX_RSSI_CHAN],1000,2000);
r = map((uint16_t)rssi_Input , 1000, 2000, 0, 1023);
#else
r = analogRead(RX_RSSI_PIN);
#endif
#if RSSI_SMOOTH == 1
analog.rssi = r;
#else
rsum += r;
rsum -= rvec[ind];
rvec[ind++] = r;
ind %= RSSI_SMOOTH;
r = rsum / RSSI_SMOOTH;
analog.rssi = r;
#endif
#endif // RX RSSI
break;
}
default: // here analogReader >=4, because of ++ in switch()
{
#if defined(VBAT) && defined(VBAT_CELLS)
if ( (analogReader<4) || (analogReader>4+VBAT_CELLS_NUM-1) ) break;
uint8_t ind = analogReader-4;
static uint16_t vbatcells_pins[VBAT_CELLS_NUM] = VBAT_CELLS_PINS;
static uint8_t vbatcells_offset[VBAT_CELLS_NUM] = VBAT_CELLS_OFFSETS;
static uint8_t vbatcells_div[VBAT_CELLS_NUM] = VBAT_CELLS_DIVS;
uint16_t v = analogRead(vbatcells_pins[ind]);
analog.vbatcells[ind] = vbatcells_offset[ind] + (v << 2) / vbatcells_div[ind]; // result is Vbatt in 0.1V steps
if (ind == VBAT_CELLS_NUM -1) analog.vbat = analog.vbatcells[ind];
#endif // VBAT) && defined(VBAT_CELLS)
break;
} // end default
} // end of switch()
#if defined( POWERMETER_HARD ) && (defined(LOG_VALUES) || defined(LCD_TELEMETRY))
if (analog.amperage > powerValueMaxMAH) powerValueMaxMAH = analog.amperage;
#endif
#if defined(WATTS)
analog.watts = (analog.amperage * analog.vbat) / 100; // [0.1A] * [0.1V] / 100 = [Watt]
#if defined(LOG_VALUES) || defined(LCD_TELEMETRY)
if (analog.watts > wattsMax) wattsMax = analog.watts;
#endif
#endif
#if defined(BUZZER)
alarmHandler(); // external buzzer routine that handles buzzer events globally now
#endif
if ( (calibratingA>0 && ACC ) || (calibratingG>0) ) { // Calibration phasis
LEDPIN_TOGGLE;
} else {
if (f.ACC_CALIBRATED) {LEDPIN_OFF;}
if (f.ARMED) {LEDPIN_ON;}
}
#if defined(LED_RING)
static uint32_t LEDTime;
if ( currentTime > LEDTime ) {
LEDTime = currentTime + 50000;
i2CLedRingState();
}
#endif
#if defined(LED_FLASHER)
auto_switch_led_flasher();
#endif
if ( currentTime > calibratedAccTime ) {
if (! f.SMALL_ANGLES_25) {
// the multi uses ACC and is not calibrated or is too much inclinated
f.ACC_CALIBRATED = 0;
LEDPIN_TOGGLE;
calibratedAccTime = currentTime + 100000;
} else {
f.ACC_CALIBRATED = 1;
}
}
#if !(defined(SERIAL_RX) && defined(PROMINI)) //Only one serial port on ProMini. Skip serial com if SERIAL RX in use. Note: Spek code will auto-call serialCom if GUI data detected on serial0.
serialCom();
#endif
#if defined(POWERMETER)
analog.intPowerMeterSum = (pMeter[PMOTOR_SUM]/PLEVELDIV);
intPowerTrigger1 = conf.powerTrigger1 * PLEVELSCALE;
#endif
#ifdef LCD_TELEMETRY_AUTO
static char telemetryAutoSequence [] = LCD_TELEMETRY_AUTO;
static uint8_t telemetryAutoIndex = 0;
static uint16_t telemetryAutoTimer = 0;
if ( (telemetry_auto) && (! (++telemetryAutoTimer % LCD_TELEMETRY_AUTO_FREQ) ) ){
telemetry = telemetryAutoSequence[++telemetryAutoIndex % strlen(telemetryAutoSequence)];
LCDclear(); // make sure to clear away remnants
}
#endif
#ifdef LCD_TELEMETRY
static uint16_t telemetryTimer = 0;
if (! (++telemetryTimer % LCD_TELEMETRY_FREQ)) {
#if (LCD_TELEMETRY_DEBUG+0 > 0)
telemetry = LCD_TELEMETRY_DEBUG;
#endif
if (telemetry) lcd_telemetry();
}
#endif
#ifdef TELEMETRY
run_telemetry();
#endif
#if GPS & defined(GPS_LED_INDICATOR) // modified by MIS to use STABLEPIN LED for number of sattelites indication
static uint32_t GPSLEDTime; // - No GPS FIX -> LED blink at speed of incoming GPS frames
static uint8_t blcnt; // - Fix and sat no. bellow 5 -> LED off
if(currentTime > GPSLEDTime) { // - Fix and sat no. >= 5 -> LED blinks, one blink for 5 sat, two blinks for 6 sat, three for 7 ...
if(f.GPS_FIX && GPS_numSat >= 5) {
if(++blcnt > 2*GPS_numSat) blcnt = 0;
GPSLEDTime = currentTime + 150000;
if(blcnt >= 10 && ((blcnt%2) == 0)) {STABLEPIN_ON;} else {STABLEPIN_OFF;}
}else{
if((GPS_update == 1) && !f.GPS_FIX) {STABLEPIN_ON;} else {STABLEPIN_OFF;}
blcnt = 0;
}
}
#endif
#if defined(LOG_VALUES) && (LOG_VALUES >= 2)
if (cycleTime > cycleTimeMax) cycleTimeMax = cycleTime; // remember highscore
if (cycleTime < cycleTimeMin) cycleTimeMin = cycleTime; // remember lowscore
#endif
if (f.ARMED) {
#if defined(LCD_TELEMETRY) || defined(ARMEDTIMEWARNING) || defined(LOG_PERMANENT) || defined (TELEMETRY)
armedTime += (uint32_t)cycleTime;
#endif
#if defined(VBAT)
if ( (analog.vbat > NO_VBAT) && (analog.vbat < vbatMin) ) vbatMin = analog.vbat;
#endif
#ifdef LCD_TELEMETRY
#if BARO
if ( (alt.EstAlt > BAROaltMax) ) BAROaltMax = alt.EstAlt;
#endif
#if GPS
if ( (GPS_speed > GPS_speedMax) ) GPS_speedMax = GPS_speed;
#endif
#endif
}
}
void setup() {
SerialOpen(0,SERIAL0_COM_SPEED);
#if defined(PROMICRO)
SerialOpen(1,SERIAL1_COM_SPEED);
#endif
#if defined(MEGA)
SerialOpen(1,SERIAL1_COM_SPEED);
SerialOpen(2,SERIAL2_COM_SPEED);
SerialOpen(3,SERIAL3_COM_SPEED);
#endif
LEDPIN_PINMODE;
POWERPIN_PINMODE;
BUZZERPIN_PINMODE;
STABLEPIN_PINMODE;
POWERPIN_OFF;
initOutput();
readGlobalSet();
#ifndef NO_FLASH_CHECK
#if defined(MEGA)
uint16_t i = 65000; // only first ~64K for mega board due to pgm_read_byte limitation
#else
uint16_t i = 32000;
#endif
uint16_t flashsum = 0;
uint8_t pbyt;
while(i--) {
pbyt = pgm_read_byte(i); // calculate flash checksum
flashsum += pbyt;
flashsum ^= (pbyt<<8);
}
#endif
#ifdef MULTIPLE_CONFIGURATION_PROFILES
global_conf.currentSet=2;
#else
global_conf.currentSet=0;
#endif
while(1) { // check settings integrity
#ifndef NO_FLASH_CHECK
if(readEEPROM()) { // check current setting integrity
if(flashsum != global_conf.flashsum) update_constants(); // update constants if firmware is changed and integrity is OK
}
#else
readEEPROM(); // check current setting integrity
#endif
if(global_conf.currentSet == 0) break; // all checks is done
global_conf.currentSet--; // next setting for check
}
readGlobalSet(); // reload global settings for get last profile number
#ifndef NO_FLASH_CHECK
if(flashsum != global_conf.flashsum) {
global_conf.flashsum = flashsum; // new flash sum
writeGlobalSet(1); // update flash sum in global config
}
#endif
readEEPROM(); // load setting data from last used profile
blinkLED(2,40,global_conf.currentSet+1);
#if GPS
recallGPSconf(); //Load GPS configuration parameteres
#endif
configureReceiver();
#if defined (PILOTLAMP)
PL_INIT;
#endif
#if defined(OPENLRSv2MULTI)
initOpenLRS();
#endif
initSensors();
#if GPS
GPS_set_pids();
#endif
previousTime = micros();
#if defined(GIMBAL)
calibratingA = 512;
#endif
calibratingG = 512;
calibratingB = 200; // 10 seconds init_delay + 200 * 25 ms = 15 seconds before ground pressure settles
#if defined(POWERMETER)
for(uint8_t j=0; j<=PMOTOR_SUM; j++) pMeter[j]=0;
#endif
/************************************/
#if GPS
#if defined(GPS_SERIAL)
GPS_SerialInit();
#endif
GPS_conf.max_wp_number = getMaxWPNumber();
#endif
#if defined(LCD_ETPP) || defined(LCD_LCD03) || defined(LCD_LCD03S) || defined(OLED_I2C_128x64) || defined(OLED_DIGOLE) || defined(LCD_TELEMETRY_STEP)
initLCD();
#endif
#ifdef LCD_TELEMETRY_DEBUG
telemetry_auto = 1;
#endif
#ifdef LCD_CONF_DEBUG
configurationLoop();
#endif
#ifdef TELEMETRY
init_telemetry();
#endif
#ifdef LANDING_LIGHTS_DDR
init_landing_lights();
#endif
#ifdef FASTER_ANALOG_READS
ADCSRA |= _BV(ADPS2) ; ADCSRA &= ~_BV(ADPS1); ADCSRA &= ~_BV(ADPS0); // this speeds up analogRead without loosing too much resolution: http://www.arduino.cc/cgi-bin/yabb2/YaBB.pl?num=1208715493/11
#endif
#if defined(LED_FLASHER)
init_led_flasher();
led_flasher_set_sequence(LED_FLASHER_SEQUENCE);
#endif
f.SMALL_ANGLES_25=1; // important for gyro only conf
#ifdef LOG_PERMANENT
// read last stored set
readPLog();
plog.lifetime += plog.armed_time / 1000000;
plog.start++; // #powercycle/reset/initialize events
// dump plog data to terminal
#ifdef LOG_PERMANENT_SHOW_AT_STARTUP
dumpPLog(0);
#endif
plog.armed_time = 0; // lifetime in seconds
//plog.running = 0; // toggle on arm & disarm to monitor for clean shutdown vs. powercut
#endif
#ifdef DEBUGMSG
debugmsg_append_str("initialization completed\n");
#endif
}
void go_arm() {
if(calibratingG == 0
#if defined(ONLYARMWHENFLAT)
&& f.ACC_CALIBRATED
#endif
#if defined(FAILSAFE)
&& failsafeCnt < 2
#endif
#if GPS && defined(ONLY_ALLOW_ARM_WITH_GPS_3DFIX)
&& (f.GPS_FIX && GPS_numSat >= 5)
#endif
) {
if(!f.ARMED && !f.BARO_MODE) { // arm now!
f.ARMED = 1;
#if defined(HEADFREE)
headFreeModeHold = att.heading;
#endif
magHold = att.heading;
#if defined(VBAT)
if (analog.vbat > NO_VBAT) vbatMin = analog.vbat;
#endif
#ifdef ALTITUDE_RESET_ON_ARM
#if BARO
calibratingB = 10; // calibrate baro to new ground level (10 * 25 ms = ~250 ms non blocking)
#endif
#endif
#ifdef LCD_TELEMETRY // reset some values when arming
#if BARO
BAROaltMax = alt.EstAlt;
#endif
#if GPS
GPS_speedMax = 0;
#endif
#if defined( POWERMETER_HARD ) && (defined(LOG_VALUES) || defined(LCD_TELEMETRY))
powerValueMaxMAH = 0;
#endif
#ifdef WATTS
wattsMax = 0;
#endif
#endif
#ifdef LOG_PERMANENT
plog.arm++; // #arm events
plog.running = 1; // toggle on arm & disarm to monitor for clean shutdown vs. powercut
// write now.
writePLog();
#endif
}
} else if(!f.ARMED) {
blinkLED(2,255,1);
SET_ALARM(ALRM_FAC_ACC, ALRM_LVL_ON);
}
}
void go_disarm() {
if (f.ARMED) {
f.ARMED = 0;
#ifdef LOG_PERMANENT
plog.disarm++; // #disarm events
plog.armed_time = armedTime ; // lifetime in seconds
if (failsafeEvents) plog.failsafe++; // #acitve failsafe @ disarm
if (i2c_errors_count > 10) plog.i2c++; // #i2c errs @ disarm
plog.running = 0; // toggle @ arm & disarm to monitor for clean shutdown vs. powercut
// write now.
writePLog();
#endif
}
}
// ******** Main Loop *********
void loop () {
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
static uint8_t rcSticks; // this hold sticks position for command combos
uint8_t axis,i;
int16_t error,errorAngle;
int16_t delta;
int16_t PTerm = 0,ITerm = 0,DTerm, PTermACC, ITermACC;
static int16_t lastGyro[2] = {0,0};
static int16_t errorAngleI[2] = {0,0};
#if PID_CONTROLLER == 1
static int32_t errorGyroI_YAW;
static int16_t delta1[2],delta2[2];
static int16_t errorGyroI[2] = {0,0};
#elif PID_CONTROLLER == 2
static int16_t delta1[3],delta2[3];
static int32_t errorGyroI[3] = {0,0,0};
static int16_t lastError[3] = {0,0,0};
int16_t deltaSum;
int16_t AngleRateTmp, RateError;
#endif
static uint16_t rcTime = 0;
static int16_t initialThrottleHold;
int16_t rc;
int32_t prop = 0;
#if defined(SERIAL_RX)
if (spekFrameFlags == 0x01) readSerial_RX();
#endif
#if defined(OPENLRSv2MULTI)
Read_OpenLRS_RC();
#endif
#if defined(SERIAL_RX)
if ((spekFrameDone == 0x01) || ((int16_t)(currentTime-rcTime) >0 )) {
spekFrameDone = 0x00;
#else
if ((int16_t)(currentTime-rcTime) >0 ) { // 50Hz
#endif
rcTime = currentTime + 20000;
computeRC();
// Failsafe routine - added by MIS
#if defined(FAILSAFE)
if ( failsafeCnt > (5*FAILSAFE_DELAY) && f.ARMED) { // Stabilize, and set Throttle to specified level
for(i=0; i<3; i++) rcData[i] = MIDRC; // after specified guard time after RC signal is lost (in 0.1sec)
rcData[THROTTLE] = conf.failsafe_throttle;
if (failsafeCnt > 5*(FAILSAFE_DELAY+FAILSAFE_OFF_DELAY)) { // Turn OFF motors after specified Time (in 0.1sec)
go_disarm(); // This will prevent the copter to automatically rearm if failsafe shuts it down and prevents
f.OK_TO_ARM = 0; // to restart accidentely by just reconnect to the tx - you will have to switch off first to rearm
}
failsafeEvents++;
}
if ( failsafeCnt > (5*FAILSAFE_DELAY) && !f.ARMED) { //Turn of "Ok To arm to prevent the motors from spinning after repowering the RX with low throttle and aux to arm
go_disarm(); // This will prevent the copter to automatically rearm if failsafe shuts it down and prevents
f.OK_TO_ARM = 0; // to restart accidentely by just reconnect to the tx - you will have to switch off first to rearm
}
failsafeCnt++;
#endif
// end of failsafe routine - next change is made with RcOptions setting
// ------------------ STICKS COMMAND HANDLER --------------------
// checking sticks positions
uint8_t stTmp = 0;
for(i=0;i<4;i++) {
stTmp >>= 2;
if(rcData[i] > MINCHECK) stTmp |= 0x80; // check for MIN
if(rcData[i] < MAXCHECK) stTmp |= 0x40; // check for MAX
}
if(stTmp == rcSticks) {
if(rcDelayCommand<250) rcDelayCommand++;
} else rcDelayCommand = 0;
rcSticks = stTmp;
// perform actions
if (rcData[THROTTLE] <= MINCHECK) { // THROTTLE at minimum
#if !defined(FIXEDWING)
errorGyroI[ROLL] = 0; errorGyroI[PITCH] = 0;
#if PID_CONTROLLER == 1
errorGyroI_YAW = 0;
#elif PID_CONTROLLER == 2
errorGyroI[YAW] = 0;
#endif
errorAngleI[ROLL] = 0; errorAngleI[PITCH] = 0;
#endif
if (conf.activate[BOXARM] > 0) { // Arming/Disarming via ARM BOX
if ( rcOptions[BOXARM] && f.OK_TO_ARM ) go_arm(); else if (f.ARMED) go_disarm();
}
}
if(rcDelayCommand == 20) {
if(f.ARMED) { // actions during armed
#ifdef ALLOW_ARM_DISARM_VIA_TX_YAW
if (conf.activate[BOXARM] == 0 && rcSticks == THR_LO + YAW_LO + PIT_CE + ROL_CE) go_disarm(); // Disarm via YAW
#endif
#ifdef ALLOW_ARM_DISARM_VIA_TX_ROLL
if (conf.activate[BOXARM] == 0 && rcSticks == THR_LO + YAW_CE + PIT_CE + ROL_LO) go_disarm(); // Disarm via ROLL
#endif
} else { // actions during not armed
i=0;
if (rcSticks == THR_LO + YAW_LO + PIT_LO + ROL_CE) { // GYRO calibration
calibratingG=512;
#if GPS
GPS_reset_home_position();
#endif
#if BARO
calibratingB=10; // calibrate baro to new ground level (10 * 25 ms = ~250 ms non blocking)
#endif
}
#if defined(INFLIGHT_ACC_CALIBRATION)
else if (rcSticks == THR_LO + YAW_LO + PIT_HI + ROL_HI) { // Inflight ACC calibration START/STOP
if (AccInflightCalibrationMeasurementDone){ // trigger saving into eeprom after landing
AccInflightCalibrationMeasurementDone = 0;
AccInflightCalibrationSavetoEEProm = 1;
}else{
AccInflightCalibrationArmed = !AccInflightCalibrationArmed;
#if defined(BUZZER)
if (AccInflightCalibrationArmed) SET_ALARM_BUZZER(ALRM_FAC_TOGGLE, ALRM_LVL_TOGGLE_2);
else SET_ALARM_BUZZER(ALRM_FAC_TOGGLE, ALRM_LVL_TOGGLE_ELSE);
#endif
}
}
#endif
#ifdef MULTIPLE_CONFIGURATION_PROFILES
if (rcSticks == THR_LO + YAW_LO + PIT_CE + ROL_LO) i=1; // ROLL left -> Profile 1
else if (rcSticks == THR_LO + YAW_LO + PIT_HI + ROL_CE) i=2; // PITCH up -> Profile 2
else if (rcSticks == THR_LO + YAW_LO + PIT_CE + ROL_HI) i=3; // ROLL right -> Profile 3
if(i) {
global_conf.currentSet = i-1;
writeGlobalSet(0);
readEEPROM();
blinkLED(2,40,i);
SET_ALARM(ALRM_FAC_TOGGLE, i);
}
#endif
if (rcSticks == THR_LO + YAW_HI + PIT_HI + ROL_CE) { // Enter LCD config
#if defined(LCD_CONF)
configurationLoop(); // beginning LCD configuration
#endif
previousTime = micros();
}
#ifdef ALLOW_ARM_DISARM_VIA_TX_YAW
else if (conf.activate[BOXARM] == 0 && rcSticks == THR_LO + YAW_HI + PIT_CE + ROL_CE) go_arm(); // Arm via YAW
#endif
#ifdef ALLOW_ARM_DISARM_VIA_TX_ROLL
else if (conf.activate[BOXARM] == 0 && rcSticks == THR_LO + YAW_CE + PIT_CE + ROL_HI) go_arm(); // Arm via ROLL
#endif
#ifdef LCD_TELEMETRY_AUTO
else if (rcSticks == THR_LO + YAW_CE + PIT_HI + ROL_LO) { // Auto telemetry ON/OFF
if (telemetry_auto) {
telemetry_auto = 0;
telemetry = 0;
} else
telemetry_auto = 1;
}
#endif
#ifdef LCD_TELEMETRY_STEP
else if (rcSticks == THR_LO + YAW_CE + PIT_HI + ROL_HI) { // Telemetry next step
telemetry = telemetryStepSequence[++telemetryStepIndex % strlen(telemetryStepSequence)];
#if defined( OLED_I2C_128x64)
if (telemetry != 0) i2c_OLED_init();
#elif defined(OLED_DIGOLE)
if (telemetry != 0) i2c_OLED_DIGOLE_init();
#endif
LCDclear();
}
#endif
#if ACC
else if (rcSticks == THR_HI + YAW_LO + PIT_LO + ROL_CE) calibratingA=512; // throttle=max, yaw=left, pitch=min
#endif
#if MAG
else if (rcSticks == THR_HI + YAW_HI + PIT_LO + ROL_CE) f.CALIBRATE_MAG = 1; // throttle=max, yaw=right, pitch=min
#endif
i=0;