-
Notifications
You must be signed in to change notification settings - Fork 460
/
Output.cpp
1617 lines (1553 loc) · 65.4 KB
/
Output.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
#include "Arduino.h"
#include "config.h"
#include "def.h"
#include "types.h"
#include "MultiWii.h"
#include "Alarms.h"
void initializeSoftPWM(void);
#if defined(SERVO)
void initializeServo();
#endif
/**************************************************************************************/
/*************** Motor Pin order ********************/
/**************************************************************************************/
// since we are uing the PWM generation in a direct way, the pin order is just to inizialie the right pins
// its not possible to change a PWM output pin just by changing the order
#if defined(PROMINI)
uint8_t PWM_PIN[8] = {9,10,11,3,6,5,A2,12}; //for a quad+: rear,right,left,front
#endif
#if defined(PROMICRO)
#if !defined(HWPWM6)
#if defined(TEENSY20)
uint8_t PWM_PIN[8] = {14,15,9,12,22,18,16,17}; //for a quad+: rear,right,left,front
#elif defined(A32U4_4_HW_PWM_SERVOS)
uint8_t PWM_PIN[8] = {6,9,10,11,5,13,SW_PWM_P3,SW_PWM_P4}; //
#else
uint8_t PWM_PIN[8] = {9,10,5,6,4,A2,SW_PWM_P3,SW_PWM_P4}; //for a quad+: rear,right,left,front
#endif
#else
#if defined(TEENSY20)
uint8_t PWM_PIN[8] = {14,15,9,12,4,10,16,17}; //for a quad+: rear,right,left,front
#elif defined(A32U4_4_HW_PWM_SERVOS)
uint8_t PWM_PIN[8] = {6,9,10,11,5,13,SW_PWM_P3,SW_PWM_P4}; //
#else
uint8_t PWM_PIN[8] = {9,10,5,6,11,13,SW_PWM_P3,SW_PWM_P4}; //for a quad+: rear,right,left,front
#endif
#endif
#endif
#if defined(MEGA)
uint8_t PWM_PIN[8] = {3,5,6,2,7,8,9,10}; //for a quad+: rear,right,left,front //+ for y6: 7:under right 8:under left
#endif
/**************************************************************************************/
/*************** Software PWM & Servo variables ********************/
/**************************************************************************************/
#if defined(PROMINI) || (defined(PROMICRO) && defined(HWPWM6)) || (defined(MEGA) && defined(MEGA_HW_PWM_SERVOS))
#if (NUMBER_MOTOR > 4)
//for HEX Y6 and HEX6/HEX6X/HEX6H flat for promini
volatile uint8_t atomicPWM_PIN5_lowState;
volatile uint8_t atomicPWM_PIN5_highState;
volatile uint8_t atomicPWM_PIN6_lowState;
volatile uint8_t atomicPWM_PIN6_highState;
#endif
#if (NUMBER_MOTOR > 6)
//for OCTO on promini
volatile uint8_t atomicPWM_PINA2_lowState;
volatile uint8_t atomicPWM_PINA2_highState;
volatile uint8_t atomicPWM_PIN12_lowState;
volatile uint8_t atomicPWM_PIN12_highState;
#endif
#else
#if (NUMBER_MOTOR > 4)
//for HEX Y6 and HEX6/HEX6X/HEX6H and for Promicro
volatile uint16_t atomicPWM_PIN5_lowState;
volatile uint16_t atomicPWM_PIN5_highState;
volatile uint16_t atomicPWM_PIN6_lowState;
volatile uint16_t atomicPWM_PIN6_highState;
#endif
#if (NUMBER_MOTOR > 6)
//for OCTO on Promicro
volatile uint16_t atomicPWM_PINA2_lowState;
volatile uint16_t atomicPWM_PINA2_highState;
volatile uint16_t atomicPWM_PIN12_lowState;
volatile uint16_t atomicPWM_PIN12_highState;
#endif
#endif
#if defined(SERVO)
#if defined(HW_PWM_SERVOS)
// hw servo pwm does not need atomicServo[]
#elif defined(PROMINI) || (defined(PROMICRO) && defined(HWPWM6))
#if defined(AIRPLANE) || defined(HELICOPTER)
// To prevent motor to start at reset. atomicServo[7]=5 or 249 if reversed servo
volatile uint8_t atomicServo[8] = {125,125,125,125,125,125,125,5};
#else
volatile uint8_t atomicServo[8] = {125,125,125,125,125,125,125,125};
#endif
#else
#if defined(AIRPLANE)|| defined(HELICOPTER)
// To prevent motor to start at reset. atomicServo[7]=5 or 249 if reversed servo
volatile uint16_t atomicServo[8] = {8000,8000,8000,8000,8000,8000,8000,320};
#else
volatile uint16_t atomicServo[8] = {8000,8000,8000,8000,8000,8000,8000,8000};
#endif
#endif
#endif
/**************************************************************************************/
/*************** Calculate first and last used servos ********************/
/**************************************************************************************/
#if defined(SERVO)
#if defined(PRI_SERVO_FROM) && defined(SEC_SERVO_FROM)
#if PRI_SERVO_FROM < SEC_SERVO_FROM
#define SERVO_START PRI_SERVO_FROM
#else
#define SERVO_START SEC_SERVO_FROM
#endif
#else
#if defined(PRI_SERVO_FROM)
#define SERVO_START PRI_SERVO_FROM
#endif
#if defined(SEC_SERVO_FROM)
#define SERVO_START SEC_SERVO_FROM
#endif
#endif
#if defined(PRI_SERVO_TO) && defined(SEC_SERVO_TO)
#if PRI_SERVO_TO > SEC_SERVO_TO
#define SERVO_END PRI_SERVO_TO
#else
#define SERVO_END SEC_SERVO_TO
#endif
#else
#if defined(PRI_SERVO_TO)
#define SERVO_END PRI_SERVO_TO
#endif
#if defined(SEC_SERVO_TO)
#define SERVO_END SEC_SERVO_TO
#endif
#endif
#endif
/**************************************************************************************/
/*************** Writes the Servos values to the needed format ********************/
/**************************************************************************************/
void writeServos() {
#if defined(SERVO)
#if defined(PRI_SERVO_FROM) && !defined(HW_PWM_SERVOS) // write primary servos
for(uint8_t i = (PRI_SERVO_FROM-1); i < PRI_SERVO_TO; i++){
#if defined(PROMINI) || (defined(PROMICRO) && defined(HWPWM6)) || (defined(MEGA) && defined(MEGA_HW_PWM_SERVOS))
atomicServo[i] = (servo[i]-1000)>>2;
#else
atomicServo[i] = (servo[i]-1000)<<4;
#endif
}
#endif
#if defined(SEC_SERVO_FROM) && !defined(HW_PWM_SERVOS) // write secundary servos
#if (defined(SERVO_TILT)|| defined(SERVO_MIX_TILT)) && defined(MMSERVOGIMBAL)
// Moving Average Servo Gimbal by Magnetron1
static int16_t mediaMobileServoGimbalADC[3][MMSERVOGIMBALVECTORLENGHT];
static int32_t mediaMobileServoGimbalADCSum[3];
static uint8_t mediaMobileServoGimbalIDX;
uint8_t axis;
mediaMobileServoGimbalIDX = ++mediaMobileServoGimbalIDX % MMSERVOGIMBALVECTORLENGHT;
for (axis=(SEC_SERVO_FROM-1); axis < SEC_SERVO_TO; axis++) {
mediaMobileServoGimbalADCSum[axis] -= mediaMobileServoGimbalADC[axis][mediaMobileServoGimbalIDX];
mediaMobileServoGimbalADC[axis][mediaMobileServoGimbalIDX] = servo[axis];
mediaMobileServoGimbalADCSum[axis] += mediaMobileServoGimbalADC[axis][mediaMobileServoGimbalIDX];
#if defined(PROMINI) || (defined(PROMICRO) && defined(HWPWM6))
atomicServo[axis] = (mediaMobileServoGimbalADCSum[axis] / MMSERVOGIMBALVECTORLENGHT - 1000)>>2;
#else
atomicServo[axis] = (mediaMobileServoGimbalADCSum[axis] / MMSERVOGIMBALVECTORLENGHT - 1000)<<4;
#endif
}
#else
for(uint8_t i = (SEC_SERVO_FROM-1); i < SEC_SERVO_TO; i++){
#if defined(PROMINI) || (defined(PROMICRO) && defined(HWPWM6)) || (defined(MEGA) && defined(MEGA_HW_PWM_SERVOS))
atomicServo[i] = (servo[i]-1000)>>2;
#else
atomicServo[i] = (servo[i]-1000)<<4;
#endif
}
#endif
#endif
// write HW PWM servos for the mega
#if defined(MEGA) && defined(MEGA_HW_PWM_SERVOS)
#if (PRI_SERVO_FROM == 1 || SEC_SERVO_FROM == 1)
OCR5C = servo[0];
#endif
#if (PRI_SERVO_FROM <= 2 && PRI_SERVO_TO >= 2) || (SEC_SERVO_FROM <= 2 && SEC_SERVO_TO >= 2)
OCR5B = servo[1];
#endif
#if (PRI_SERVO_FROM <= 3 && PRI_SERVO_TO >= 3) || (SEC_SERVO_FROM <= 3 && SEC_SERVO_TO >= 3)
OCR5A = servo[2];
#endif
#if (PRI_SERVO_FROM <= 4 && PRI_SERVO_TO >= 4) || (SEC_SERVO_FROM <= 4 && SEC_SERVO_TO >= 4)
OCR1A = servo[3];
#endif
#if (PRI_SERVO_FROM <= 5 && PRI_SERVO_TO >= 5) || (SEC_SERVO_FROM <= 5 && SEC_SERVO_TO >= 5)
OCR1B = servo[4];
#endif
#if (PRI_SERVO_FROM <= 6 && PRI_SERVO_TO >= 6) || (SEC_SERVO_FROM <= 6 && SEC_SERVO_TO >= 6)
OCR4A = servo[5];
#endif
#if (PRI_SERVO_FROM <= 7 && PRI_SERVO_TO >= 7) || (SEC_SERVO_FROM <= 7 && SEC_SERVO_TO >= 7)
OCR4B = servo[6];
#endif
#if (PRI_SERVO_FROM <= 8 && PRI_SERVO_TO >= 8) || (SEC_SERVO_FROM <= 8 && SEC_SERVO_TO >= 8)
OCR4C = servo[7];
#endif
#endif
// write HW PWM servos for the promicro
#if defined(PROMICRO) && defined(A32U4_4_HW_PWM_SERVOS)
#if (PRI_SERVO_FROM <= 7 && PRI_SERVO_TO >= 7)
OCR1A = servo[6];// Pin 9
#endif
#if (PRI_SERVO_FROM <= 5 && PRI_SERVO_TO >= 5)
OCR1B = servo[4];// Pin 10
#endif
#if (PRI_SERVO_FROM <= 6 && PRI_SERVO_TO >= 6)
OCR3A = servo[5];// Pin 5
#endif
#if (PRI_SERVO_FROM <= 4 && PRI_SERVO_TO >= 4)
OCR1C = servo[3];// Pin 11
#endif
#endif
#endif
}
/**************************************************************************************/
/************ Writes the Motors values to the PWM compare register ******************/
/**************************************************************************************/
void writeMotors() { // [1000;2000] => [125;250]
/**************** Specific PWM Timers & Registers for the MEGA's *******************/
#if defined(MEGA)// [1000:2000] => [8000:16000] for timer 3 & 4 for mega
#if (NUMBER_MOTOR > 0)
#ifndef EXT_MOTOR_RANGE
OCR3C = motor[0]<<3; // pin 3
#else
OCR3C = ((motor[0]<<4) - 16000);
#endif
#endif
#if (NUMBER_MOTOR > 1)
#ifndef EXT_MOTOR_RANGE
OCR3A = motor[1]<<3; // pin 5
#else
OCR3A = ((motor[1]<<4) - 16000);
#endif
#endif
#if (NUMBER_MOTOR > 2)
#ifndef EXT_MOTOR_RANGE
OCR4A = motor[2]<<3; // pin 6
#else
OCR4A = ((motor[2]<<4) - 16000);
#endif
#endif
#if (NUMBER_MOTOR > 3)
#ifndef EXT_MOTOR_RANGE
OCR3B = motor[3]<<3; // pin 2
#else
OCR3B = ((motor[3]<<4) - 16000);
#endif
#endif
#if (NUMBER_MOTOR > 4)
#ifndef EXT_MOTOR_RANGE
OCR4B = motor[4]<<3; // pin 7
OCR4C = motor[5]<<3; // pin 8
#else
OCR4B = ((motor[4]<<4) - 16000);
OCR4C = ((motor[5]<<4) - 16000);
#endif
#endif
#if (NUMBER_MOTOR > 6)
#ifndef EXT_MOTOR_RANGE
OCR2B = motor[6]>>3; // pin 9
OCR2A = motor[7]>>3; // pin 10
#else
OCR2B = (motor[6]>>2) - 250;
OCR2A = (motor[7]>>2) - 250;
#endif
#endif
#endif
/******** Specific PWM Timers & Registers for the atmega32u4 (Promicro) ************/
#if defined(PROMICRO)
uint16_t Temp2;
Temp2 = motor[3] - 1000;
#if (NUMBER_MOTOR > 0)
#if defined(A32U4_4_HW_PWM_SERVOS)
// write motor0 to pin 6
// Timer 4 A & D [1000:2000] => [1000:2000]
#ifndef EXT_MOTOR_RANGE
TC4H = motor[0]>>8; OCR4D = (motor[0]&0xFF); // pin 6
#else
TC4H = (((motor[0]-1000)<<1)+16)>>8; OCR4D = ((((motor[0]-1000)<<1)+16)&0xFF); // pin 6
#endif
#else
// Timer 1 A & B [1000:2000] => [8000:16000]
#ifdef EXT_MOTOR_RANGE
OCR1A = ((motor[0]<<4) - 16000) + 128;
#elif defined(EXT_MOTOR_64KHZ)
OCR1A = (motor[0] - 1000) >> 2; // max = 255
#elif defined(EXT_MOTOR_32KHZ)
OCR1A = (motor[0] - 1000) >> 1; // max = 511
#elif defined(EXT_MOTOR_16KHZ)
OCR1A = motor[0] - 1000; // pin 9
#elif defined(EXT_MOTOR_8KHZ)
OCR1A = (motor[0]-1000) << 1; // pin 9
#else
OCR1A = motor[0]<<3; // pin 9
#endif
#endif
#endif
#if (NUMBER_MOTOR > 1)
#ifdef EXT_MOTOR_RANGE
OCR1B = ((motor[1]<<4) - 16000) + 128;
#elif defined(EXT_MOTOR_64KHZ)
OCR1B = (motor[1] - 1000) >> 2;
#elif defined(EXT_MOTOR_32KHZ)
OCR1B = (motor[1] - 1000) >> 1;
#elif defined(EXT_MOTOR_16KHZ)
OCR1B = motor[1] - 1000; // pin 10
#elif defined(EXT_MOTOR_8KHZ)
OCR1B = (motor[1]-1000) << 1; // pin 10
#else
OCR1B = motor[1]<<3; // pin 10
#endif
#endif
#if (NUMBER_MOTOR > 2) // Timer 4 A & D [1000:2000] => [1000:2000]
#if !defined(HWPWM6)
// to write values > 255 to timer 4 A/B we need to split the bytes
#ifndef EXT_MOTOR_RANGE
TC4H = (2047-motor[2])>>8; OCR4A = ((2047-motor[2])&0xFF); // pin 5
#else
TC4H = 2047-(((motor[2]-1000)<<1)+16)>>8; OCR4A = (2047-(((motor[2]-1000)<<1)+16)&0xFF); // pin 5
#endif
#else
#ifdef EXT_MOTOR_RANGE
OCR3A = ((motor[2]<<4) - 16000) + 128;
#elif defined(EXT_MOTOR_64KHZ)
OCR3A = (motor[2] - 1000) >> 2;
#elif defined(EXT_MOTOR_32KHZ)
OCR3A = (motor[2] - 1000) >> 1;
#elif defined(EXT_MOTOR_16KHZ)
OCR3A = motor[2] - 1000; // pin 5
#elif defined(EXT_MOTOR_8KHZ)
OCR3A = (motor[2]-1000) << 1; // pin 5
#else
OCR3A = motor[2]<<3; // pin 5
#endif
#endif
#endif
#if (NUMBER_MOTOR > 3)
#ifdef EXT_MOTOR_RANGE
TC4H = (((motor[3]-1000)<<1)+16)>>8; OCR4D = ((((motor[3]-1000)<<1)+16)&0xFF); // pin 6
#elif defined(EXT_MOTOR_64KHZ)
Temp2 = Temp2 >> 2;
TC4H = Temp2 >> 8;
OCR4D = Temp2 & 0xFF; // pin 6
#elif defined(EXT_MOTOR_32KHZ)
Temp2 = Temp2 >> 1;
TC4H = Temp2 >> 8;
OCR4D = Temp2 & 0xFF; // pin 6
#elif defined(EXT_MOTOR_16KHZ)
TC4H = Temp2 >> 8;
OCR4D = Temp2 & 0xFF; // pin 6
#elif defined(EXT_MOTOR_8KHZ)
TC4H = Temp2 >> 8;
OCR4D = Temp2 & 0xFF; // pin 6
#else
TC4H = motor[3]>>8; OCR4D = (motor[3]&0xFF); // pin 6
#endif
#endif
#if (NUMBER_MOTOR > 4)
#if !defined(HWPWM6)
#if (NUMBER_MOTOR == 6) && !defined(SERVO)
atomicPWM_PIN5_highState = motor[4]<<3;
atomicPWM_PIN5_lowState = 16383-atomicPWM_PIN5_highState;
atomicPWM_PIN6_highState = motor[5]<<3;
atomicPWM_PIN6_lowState = 16383-atomicPWM_PIN6_highState;
#else
atomicPWM_PIN5_highState = ((motor[4]-1000)<<4)+320;
atomicPWM_PIN5_lowState = 15743-atomicPWM_PIN5_highState;
atomicPWM_PIN6_highState = ((motor[5]-1000)<<4)+320;
atomicPWM_PIN6_lowState = 15743-atomicPWM_PIN6_highState;
#endif
#else
#ifndef EXT_MOTOR_RANGE
OCR1C = motor[4]<<3; // pin 11
TC4H = motor[5]>>8; OCR4A = (motor[5]&0xFF); // pin 13
#else
OCR1C = ((motor[4]<<4) - 16000) + 128;
TC4H = (((motor[5]-1000)<<1)+16)>>8; OCR4A = ((((motor[5]-1000)<<1)+16)&0xFF); // pin 13
#endif
#endif
#endif
#if (NUMBER_MOTOR > 6)
#if !defined(HWPWM6)
atomicPWM_PINA2_highState = ((motor[6]-1000)<<4)+320;
atomicPWM_PINA2_lowState = 15743-atomicPWM_PINA2_highState;
atomicPWM_PIN12_highState = ((motor[7]-1000)<<4)+320;
atomicPWM_PIN12_lowState = 15743-atomicPWM_PIN12_highState;
#else
atomicPWM_PINA2_highState = ((motor[6]-1000)>>2)+5;
atomicPWM_PINA2_lowState = 245-atomicPWM_PINA2_highState;
atomicPWM_PIN12_highState = ((motor[7]-1000)>>2)+5;
atomicPWM_PIN12_lowState = 245-atomicPWM_PIN12_highState;
#endif
#endif
#endif
/******** Specific PWM Timers & Registers for the atmega328P (Promini) ************/
#if defined(PROMINI)
#if (NUMBER_MOTOR > 0)
#ifdef EXT_MOTOR_RANGE // 490Hz
OCR1A = ((motor[0]>>2) - 250);
#elif defined(EXT_MOTOR_32KHZ)
OCR1A = (motor[0] - 1000) >> 2; // pin 9
#elif defined(EXT_MOTOR_4KHZ)
OCR1A = (motor[0] - 1000) << 1;
#elif defined(EXT_MOTOR_1KHZ)
OCR1A = (motor[0] - 1000) << 3;
#else
OCR1A = motor[0]>>3; // pin 9
#endif
#endif
#if (NUMBER_MOTOR > 1)
#ifdef EXT_MOTOR_RANGE // 490Hz
OCR1B = ((motor[1]>>2) - 250);
#elif defined(EXT_MOTOR_32KHZ)
OCR1B = (motor[1] - 1000) >> 2; // pin 10
#elif defined(EXT_MOTOR_4KHZ)
OCR1B = (motor[1] - 1000) << 1;
#elif defined(EXT_MOTOR_1KHZ)
OCR1B = (motor[1] - 1000) << 3;
#else
OCR1B = motor[1]>>3; // pin 10
#endif
#endif
#if (NUMBER_MOTOR > 2)
#ifdef EXT_MOTOR_RANGE // 490Hz
OCR2A = ((motor[2]>>2) - 250);
#elif defined(EXT_MOTOR_32KHZ)
OCR2A = (motor[2] - 1000) >> 2; // pin 11
#elif defined(EXT_MOTOR_4KHZ)
OCR2A = (motor[2] - 1000) >> 2;
#elif defined(EXT_MOTOR_1KHZ)
OCR2A = (motor[2] - 1000) >> 2;
#else
OCR2A = motor[2]>>3; // pin 11
#endif
#endif
#if (NUMBER_MOTOR > 3)
#ifdef EXT_MOTOR_RANGE // 490Hz
OCR2B = ((motor[3]>>2) - 250);
#elif defined(EXT_MOTOR_32KHZ)
OCR2B = (motor[3] - 1000) >> 2; // pin 3
#elif defined(EXT_MOTOR_4KHZ)
OCR2B = (motor[3] - 1000) >> 2;
#elif defined(EXT_MOTOR_1KHZ)
OCR2B = (motor[3] - 1000) >> 2;
#else
OCR2B = motor[3]>>3; // pin 3
#endif
#endif
#if (NUMBER_MOTOR > 4)
#if (NUMBER_MOTOR == 6) && !defined(SERVO)
#ifndef EXT_MOTOR_RANGE
atomicPWM_PIN6_highState = motor[4]>>3;
atomicPWM_PIN5_highState = motor[5]>>3;
#else
atomicPWM_PIN6_highState = (motor[4]>>2) - 250;
atomicPWM_PIN5_highState = (motor[5]>>2) - 250;
#endif
atomicPWM_PIN6_lowState = 255-atomicPWM_PIN6_highState;
atomicPWM_PIN5_lowState = 255-atomicPWM_PIN5_highState;
#else //note: EXT_MOTOR_RANGE not possible here
atomicPWM_PIN6_highState = ((motor[4]-1000)>>2)+5;
atomicPWM_PIN6_lowState = 245-atomicPWM_PIN6_highState;
atomicPWM_PIN5_highState = ((motor[5]-1000)>>2)+5;
atomicPWM_PIN5_lowState = 245-atomicPWM_PIN5_highState;
#endif
#endif
#if (NUMBER_MOTOR > 6) //note: EXT_MOTOR_RANGE not possible here
atomicPWM_PINA2_highState = ((motor[6]-1000)>>2)+5;
atomicPWM_PINA2_lowState = 245-atomicPWM_PINA2_highState;
atomicPWM_PIN12_highState = ((motor[7]-1000)>>2)+5;
atomicPWM_PIN12_lowState = 245-atomicPWM_PIN12_highState;
#endif
#endif
}
/**************************************************************************************/
/************ Writes the mincommand to all Motors ******************/
/**************************************************************************************/
void writeAllMotors(int16_t mc) { // Sends commands to all motors
for (uint8_t i =0;i<NUMBER_MOTOR;i++) {
motor[i]=mc;
}
writeMotors();
}
/**************************************************************************************/
/************ Initialize the PWM Timers and Registers ******************/
/**************************************************************************************/
void initOutput() {
/**************** mark all PWM pins as Output ******************/
for(uint8_t i=0;i<NUMBER_MOTOR;i++) {
pinMode(PWM_PIN[i],OUTPUT);
}
/**************** Specific PWM Timers & Registers for the MEGA's ******************/
#if defined(MEGA)
#if (NUMBER_MOTOR > 0)
// init 16bit timer 3
TCCR3A |= (1<<WGM31); // phase correct mode
TCCR3A &= ~(1<<WGM30);
TCCR3B |= (1<<WGM33);
TCCR3B &= ~(1<<CS31); // no prescaler
ICR3 |= 0x3FFF; // TOP to 16383;
TCCR3A |= _BV(COM3C1); // connect pin 3 to timer 3 channel C
#endif
#if (NUMBER_MOTOR > 1)
TCCR3A |= _BV(COM3A1); // connect pin 5 to timer 3 channel A
#endif
#if (NUMBER_MOTOR > 2)
// init 16bit timer 4
TCCR4A |= (1<<WGM41); // phase correct mode
TCCR4A &= ~(1<<WGM40);
TCCR4B |= (1<<WGM43);
TCCR4B &= ~(1<<CS41); // no prescaler
ICR4 |= 0x3FFF; // TOP to 16383;
TCCR4A |= _BV(COM4A1); // connect pin 6 to timer 4 channel A
#endif
#if (NUMBER_MOTOR > 3)
TCCR3A |= _BV(COM3B1); // connect pin 2 to timer 3 channel B
#endif
#if (NUMBER_MOTOR > 4)
TCCR4A |= _BV(COM4B1); // connect pin 7 to timer 4 channel B
TCCR4A |= _BV(COM4C1); // connect pin 8 to timer 4 channel C
#endif
#if (NUMBER_MOTOR > 6)
// timer 2 is a 8bit timer so we cant change its range
TCCR2A |= _BV(COM2B1); // connect pin 9 to timer 2 channel B
TCCR2A |= _BV(COM2A1); // connect pin 10 to timer 2 channel A
#endif
#endif
/******** Specific PWM Timers & Registers for the atmega32u4 (Promicro) ************/
#if defined(PROMICRO)
#if defined(EXT_MOTOR_64KHZ) || defined(EXT_MOTOR_32KHZ) || defined(EXT_MOTOR_16KHZ) || defined(EXT_MOTOR_8KHZ)
TCCR1A = (1<<WGM11);
TCCR1B = (1<<WGM13) | (1<<WGM12) | (1<<CS10);
TCCR3A = (1<<WGM31);
TCCR3B = (1<<WGM33) | (1<<WGM32) | (1<<CS30);
#if defined(EXT_MOTOR_64KHZ)
ICR1 = 0x00FF; // TOP to 255;
ICR3 = 0x00FF; // TOP to 255;
TC4H = 0x00;
OCR4C = 0xFF; // phase and frequency correct mode & top to 255
TCCR4B = (1<<CS40); // prescaler to 1
#elif defined(EXT_MOTOR_32KHZ)
ICR1 = 0x01FF; // TOP to 511;
ICR3 = 0x01FF; // TOP to 511;
TC4H = 0x01;
OCR4C = 0xFF; // phase and frequency correct mode & top to 511
TCCR4B = (1<<CS40); // prescaler to 1
#elif defined(EXT_MOTOR_16KHZ)
ICR1 = 0x03FF; // TOP to 1023;
ICR3 = 0x03FF; // TOP to 1023;
TC4H = 0x03;
OCR4C = 0xFF; // phase and frequency correct mode & top to 1023
TCCR4B = (1<<CS40); // prescaler to 1
#elif defined(EXT_MOTOR_8KHZ)
ICR1 = 0x07FF; // TOP to 2046;
ICR3 = 0x07FF; // TOP to 2046;
TC4H = 0x3;
OCR4C = 0xFF; // phase and frequency correct mode
TCCR4B = (1<<CS41); // prescaler to 2
#endif
TCCR1A |= _BV(COM1A1); // connect pin 9 to timer 1 channel A
TCCR1A |= _BV(COM1B1); // connect pin 10 to timer 1 channel B
TCCR3A |= _BV(COM3A1); // connect pin 5 to timer 3 channel A
TCCR4D = 0;
TCCR4C |= (1<<COM4D1)|(1<<PWM4D); // connect pin 6 to timer 4 channel D
#else
#if (NUMBER_MOTOR > 0) && ( !defined(A32U4_4_HW_PWM_SERVOS) )
TCCR1A |= (1<<WGM11); // phase correct mode & no prescaler
TCCR1A &= ~(1<<WGM10);
TCCR1B &= ~(1<<WGM12) & ~(1<<CS11) & ~(1<<CS12);
TCCR1B |= (1<<WGM13) | (1<<CS10);
ICR1 |= 0x3FFF; // TOP to 16383;
TCCR1A |= _BV(COM1A1); // connect pin 9 to timer 1 channel A
#endif
#if (NUMBER_MOTOR > 1)
TCCR1A |= _BV(COM1B1); // connect pin 10 to timer 1 channel B
#endif
#if (NUMBER_MOTOR > 2)
#if !defined(HWPWM6) // timer 4A
TCCR4E |= (1<<ENHC4); // enhanced pwm mode
TCCR4B &= ~(1<<CS41); TCCR4B |= (1<<CS42)|(1<<CS40); // prescaler to 16
TCCR4D |= (1<<WGM40); TC4H = 0x3; OCR4C = 0xFF; // phase and frequency correct mode & top to 1023 but with enhanced pwm mode we have 2047
TCCR4A |= (1<<COM4A0)|(1<<PWM4A); // connect pin 5 to timer 4 channel A
#else // timer 3A
TCCR3A |= (1<<WGM31); // phase correct mode & no prescaler
TCCR3A &= ~(1<<WGM30);
TCCR3B &= ~(1<<WGM32) & ~(1<<CS31) & ~(1<<CS32);
TCCR3B |= (1<<WGM33) | (1<<CS30);
ICR3 |= 0x3FFF; // TOP to 16383;
TCCR3A |= _BV(COM3A1); // connect pin 5 to timer 3 channel A
#endif
#endif
#if (NUMBER_MOTOR > 3) || ( (NUMBER_MOTOR > 0) && defined(A32U4_4_HW_PWM_SERVOS) )
#if defined(HWPWM6)
TCCR4E |= (1<<ENHC4); // enhanced pwm mode
TCCR4B &= ~(1<<CS41); TCCR4B |= (1<<CS42)|(1<<CS40); // prescaler to 16
TCCR4D |= (1<<WGM40); TC4H = 0x3; OCR4C = 0xFF; // phase and frequency correct mode & top to 1023 but with enhanced pwm mode we have 2047
#endif
TCCR4C |= (1<<COM4D1)|(1<<PWM4D); // connect pin 6 to timer 4 channel D
#endif
#if (NUMBER_MOTOR > 4)
#if defined(HWPWM6)
TCCR1A |= _BV(COM1C1); // connect pin 11 to timer 1 channel C
TCCR4A |= (1<<COM4A1)|(1<<PWM4A); // connect pin 13 to timer 4 channel A
#else
initializeSoftPWM();
#endif
#endif
#if (NUMBER_MOTOR > 6)
#if defined(HWPWM6)
initializeSoftPWM();
#endif
#endif
#endif
#endif
/******** Specific PWM Timers & Registers for the atmega328P (Promini) ************/
#if defined(PROMINI)
#if defined(EXT_MOTOR_32KHZ)
TCCR1A = (1<<WGM11); // phase correct mode & no prescaler
TCCR1B = (1<<WGM13) | (1<<CS10);
ICR1 = 0x00FF; // TOP to 255;
TCCR2B = (1<<CS20);
#elif defined(EXT_MOTOR_4KHZ)
TCCR1A = (1<<WGM11); // phase correct mode & no prescaler
TCCR1B = (1<<WGM13) | (1<<CS10);
ICR1 = 0x07F8; // TOP to 1023;
TCCR2B = (1<<CS21);
#elif defined(EXT_MOTOR_1KHZ)
TCCR1A = (1<<WGM11); // phase correct mode & no prescaler
TCCR1B = (1<<WGM13) | (1<<CS10);
ICR1 = 0x1FE0; // TOP to 8184;
TCCR2B = (1<<CS20) | (1<<CS21);
#endif
#if (NUMBER_MOTOR > 0)
TCCR1A |= _BV(COM1A1); // connect pin 9 to timer 1 channel A
#endif
#if (NUMBER_MOTOR > 1)
TCCR1A |= _BV(COM1B1); // connect pin 10 to timer 1 channel B
#endif
#if (NUMBER_MOTOR > 2)
TCCR2A |= _BV(COM2A1); // connect pin 11 to timer 2 channel A
#endif
#if (NUMBER_MOTOR > 3)
TCCR2A |= _BV(COM2B1); // connect pin 3 to timer 2 channel B
#endif
#if (NUMBER_MOTOR > 4) // PIN 5 & 6 or A0 & A1
initializeSoftPWM();
#if defined(A0_A1_PIN_HEX) || (NUMBER_MOTOR > 6)
pinMode(5,INPUT);pinMode(6,INPUT); // we reactivate the INPUT affectation for these two PINs
pinMode(A0,OUTPUT);pinMode(A1,OUTPUT);
#endif
#endif
#endif
/******** special version of MultiWii to calibrate all attached ESCs ************/
#if defined(ESC_CALIB_CANNOT_FLY)
writeAllMotors(ESC_CALIB_HIGH);
blinkLED(2,20, 2);
delay(4000);
writeAllMotors(ESC_CALIB_LOW);
blinkLED(3,20, 2);
while (1) {
delay(5000);
blinkLED(4,20, 2);
SET_ALARM_BUZZER(ALRM_FAC_CONFIRM, ALRM_LVL_CONFIRM_2);
}
exit; // statement never reached
#endif
writeAllMotors(MINCOMMAND);
delay(300);
#if defined(SERVO)
initializeServo();
#endif
}
#if defined(SERVO)
/**************************************************************************************/
/************ Initialize the PWM Servos ******************/
/**************************************************************************************/
void initializeServo() {
#if !defined(HW_PWM_SERVOS)
// do pins init
#if (PRI_SERVO_FROM == 1) || (SEC_SERVO_FROM == 1)
SERVO_1_PINMODE;
#endif
#if (PRI_SERVO_FROM <= 2 && PRI_SERVO_TO >= 2) || (SEC_SERVO_FROM <= 2 && SEC_SERVO_TO >= 2)
SERVO_2_PINMODE;
#endif
#if (PRI_SERVO_FROM <= 3 && PRI_SERVO_TO >= 3) || (SEC_SERVO_FROM <= 3 && SEC_SERVO_TO >= 3)
SERVO_3_PINMODE;
#endif
#if (PRI_SERVO_FROM <= 4 && PRI_SERVO_TO >= 4) || (SEC_SERVO_FROM <= 4 && SEC_SERVO_TO >= 4)
SERVO_4_PINMODE;
#endif
#if (PRI_SERVO_FROM <= 5 && PRI_SERVO_TO >= 5) || (SEC_SERVO_FROM <= 5 && SEC_SERVO_TO >= 5)
SERVO_5_PINMODE;
#endif
#if (PRI_SERVO_FROM <= 6 && PRI_SERVO_TO >= 6) || (SEC_SERVO_FROM <= 6 && SEC_SERVO_TO >= 6)
SERVO_6_PINMODE;
#endif
#if (PRI_SERVO_FROM <= 7 && PRI_SERVO_TO >= 7) || (SEC_SERVO_FROM <= 7 && SEC_SERVO_TO >= 7)
SERVO_7_PINMODE;
#endif
#if (PRI_SERVO_FROM <= 8 && PRI_SERVO_TO >= 8) || (SEC_SERVO_FROM <= 8 && SEC_SERVO_TO >= 8)
SERVO_8_PINMODE;
#endif
#endif
#if defined(SERVO_1_HIGH)
#if defined(PROMINI) || (defined(PROMICRO) && defined(HWPWM6)) // uses timer 0 Comperator A (8 bit)
TCCR0A = 0; // normal counting mode
TIMSK0 |= (1<<OCIE0A); // Enable CTC interrupt
#define SERVO_ISR TIMER0_COMPA_vect
#define SERVO_CHANNEL OCR0A
#define SERVO_1K_US 250
#endif
#if (defined(PROMICRO) && !defined(HWPWM6)) // uses timer 3 Comperator A (11 bit)
TCCR3A &= ~(1<<WGM30) & ~(1<<WGM31); //normal counting & no prescaler
TCCR3B &= ~(1<<WGM32) & ~(1<<CS31) & ~(1<<CS32) & ~(1<<WGM33);
TCCR3B |= (1<<CS30);
TIMSK3 |= (1<<OCIE3A); // Enable CTC interrupt
#define SERVO_ISR TIMER3_COMPA_vect
#define SERVO_CHANNEL OCR3A
#define SERVO_1K_US 16000
#endif
#if defined(MEGA) // uses timer 5 Comperator A (11 bit)
TCCR5A &= ~(1<<WGM50) & ~(1<<WGM51); //normal counting & no prescaler
TCCR5B &= ~(1<<WGM52) & ~(1<<CS51) & ~(1<<CS52) & ~(1<<WGM53);
TCCR5B |= (1<<CS50);
TIMSK5 |= (1<<OCIE5A); // Enable CTC interrupt
#define SERVO_ISR TIMER5_COMPA_vect
#define SERVO_CHANNEL OCR5A
#define SERVO_1K_US 16000
#endif
#endif
#if defined(MEGA) && defined(MEGA_HW_PWM_SERVOS)
#if defined(SERVO_RFR_RATE)
#if (SERVO_RFR_RATE < 20)
#define SERVO_RFR_RATE 20
#endif
#if (SERVO_RFR_RATE > 400)
#define SERVO_RFR_RATE 400
#endif
#else
#if defined(SERVO_RFR_50HZ)
#define SERVO_RFR_RATE 50
#elif defined(SERVO_RFR_160HZ)
#define SERVO_RFR_RATE 160
#elif defined(SERVO_RFR_300HZ)
#define SERVO_RFR_RATE 300
#endif
#endif
#define SERVO_TOP_VAL (uint16_t)(1000000L / SERVO_RFR_RATE)
// init Timer 5, 1 and 4 of the mega for hw PWM
TIMSK5 &= ~(1<<OCIE5A); // Disable software PWM
#if (PRI_SERVO_TO >= 1) || (SEC_SERVO_TO >= 1)
TCCR5A |= (1<<WGM51); // phase correct mode & prescaler to 8 = 1us resolution
TCCR5A &= ~(1<<WGM50);
TCCR5B &= ~(1<<WGM52) & ~(1<<CS50) & ~(1<<CS52);
TCCR5B |= (1<<WGM53) | (1<<CS51);
ICR5 = SERVO_TOP_VAL;
#if (PRI_SERVO_FROM == 1 || SEC_SERVO_FROM == 1)
pinMode(44,OUTPUT);
TCCR5A |= (1<<COM5C1); // pin 44
#endif
#if (PRI_SERVO_FROM <= 2 && PRI_SERVO_TO >= 2) || (SEC_SERVO_FROM <= 2 && SEC_SERVO_TO >= 2)
pinMode(45,OUTPUT);
TCCR5A |= (1<<COM5B1); // pin 45
#endif
#if (PRI_SERVO_FROM <= 3 && PRI_SERVO_TO >= 3) || (SEC_SERVO_FROM <= 3 && SEC_SERVO_TO >= 3)
pinMode(46,OUTPUT);
TCCR5A |= (1<<COM5A1); // pin 46
#endif
#endif
#if (PRI_SERVO_TO >= 4) || (SEC_SERVO_TO >= 4)
TCCR1A |= (1<<WGM11); // phase correct mode & prescaler to 8
TCCR1A &= ~(1<<WGM10);
TCCR1B &= ~(1<<WGM12) & ~(1<<CS10) & ~(1<<CS12);
TCCR1B |= (1<<WGM13) | (1<<CS11);
ICR1 = SERVO_TOP_VAL;
#if (PRI_SERVO_FROM <= 4 && PRI_SERVO_TO >= 4) || (SEC_SERVO_FROM <= 4 && SEC_SERVO_TO >= 4)
pinMode(11, OUTPUT);
TCCR1A |= (1<<COM1A1); // pin 11
#endif
#if (PRI_SERVO_FROM <= 5 && PRI_SERVO_TO >= 5) || (SEC_SERVO_FROM <= 5 && SEC_SERVO_TO >= 5)
pinMode(12,OUTPUT);
TCCR1A |= (1<<COM1B1); // pin 12
#endif
#endif
#if (PRI_SERVO_TO >= 6) || (SEC_SERVO_TO >= 6)
// init 16bit timer 4
TCCR4A |= (1<<WGM41); // phase correct mode
TCCR4A &= ~(1<<WGM40);
TCCR4B &= ~(1<<WGM42) & ~(1<<CS40) & ~(1<<CS42);
TCCR4B |= (1<<WGM43) | (1<<CS41);
ICR4 = SERVO_TOP_VAL;
#if (PRI_SERVO_FROM <= 6 && PRI_SERVO_TO >= 6) || (SEC_SERVO_FROM <= 6 && SEC_SERVO_TO >= 6)
pinMode(6,OUTPUT);
TCCR4A |= _BV(COM4A1); // connect pin 6 to timer 4 channel A
#endif
#if (PRI_SERVO_FROM <= 7 && PRI_SERVO_TO >= 7) || (SEC_SERVO_FROM <= 7 && SEC_SERVO_TO >= 7)
pinMode(7,OUTPUT);
TCCR4A |= _BV(COM4B1); // connect pin 7 to timer 4 channel B
#endif
#if (PRI_SERVO_FROM <= 8 && PRI_SERVO_TO >= 8) || (SEC_SERVO_FROM <= 8 && SEC_SERVO_TO >= 8)
#if defined(AIRPLANE) || defined(HELICOPTER)
servo[7] = MINCOMMAND; // Trhottle at minimum for airplane and heli
OCR4C = MINCOMMAND;
#endif
pinMode(8,OUTPUT);
TCCR4A |= _BV(COM4C1); // connect pin 8 to timer 4 channel C
#endif
#endif
#endif // mega hw pwm
#if defined(PROMICRO) && defined(A32U4_4_HW_PWM_SERVOS)
// atm. always initialize 4 servos to pins 9, 10, 11, 5
TIMSK1 &= ~(1<<OCIE1A) & ~(1<<OCIE1B) & ~(1<<OCIE1C);
TCCR1A |= (1<<WGM11); // phase correct mode & prescaler to 8
TCCR1A &= ~(1<<WGM10);
TCCR1B &= ~(1<<WGM12) & ~(1<<CS10) & ~(1<<CS12);
TCCR1B |= (1<<WGM13) | (1<<CS11);
pinMode(9,OUTPUT);
TCCR1A |= (1<<COM1A1); // pin 9
pinMode(10,OUTPUT);
TCCR1A |= (1<<COM1B1); // pin 10
pinMode(11,OUTPUT);
TCCR1A |= (1<<COM1C1); // pin 11
TCCR3A |= (1<<WGM31); // phase correct mode & prescaler to 8
TCCR3A &= ~(1<<WGM30);
TCCR3B &= ~(1<<WGM32) & ~(1<<CS30) & ~(1<<CS32);
TCCR3B |= (1<<WGM33) | (1<<CS31);
pinMode(5,OUTPUT);
TCCR3A |= (1<<COM3A1); // pin 5
#if defined(SERVO_RFR_RATE)
#if (SERVO_RFR_RATE < 50) || (SERVO_RFR_RATE > 400)
#error "* invalid SERVO_RFR_RATE specified"
#endif
#define SERVO_TOP_VAL (uint16_t)(1000000L / SERVO_RFR_RATE)
#elif defined(SERVO_RFR_50HZ)
#define SERVO_TOP_VAL 16700
#elif defined(SERVO_RFR_160HZ)
#define SERVO_TOP_VAL 6200
#elif defined(SERVO_RFR_300HZ)
#define SERVO_TOP_VAL 3300
#else
#error "* must set SERVO_RFR_RATE or one of the fixed refresh rates of 50, 160 or 300 Hz"
#endif
#if defined(SERVO_PIN5_RFR_RATE)
#if (SERVO_PIN5_RFR_RATE < 50) || (SERVO_PIN5_RFR_RATE > 400)
#error "* invalid SERVO_PIN5_RFR_RATE specified"
#endif
#define SERVO_PIN5_TOP_VAL (uint16_t)(1000000L / SERVO_PIN5_RFR_RATE)
#else
#define SERVO_PIN5_TOP_VAL SERVO_TOP_VAL
#endif
ICR1 = SERVO_TOP_VAL; // set TOP timer 1
ICR3 = SERVO_PIN5_TOP_VAL; // set TOP timer 3
#endif // promicro hw pwm
}
/**************************************************************************************/
/************ Servo software PWM generation ******************/
/**************************************************************************************/
// prescaler is set by default to 64 on Timer0
// Duemilanove : 16MHz / 64 => 4 us
// 256 steps = 1 counter cycle = 1024 us
// for servo 2-8
// its almost the same as for servo 1
#if defined(SERVO_1_HIGH) && !defined(A32U4_4_HW_PWM_SERVOS)
#define SERVO_PULSE(PIN_HIGH,ACT_STATE,SERVO_NUM,LAST_PIN_LOW) \
}else if(state == ACT_STATE){ \
LAST_PIN_LOW; \
PIN_HIGH; \
SERVO_CHANNEL+=SERVO_1K_US; \
state++; \
}else if(state == ACT_STATE+1){ \
SERVO_CHANNEL+=atomicServo[SERVO_NUM]; \
state++; \
ISR(SERVO_ISR) {
static uint8_t state = 0; // indicates the current state of the chain
if(state == 0){
SERVO_1_HIGH; // set servo 1's pin high
SERVO_CHANNEL+=SERVO_1K_US; // wait 1000us
state++; // count up the state
}else if(state==1){
SERVO_CHANNEL+=atomicServo[SERVO_1_ARR_POS]; // load the servo's value (0-1000us)
state++; // count up the state
#if defined(SERVO_2_HIGH)
SERVO_PULSE(SERVO_2_HIGH,2,SERVO_2_ARR_POS,SERVO_1_LOW); // the same here
#endif
#if defined(SERVO_3_HIGH)
SERVO_PULSE(SERVO_3_HIGH,4,SERVO_3_ARR_POS,SERVO_2_LOW);
#endif
#if defined(SERVO_4_HIGH)
SERVO_PULSE(SERVO_4_HIGH,6,SERVO_4_ARR_POS,SERVO_3_LOW);
#endif
#if defined(SERVO_5_HIGH)
SERVO_PULSE(SERVO_5_HIGH,8,SERVO_5_ARR_POS,SERVO_4_LOW);
#endif
#if defined(SERVO_6_HIGH)
SERVO_PULSE(SERVO_6_HIGH,10,SERVO_6_ARR_POS,SERVO_5_LOW);
#endif
#if defined(SERVO_7_HIGH)
SERVO_PULSE(SERVO_7_HIGH,12,SERVO_7_ARR_POS,SERVO_6_LOW);
#endif
#if defined(SERVO_8_HIGH)
SERVO_PULSE(SERVO_8_HIGH,14,SERVO_8_ARR_POS,SERVO_7_LOW);
#endif
}else{
LAST_LOW;
#if defined(SERVO_RFR_300HZ)
#if defined(SERVO_3_HIGH) // if there are 3 or more servos we dont need to slow it down
SERVO_CHANNEL+=(SERVO_1K_US>>3); // 0 would be better but it causes bad jitter
state=0;
#else // if there are less then 3 servos we need to slow it to not go over 300Hz (the highest working refresh rate for the digital servos for what i know..)
SERVO_CHANNEL+=SERVO_1K_US;
if(state<4){
state+=2;
}else{
state=0;
}
#endif
#endif
#if defined(SERVO_RFR_160HZ)
#if defined(SERVO_4_HIGH) // if there are 4 or more servos we dont need to slow it down
SERVO_CHANNEL+=(SERVO_1K_US>>3); // 0 would be better but it causes bad jitter
state=0;
#else // if there are less then 4 servos we need to slow it to not go over ~170Hz (the highest working refresh rate for analog servos)
SERVO_CHANNEL+=SERVO_1K_US;
if(state<8){
state+=2;
}else{
state=0;
}
#endif
#endif
#if defined(SERVO_RFR_50HZ) // to have ~ 50Hz for all servos
SERVO_CHANNEL+=SERVO_1K_US;
if(state<30){
state+=2;
}else{
state=0;
}
#endif
}
}
#endif
#endif
/**************************************************************************************/
/************ Motor software PWM generation ******************/
/**************************************************************************************/
// SW PWM is only used if there are not enough HW PWM pins (for exampe hexa on a promini)
#if (NUMBER_MOTOR > 4) && (defined(PROMINI) || defined(PROMICRO))
/**************** Pre define the used ISR's and Timerchannels ******************/
#if !defined(PROMICRO)
#define SOFT_PWM_ISR1 TIMER0_COMPB_vect
#define SOFT_PWM_ISR2 TIMER0_COMPA_vect
#define SOFT_PWM_CHANNEL1 OCR0B
#define SOFT_PWM_CHANNEL2 OCR0A
#elif !defined(HWPWM6)
#define SOFT_PWM_ISR1 TIMER3_COMPB_vect
#define SOFT_PWM_ISR2 TIMER3_COMPC_vect
#define SOFT_PWM_CHANNEL1 OCR3B
#define SOFT_PWM_CHANNEL2 OCR3C
#else
#define SOFT_PWM_ISR2 TIMER0_COMPB_vect
#define SOFT_PWM_CHANNEL2 OCR0B
#endif
/**************** Initialize Timers and PWM Channels ******************/
void initializeSoftPWM(void) {