forked from multiwii/multiwii-firmware
-
Notifications
You must be signed in to change notification settings - Fork 0
/
def.h
1997 lines (1838 loc) · 76.5 KB
/
def.h
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
#ifndef DEF_H_
#define DEF_H_
/**************************************************************************************/
/*************** test configurations ********************/
/**************************************************************************************/
#if COPTERTEST == 1
#define QUADP
#define WMP
#elif COPTERTEST == 2
#define FLYING_WING
#define WMP
#define BMA020
#define FAILSAFE
#define LCD_CONF
#define LCD_TEXTSTAR
#define VBAT
#define POWERMETER_SOFT
#elif COPTERTEST == 3
#define TRI
#define FREEIMUv035_MS
#define BUZZER
#define VBAT
#define POWERMETER_HARD
#define LCD_CONF
#define LCD_CONF_AUX
#define LCD_VT100
#define LCD_TELEMETRY
#define LCD_TELEMETRY_STEP "01245"
#define LOG_VALUES 1
#define SUPPRESS_BARO_ALTHOLD
#define VARIOMETER 12
#elif COPTERTEST == 4
#define QUADX
#define CRIUS_SE
#define SPEKTRUM 2048
#define LED_RING
#define GPS_SERIAL 2
#define NMEA
#define LOG_VALUES 2
#define LOG_PERMANENT
#define LOG_PERMANENT_SERVICE_LIFETIME 36000
#elif COPTERTEST == 5
#define HELI_120_CCPM
#define CRIUS_LITE
#undef DISABLE_POWER_PIN
#define RCAUXPIN8
#define OLED_I2C_128x64
#define LCD_TELEMETRY
#define LOG_VALUES 3
#define DEBUG
#undef SERVO_RFR_50HZ
#define SERVO_RFR_160HZ
#define VBAT
#define POWERMETER_SOFT
#define MMGYRO 10
#define MMGYROVECTORLENGTH 15
#define GYRO_SMOOTHING {45, 45, 50}
#define INFLIGHT_ACC_CALIBRATION
#define LOG_PERMANENT
#define LOG_PERMANENT_SHOW_AT_STARTUP
#define LOG_PERMANENT_SHOW_AT_L
#define LOG_PERMANENT_SERVICE_LIFETIME 36000
#define GOVERNOR_P 0
#define GOVERNOR_D 10
#define YAW_COLL_PRECOMP 15
#define YAW_COLL_PRECOMP_DEADBAND 130
#define VOLTAGEDROP_COMPENSATION
#elif COPTERTEST == 6
#define HEX6H
#define DIYFLYING_MAGE_V1
#define BUZZER
#define RCOPTIONSBEEP // ca. 80byte
#define ARMEDTIMEWARNING 480 // 8 min = 480seconds
#define VBAT
#define VOLTAGEDROP_COMPENSATION
#define MEGA_HW_PWM_SERVOS
#define SERVO_RFR_RATE 300 // In Hz, you can set it from 20 to 400Hz, used only in HW PWM mode
#define LOG_VALUES 1
#define DEBUG
#define MULTIPLE_CONFIGURATION_PROFILES
#define DISPLAY_FONT_DSIZE
#define OLED_DIGOLE
#define LCD_CONF
#elif COPTERTEST == 7
#define HELI_120_CCPM
#define YAW_COLL_PRECOMP 15
#define YAW_COLL_PRECOMP_DEADBAND 130
#define NANOWII
#define FORCE_ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = X; imu.accADC[PITCH] = Y; imu.accADC[YAW] = Z;}
#define FORCE_GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = -Y; imu.gyroADC[PITCH] = X; imu.gyroADC[YAW] = -Z;}
#define A32U4_4_HW_PWM_SERVOS
#define SERVO_RFR_RATE 200 // 200 for graupner is ok
#define SERVO_PIN5_RFR_RATE 165 // In Hz, you can set it from 20 to 400Hz, used only in HW PWM mode for mega and 32u4
#define SPEKTRUM 1024
#define BUZZER
#define RCOPTIONSBEEP // ca. 80byte
#define VBAT
#define LOG_VALUES 1
#define DISPLAY_FONT_DSIZE
#define OLED_DIGOLE
#define LCD_CONF
#define LCD_TELEMETRY
#define LCD_TELEMETRY_AUTO "1"
#define LCD_TELEMETRY_STEP "F14$5R"
#define LOG_PERMANENT
#define LOG_PERMANENT_SHOW_AFTER_CONFIG
#define SUPPRESS_OTHER_SERIAL_COMMANDS
#define SUPPRESS_DEFAULTS_FROM_GUI
#define NO_FLASH_CHECK
#define DEBUG_FREE
#elif COPTERTEST == 8
#define BI
#define ITG3200
#define PID_CONTROLLER 2
#define ESC_CALIB_CANNOT_FLY
#elif COPTERTEST == 9
#define AIRPLANE
#define FREEIMUv035
#define POWERMETER_HARD
#define WATTS
#define VBAT
#define VBAT_CELLS
#define VBAT_CELLS_NUM 3
#define VBAT_CELLS_PINS {A0, A1, A2 }
#define VBAT_CELLS_OFFSETS {0, 50, 83 }
#define VBAT_CELLS_DIVS { 75, 122, 98 }
#elif defined(COPTERTEST)
#error "*** this test is not yet defined"
#endif
/**************************************************************************************/
/*************** Proc specific definitions ********************/
/**************************************************************************************/
// Proc auto detection
#if defined(__AVR_ATmega168__) || defined(__AVR_ATmega328P__)
#define PROMINI
#endif
#if defined(__AVR_ATmega32U4__) || defined(TEENSY20)
#define PROMICRO
#endif
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2560__) || defined(__AVR_ATmega2561__)
#define MEGA
#endif
/**************************************************************************************/
/*************** motor and servo numbers ********************/
/**************************************************************************************/
#define SERVO_RATES {30,30,100,100,100,100,100,100}
#if defined (AIRPLANE) || defined(FLYING_WING)
#define FIXEDWING
#endif
#if defined(HELI_120_CCPM) || defined(HELI_90_DEG)
#define HELICOPTER
#endif
#if defined(BI) || defined(TRI) || defined(FIXEDWING) || defined(HELICOPTER) || defined(SINGLECOPTER)|| defined(DUALCOPTER)
#define COPTER_WITH_SERVO
#endif
#if defined(COPTER_WITH_SERVO) || defined(SERVO_TILT) || defined(GIMBAL) || defined(CAMTRIG) || defined(SERVO_MIX_TILT)
#define SERVO
#endif
#if defined(DYNBALANCE)
#define DYNBAL 1
#else
#define DYNBAL 0
#endif
#if defined(FLAPS)
#define FLAP 1
#else
#define FLAP 0
#endif
#if defined(MEGA) && defined(MEGA_HW_PWM_SERVOS)
#define TRI_SERVO 4
#else
#define TRI_SERVO 6
#endif
#if defined(GIMBAL)
#define NUMBER_MOTOR 0
#define PRI_SERVO_FROM 1 // use servo from 1 to 2
#define PRI_SERVO_TO 2
#elif defined(FLYING_WING)
#define PRI_SERVO_FROM 4
#if defined (USE_THROTTLESERVO)
#define NUMBER_MOTOR 0
#define PRI_SERVO_TO 8 // use servo from 4,5 and 8
#else
#define NUMBER_MOTOR 1
#define PRI_SERVO_TO 5 // use servo from 4 to 5
#endif
#elif defined(SINGLECOPTER)
#define NUMBER_MOTOR 1
#define PRI_SERVO_FROM 4 // use servo from 4 to 7
#define PRI_SERVO_TO 7
#elif defined(DUALCOPTER)
#define NUMBER_MOTOR 2
#define PRI_SERVO_FROM 5 // use servo from 5 to 6
#define PRI_SERVO_TO 6
#elif defined(AIRPLANE)
#if defined (USE_THROTTLESERVO)
#define NUMBER_MOTOR 0
#define PRI_SERVO_TO 8
#else
#define NUMBER_MOTOR 1
#define PRI_SERVO_TO 7
#endif
#if defined(FLAPS)
#define PRI_SERVO_FROM 3 // use servo from 3 to 8
#undef CAMTRIG // Disable Camtrig on A2
#else
#define PRI_SERVO_FROM 4 // use servo from 4 to 8
#endif
#elif defined(BI)
#define NUMBER_MOTOR 2
#define PRI_SERVO_FROM 5 // use servo from 5 to 6
#define PRI_SERVO_TO 6
#elif defined(TRI)
#define NUMBER_MOTOR 3
#define PRI_SERVO_FROM TRI_SERVO // use only servo 6 (or 4 with Mega HW PWM)
#define PRI_SERVO_TO TRI_SERVO
#elif defined(QUADP) || defined(QUADX) || defined(Y4)|| defined(VTAIL4)
#define NUMBER_MOTOR 4
#elif defined(Y6) || defined(HEX6) || defined(HEX6X) || defined(HEX6H)
#define NUMBER_MOTOR 6
#elif defined(OCTOX8) || defined(OCTOFLATP) || defined(OCTOFLATX)
#define NUMBER_MOTOR 8
#elif defined(HELICOPTER)
#define PRI_SERVO_FROM 4
#ifdef HELI_USE_SERVO_FOR_THROTTLE
#define NUMBER_MOTOR 0 // use servo to drive throttle output
#define PRI_SERVO_TO 8 // use servo from 4 to 8
#else
#define NUMBER_MOTOR 1 // use motor1 for throttle, DO NOT SET TO 2, OR IT WILL BURN/DESTROY SERVO7 USED FOR SWASH
#define PRI_SERVO_TO 7 // use servo from 4 to 7
#endif
#endif
#if (defined(SERVO_TILT)|| defined(SERVO_MIX_TILT))&& defined(CAMTRIG)
#define SEC_SERVO_FROM 1 // use servo from 1 to 3
#define SEC_SERVO_TO 3
#else
#if defined(SERVO_TILT)|| defined(SERVO_MIX_TILT)
// if A0 and A1 is taken by motors, we can use A2 and 12 for Servo tilt
#if defined(A0_A1_PIN_HEX) && (NUMBER_MOTOR == 6) && defined(PROMINI)
#define SEC_SERVO_FROM 3 // use servo from 3 to 4
#define SEC_SERVO_TO 4
#else
#define SEC_SERVO_FROM 1 // use servo from 1 to 2
#define SEC_SERVO_TO 2
#endif
#endif
#if defined(CAMTRIG)
#define SEC_SERVO_FROM 3 // use servo 3
#define SEC_SERVO_TO 3
#endif
#endif
#if defined(SIRIUS_AIR) || defined(SIRIUS_AIR_GPS)
#define RCAUX2PIND17
#endif
/************************** atmega328P (Promini) ************************************/
#if defined(PROMINI)
#if !defined(MONGOOSE1_0)
#define LEDPIN_PINMODE pinMode (13, OUTPUT);
#define LEDPIN_TOGGLE PINB |= 1<<5; //switch LEDPIN state (digital PIN 13)
#define LEDPIN_OFF PORTB &= ~(1<<5);
#define LEDPIN_ON PORTB |= (1<<5);
#endif
#if !defined(RCAUXPIN8)
#if !defined(MONGOOSE1_0)
#define BUZZERPIN_PINMODE pinMode (8, OUTPUT);
#if NUMBER_MOTOR >4
#undef PILOTLAMP
#endif
#if defined PILOTLAMP && NUMBER_MOTOR <5
#define PL_PIN_ON PORTB |= 1;
#define PL_PIN_OFF PORTB &= ~1;
#else
#define BUZZERPIN_ON PORTB |= 1;
#define BUZZERPIN_OFF PORTB &= ~1;
#endif
#endif
#else
#define BUZZERPIN_PINMODE ;
#define BUZZERPIN_ON ;
#define BUZZERPIN_OFF ;
#define RCAUXPIN
#endif
#if !defined(RCAUXPIN12) && !defined(DISABLE_POWER_PIN)
#define POWERPIN_PINMODE pinMode (12, OUTPUT);
#define POWERPIN_ON PORTB |= 1<<4;
#define POWERPIN_OFF PORTB &= ~(1<<4); //switch OFF WMP, digital PIN 12
#else
#define POWERPIN_PINMODE ;
#define POWERPIN_ON ;
#define POWERPIN_OFF ;
#endif
#if defined(RCAUXPIN12)
#define RCAUXPIN
#endif
#define I2C_PULLUPS_ENABLE PORTC |= 1<<4; PORTC |= 1<<5; // PIN A4&A5 (SDA&SCL)
#define I2C_PULLUPS_DISABLE PORTC &= ~(1<<4); PORTC &= ~(1<<5);
#if !defined(MONGOOSE1_0)
#define PINMODE_LCD pinMode(0, OUTPUT);
#define LCDPIN_OFF PORTD &= ~1; //switch OFF digital PIN 0
#define LCDPIN_ON PORTD |= 1;
#define STABLEPIN_PINMODE ;
#define STABLEPIN_ON ;
#define STABLEPIN_OFF ;
#endif
#define PPM_PIN_INTERRUPT attachInterrupt(0, rxInt, RISING); //PIN 0
#define RX_SERIAL_PORT 0
//RX PIN assignment inside the port //for PORTD
#define THROTTLEPIN 2
#define ROLLPIN 4
#define PITCHPIN 5
#define YAWPIN 6
#define AUX1PIN 7
#define AUX2PIN 0 // optional PIN 8 or PIN 12
#define AUX3PIN 1 // unused
#define AUX4PIN 3 // unused
#define PCINT_PIN_COUNT 5
#define PCINT_RX_BITS (1<<2),(1<<4),(1<<5),(1<<6),(1<<7)
#define PCINT_RX_PORT PORTD
#define PCINT_RX_MASK PCMSK2
#define PCIR_PORT_BIT (1<<2)
#define RX_PC_INTERRUPT PCINT2_vect
#define RX_PCINT_PIN_PORT PIND
#define V_BATPIN A3 // Analog PIN 3
#define PSENSORPIN A2 // Analog PIN 2
#if defined(A0_A1_PIN_HEX) || (NUMBER_MOTOR > 6)
#define SOFT_PWM_1_PIN_HIGH PORTC |= 1<<0;
#define SOFT_PWM_1_PIN_LOW PORTC &= ~(1<<0);
#define SOFT_PWM_2_PIN_HIGH PORTC |= 1<<1;
#define SOFT_PWM_2_PIN_LOW PORTC &= ~(1<<1);
#else
#define SOFT_PWM_1_PIN_HIGH PORTD |= 1<<5;
#define SOFT_PWM_1_PIN_LOW PORTD &= ~(1<<5);
#define SOFT_PWM_2_PIN_HIGH PORTD |= 1<<6;
#define SOFT_PWM_2_PIN_LOW PORTD &= ~(1<<6);
#endif
#define SOFT_PWM_3_PIN_HIGH PORTC |= 1<<2;
#define SOFT_PWM_3_PIN_LOW PORTC &= ~(1<<2);
#define SOFT_PWM_4_PIN_HIGH PORTB |= 1<<4;
#define SOFT_PWM_4_PIN_LOW PORTB &= ~(1<<4);
#define SERVO_1_PINMODE pinMode(A0,OUTPUT); // TILT_PITCH - WING left
#define SERVO_1_PIN_HIGH PORTC |= 1<<0;
#define SERVO_1_PIN_LOW PORTC &= ~(1<<0);
#define SERVO_2_PINMODE pinMode(A1,OUTPUT); // TILT_ROLL - WING right
#define SERVO_2_PIN_HIGH PORTC |= 1<<1;
#define SERVO_2_PIN_LOW PORTC &= ~(1<<1);
#define SERVO_3_PINMODE pinMode(A2,OUTPUT); // CAM TRIG - alt TILT_PITCH
#define SERVO_3_PIN_HIGH PORTC |= 1<<2;
#define SERVO_3_PIN_LOW PORTC &= ~(1<<2);
#if !defined(MONGOOSE1_0)
#define SERVO_4_PINMODE pinMode(12,OUTPUT); // new - alt TILT_ROLL
#define SERVO_4_PIN_HIGH PORTB |= 1<<4;
#define SERVO_4_PIN_LOW PORTB &= ~(1<<4);
#endif
#define SERVO_5_PINMODE pinMode(11,OUTPUT); // BI LEFT
#define SERVO_5_PIN_HIGH PORTB |= 1<<3;
#define SERVO_5_PIN_LOW PORTB &= ~(1<<3);
#define SERVO_6_PINMODE pinMode(3,OUTPUT); // TRI REAR - BI RIGHT
#define SERVO_6_PIN_HIGH PORTD|= 1<<3;
#define SERVO_6_PIN_LOW PORTD &= ~(1<<3);
#define SERVO_7_PINMODE pinMode(10,OUTPUT); // new
#define SERVO_7_PIN_HIGH PORTB |= 1<<2;
#define SERVO_7_PIN_LOW PORTB &= ~(1<<2);
#define SERVO_8_PINMODE pinMode(9,OUTPUT); // new
#define SERVO_8_PIN_HIGH PORTB |= 1<<1;
#define SERVO_8_PIN_LOW PORTB &= ~(1<<1);
#endif
/************************** atmega32u4 (Promicro) ***********************************/
#if defined(PROMICRO)
#if defined(MICROWII)
#define A32U4ALLPINS
#endif
#if !defined(TEENSY20)
#define LEDPIN_PINMODE //
#define LEDPIN_TOGGLE PIND |= 1<<5; //switch LEDPIN state (Port D5)
#if !defined(PROMICRO10)
#define LEDPIN_OFF PORTD |= (1<<5);
#define LEDPIN_ON PORTD &= ~(1<<5);
#else
#define LEDPIN_OFF PORTD &= ~(1<<5);
#define LEDPIN_ON PORTD |= (1<<5);
#endif
#else
#define LEDPIN_PINMODE DDRD |= (1<<6);
#define LEDPIN_OFF PORTD &= ~(1<<6);
#define LEDPIN_ON PORTD |= (1<<6);
#define LEDPIN_TOGGLE PIND |= 1<<6; //switch LEDPIN state (Port D6)
#endif
#if defined(D8BUZZER)
#define BUZZERPIN_PINMODE DDRB |= (1<<4);
#if defined PILOTLAMP
#define PL_PIN_ON PORTB |= 1<<4;
#define PL_PIN_OFF PORTB &= ~(1<<4);
#else
#define BUZZERPIN_ON PORTB |= 1<<4;
#define BUZZERPIN_OFF PORTB &= ~(1<<4);
#endif
#elif defined(A32U4ALLPINS)
#define BUZZERPIN_PINMODE DDRD |= (1<<4);
#if defined PILOTLAMP
#define PL_PIN_ON PORTD |= 1<<4;
#define PL_PIN_OFF PORTD &= ~(1<<4);
#else
#define BUZZERPIN_ON PORTD |= 1<<4;
#define BUZZERPIN_OFF PORTD &= ~(1<<4);
#endif
#else
#define BUZZERPIN_PINMODE DDRD |= (1<<3);
#if defined PILOTLAMP
#define PL_PIN_ON PORTD |= 1<<3;
#define PL_PIN_OFF PORTD &= ~(1<<3);
#else
#define BUZZERPIN_ON PORTD |= 1<<3;
#define BUZZERPIN_OFF PORTD &= ~(1<<3);
#endif
#endif
#define POWERPIN_PINMODE //
#define POWERPIN_ON //
#define POWERPIN_OFF //
#define I2C_PULLUPS_ENABLE PORTD |= 1<<0; PORTD |= 1<<1; // PIN 2&3 (SDA&SCL)
#define I2C_PULLUPS_DISABLE PORTD &= ~(1<<0); PORTD &= ~(1<<1);
#define PINMODE_LCD DDRD |= (1<<2);
#define LCDPIN_OFF PORTD &= ~1;
#define LCDPIN_ON PORTD |= 1;
#define STABLEPIN_PINMODE ;
#define STABLEPIN_ON ;
#define STABLEPIN_OFF ;
#define PPM_PIN_INTERRUPT DDRE &= ~(1 << 6);PORTE |= (1 << 6); EICRB |= (1 << ISC61)|(1 << ISC60); EIMSK |= (1 << INT6);
#if !defined(RX_SERIAL_PORT)
#define RX_SERIAL_PORT 1
#endif
#define USB_CDC_TX 3
#define USB_CDC_RX 2
//soft PWM Pins
#define SOFT_PWM_1_PIN_HIGH PORTD |= 1<<4;
#define SOFT_PWM_1_PIN_LOW PORTD &= ~(1<<4);
#define SOFT_PWM_2_PIN_HIGH PORTF |= 1<<5;
#define SOFT_PWM_2_PIN_LOW PORTF &= ~(1<<5);
#if !defined(A32U4ALLPINS)
#define SOFT_PWM_3_PIN_HIGH PORTF |= 1<<7;
#define SOFT_PWM_3_PIN_LOW PORTF &= ~(1<<7);
#define SOFT_PWM_4_PIN_HIGH PORTF |= 1<<6;
#define SOFT_PWM_4_PIN_LOW PORTF &= ~(1<<6);
#define SW_PWM_P3 A1
#define SW_PWM_P4 A0
#else
#define SOFT_PWM_3_PIN_HIGH PORTF |= 1<<4;
#define SOFT_PWM_3_PIN_LOW PORTF &= ~(1<<4);
#define SOFT_PWM_4_PIN_HIGH PORTF |= 1<<5;
#define SOFT_PWM_4_PIN_LOW PORTF &= ~(1<<5);
#define SW_PWM_P3 A2
#define SW_PWM_P4 A3
#endif
// Servos
#define SERVO_1_PINMODE DDRF |= (1<<7); // A0
#define SERVO_1_PIN_HIGH PORTF|= 1<<7;
#define SERVO_1_PIN_LOW PORTF &= ~(1<<7);
#define SERVO_2_PINMODE DDRF |= (1<<6); // A1
#define SERVO_2_PIN_HIGH PORTF |= 1<<6;
#define SERVO_2_PIN_LOW PORTF &= ~(1<<6);
#define SERVO_3_PINMODE DDRF |= (1<<5); // A2
#define SERVO_3_PIN_HIGH PORTF |= 1<<5;
#define SERVO_3_PIN_LOW PORTF &= ~(1<<5);
#if !defined(A32U4ALLPINS)
#define SERVO_4_PINMODE DDRD |= (1<<4); // 4
#define SERVO_4_PIN_HIGH PORTD |= 1<<4;
#define SERVO_4_PIN_LOW PORTD &= ~(1<<4);
#else
#define SERVO_4_PINMODE DDRF |= (1<<4); // A3
#define SERVO_4_PIN_HIGH PORTF |= 1<<4;
#define SERVO_4_PIN_LOW PORTF &= ~(1<<4);
#endif
#define SERVO_5_PINMODE DDRC |= (1<<6); // 5
#define SERVO_5_PIN_HIGH PORTC|= 1<<6;
#define SERVO_5_PIN_LOW PORTC &= ~(1<<6);
#define SERVO_6_PINMODE DDRD |= (1<<7); // 6
#define SERVO_6_PIN_HIGH PORTD |= 1<<7;
#define SERVO_6_PIN_LOW PORTD &= ~(1<<7);
#define SERVO_7_PINMODE DDRB |= (1<<6); // 10
#define SERVO_7_PIN_HIGH PORTB |= 1<<6;
#define SERVO_7_PIN_LOW PORTB &= ~(1<<6);
#define SERVO_8_PINMODE DDRB |= (1<<5); // 9
#define SERVO_8_PIN_HIGH PORTB |= 1<<5;
#define SERVO_8_PIN_LOW PORTB &= ~(1<<5);
//Standart RX
#define THROTTLEPIN 3
#if defined(A32U4ALLPINS)
#define ROLLPIN 6
#define PITCHPIN 2
#define YAWPIN 4
#define AUX1PIN 5
#else
#define ROLLPIN 4
#define PITCHPIN 5
#define YAWPIN 2
#define AUX1PIN 6
#endif
#define AUX2PIN 7
#define AUX3PIN 1 // unused
#define AUX4PIN 0 // unused
#if !defined(RCAUX2PIND17)
#define PCINT_PIN_COUNT 4
#define PCINT_RX_BITS (1<<1),(1<<2),(1<<3),(1<<4)
#else
#define PCINT_PIN_COUNT 5 // one more bit (PB0) is added in RX code
#define PCINT_RX_BITS (1<<1),(1<<2),(1<<3),(1<<4),(1<<0)
#endif
#define PCINT_RX_PORT PORTB
#define PCINT_RX_MASK PCMSK0
#define PCIR_PORT_BIT (1<<0)
#define RX_PC_INTERRUPT PCINT0_vect
#define RX_PCINT_PIN_PORT PINB
#if !defined(A32U4ALLPINS) && !defined(TEENSY20)
#define V_BATPIN A3 // Analog PIN 3
#elif defined(A32U4ALLPINS)
#define V_BATPIN A4 // Analog PIN 4
#else
#define V_BATPIN A2 // Analog PIN 3
#endif
#if !defined(TEENSY20)
#define PSENSORPIN A2 // Analog PIN 2
#else
#define PSENSORPIN A2 // Analog PIN 2
#endif
#endif
/************************** all the Mega types ***********************************/
#if defined(MEGA)
#define LEDPIN_PINMODE pinMode (13, OUTPUT);pinMode (30, OUTPUT);
#define LEDPIN_TOGGLE PINB |= (1<<7); PINC |= (1<<7);
#define LEDPIN_ON PORTB |= (1<<7); PORTC |= (1<<7);
#define LEDPIN_OFF PORTB &= ~(1<<7);PORTC &= ~(1<<7);
#define BUZZERPIN_PINMODE pinMode (32, OUTPUT);
#if defined PILOTLAMP
#define PL_PIN_ON PORTC |= 1<<5;
#define PL_PIN_OFF PORTC &= ~(1<<5);
#else
#define BUZZERPIN_ON PORTC |= 1<<5;
#define BUZZERPIN_OFF PORTC &= ~(1<<5);
#endif
#if !defined(DISABLE_POWER_PIN)
#define POWERPIN_PINMODE pinMode (37, OUTPUT);
#define POWERPIN_ON PORTC |= 1<<0;
#define POWERPIN_OFF PORTC &= ~(1<<0);
#else
#define POWERPIN_PINMODE ;
#define POWERPIN_ON ;
#define POWERPIN_OFF ;
#endif
#define I2C_PULLUPS_ENABLE PORTD |= 1<<0; PORTD |= 1<<1; // PIN 20&21 (SDA&SCL)
#define I2C_PULLUPS_DISABLE PORTD &= ~(1<<0); PORTD &= ~(1<<1);
#define PINMODE_LCD pinMode(0, OUTPUT);
#define LCDPIN_OFF PORTE &= ~1; //switch OFF digital PIN 0
#define LCDPIN_ON PORTE |= 1;
#define STABLEPIN_PINMODE pinMode (31, OUTPUT);
#define STABLEPIN_ON PORTC |= 1<<6;
#define STABLEPIN_OFF PORTC &= ~(1<<6);
#if defined(PPM_ON_THROTTLE)
//configure THROTTLE PIN (A8 pin) as input witch pullup and enabled PCINT interrupt
#define PPM_PIN_INTERRUPT DDRK &= ~(1<<0); PORTK |= (1<<0); PCICR |= (1<<2); PCMSK2 |= (1<<0);
#else
#define PPM_PIN_INTERRUPT attachInterrupt(4, rxInt, RISING); //PIN 19, also used for Spektrum satellite option
#endif
#if !defined(RX_SERIAL_PORT)
#define RX_SERIAL_PORT 1
#endif
//RX PIN assignment inside the port //for PORTK
#define THROTTLEPIN 0 //PIN 62 = PIN A8
#define ROLLPIN 1 //PIN 63 = PIN A9
#define PITCHPIN 2 //PIN 64 = PIN A10
#define YAWPIN 3 //PIN 65 = PIN A11
#define AUX1PIN 4 //PIN 66 = PIN A12
#define AUX2PIN 5 //PIN 67 = PIN A13
#define AUX3PIN 6 //PIN 68 = PIN A14
#define AUX4PIN 7 //PIN 69 = PIN A15
#define V_BATPIN A0 // Analog PIN 0
#define PSENSORPIN A2 // Analog PIN 2
#define PCINT_PIN_COUNT 8
#define PCINT_RX_BITS (1<<2),(1<<4),(1<<5),(1<<6),(1<<7),(1<<0),(1<<1),(1<<3)
#define PCINT_RX_PORT PORTK
#define PCINT_RX_MASK PCMSK2
#define PCIR_PORT_BIT (1<<2)
#define RX_PC_INTERRUPT PCINT2_vect
#define RX_PCINT_PIN_PORT PINK
#define SERVO_1_PINMODE pinMode(34,OUTPUT);pinMode(44,OUTPUT); // TILT_PITCH - WING left
#define SERVO_1_PIN_HIGH PORTC |= 1<<3;PORTL |= 1<<5;
#define SERVO_1_PIN_LOW PORTC &= ~(1<<3);PORTL &= ~(1<<5);
#define SERVO_2_PINMODE pinMode(35,OUTPUT);pinMode(45,OUTPUT); // TILT_ROLL - WING right
#define SERVO_2_PIN_HIGH PORTC |= 1<<2;PORTL |= 1<<4;
#define SERVO_2_PIN_LOW PORTC &= ~(1<<2);PORTL &= ~(1<<4);
#define SERVO_3_PINMODE pinMode(33,OUTPUT); pinMode(46,OUTPUT); // CAM TRIG - alt TILT_PITCH
#define SERVO_3_PIN_HIGH PORTC |= 1<<4;PORTL |= 1<<3;
#define SERVO_3_PIN_LOW PORTC &= ~(1<<4);PORTL &= ~(1<<3);
#define SERVO_4_PINMODE pinMode (37, OUTPUT);pinMode(7,OUTPUT); // new - alt TILT_ROLL
#define SERVO_4_PIN_HIGH PORTC |= 1<<0; PORTH |= 1<<4;
#define SERVO_4_PIN_LOW PORTC &= ~(1<<0);PORTH &= ~(1<<4);
#define SERVO_5_PINMODE pinMode(6,OUTPUT); // BI LEFT
#define SERVO_5_PIN_HIGH PORTH |= 1<<3;
#define SERVO_5_PIN_LOW PORTH &= ~(1<<3);
#define SERVO_6_PINMODE pinMode(2,OUTPUT); // TRI REAR - BI RIGHT
#define SERVO_6_PIN_HIGH PORTE |= 1<<4;
#define SERVO_6_PIN_LOW PORTE &= ~(1<<4);
#define SERVO_7_PINMODE pinMode(5,OUTPUT); // new
#define SERVO_7_PIN_HIGH PORTE |= 1<<3;
#define SERVO_7_PIN_LOW PORTE &= ~(1<<3);
#define SERVO_8_PINMODE pinMode(3,OUTPUT); // new
#define SERVO_8_PIN_HIGH PORTE |= 1<<5;
#define SERVO_8_PIN_LOW PORTE &= ~(1<<5);
#endif
// special defines for the Mongose IMU board
// note: that may be moved to the IMU Orientations because this are board defines .. not Proc
#if defined(MONGOOSE1_0) // basically it's a PROMINI without some PINS => same code as a PROMINI board except PIN definition
// note: to avoid too much dubble code there are now just the differencies
// http://www.multiwii.com/forum/viewtopic.php?f=6&t=627
#define LEDPIN_PINMODE pinMode (4, OUTPUT);
#define LEDPIN_TOGGLE PIND |= 1<<4; //switch LEDPIN state (digital PIN 13)
#define LEDPIN_OFF PORTD &= ~(1<<4);
#define LEDPIN_ON PORTD |= (1<<4);
#define SPEK_BAUD_SET UCSR0A = (1<<U2X0); UBRR0H = ((F_CPU / 4 / 115200 -1) / 2) >> 8; UBRR0L = ((F_CPU / 4 / 115200 -1) / 2);
#define RX_SERIAL_PORT 0
/* Unavailable pins on MONGOOSE1_0 */
#define BUZZERPIN_PINMODE ; // D8
#define BUZZERPIN_ON ;
#define BUZZERPIN_OFF ;
#define POWERPIN_PINMODE ; // D12
#define POWERPIN_ON ;
#define POWERPIN_OFF ;
#define STABLEPIN_PINMODE ; //
#define STABLEPIN_ON ;
#define STABLEPIN_OFF ;
#define PINMODE_LCD ; //
#define LCDPIN_OFF ;
#define LCDPIN_ON ;
#define SERVO_4_PINMODE ; // Not available
#define SERVO_4_PIN_HIGH ;
#define SERVO_4_PIN_LOW ;
#endif
/********************** Sort the Servos for the most ideal SW PWM ************************/
// this define block sorts the above slected servos to be in a simple order from 1 - (count of total servos)
// its pretty fat but its the best way i found to get less compiled code and max speed in the ISR without loosing its flexibility
#if (PRI_SERVO_FROM == 1) || (SEC_SERVO_FROM == 1)
#define LAST_LOW SERVO_1_PIN_LOW
#define SERVO_1_HIGH SERVO_1_PIN_HIGH
#define SERVO_1_LOW SERVO_1_PIN_LOW
#define SERVO_1_ARR_POS 0
#endif
#if (PRI_SERVO_FROM <= 2 && PRI_SERVO_TO >= 2) || (SEC_SERVO_FROM <= 2 && SEC_SERVO_TO >= 2)
#undef LAST_LOW
#define LAST_LOW SERVO_2_PIN_LOW
#if !defined(SERVO_1_HIGH)
#define SERVO_1_HIGH SERVO_2_PIN_HIGH
#define SERVO_1_LOW SERVO_2_PIN_LOW
#define SERVO_1_ARR_POS 1
#else
#define SERVO_2_HIGH SERVO_2_PIN_HIGH
#define SERVO_2_LOW SERVO_2_PIN_LOW
#define SERVO_2_ARR_POS 1
#endif
#endif
#if (PRI_SERVO_FROM <= 3 && PRI_SERVO_TO >= 3) || (SEC_SERVO_FROM <= 3 && SEC_SERVO_TO >= 3)
#undef LAST_LOW
#define LAST_LOW SERVO_3_PIN_LOW
#if !defined(SERVO_1_HIGH)
#define SERVO_1_HIGH SERVO_3_PIN_HIGH
#define SERVO_1_LOW SERVO_3_PIN_LOW
#define SERVO_1_ARR_POS 2
#elif !defined(SERVO_2_HIGH)
#define SERVO_2_HIGH SERVO_3_PIN_HIGH
#define SERVO_2_LOW SERVO_3_PIN_LOW
#define SERVO_2_ARR_POS 2
#else
#define SERVO_3_HIGH SERVO_3_PIN_HIGH
#define SERVO_3_LOW SERVO_3_PIN_LOW
#define SERVO_3_ARR_POS 2
#endif
#endif
#if (PRI_SERVO_FROM <= 4 && PRI_SERVO_TO >= 4) || (SEC_SERVO_FROM <= 4 && SEC_SERVO_TO >= 4)
#undef LAST_LOW
#define LAST_LOW SERVO_4_PIN_LOW
#if !defined(SERVO_1_HIGH)
#define SERVO_1_HIGH SERVO_4_PIN_HIGH
#define SERVO_1_LOW SERVO_4_PIN_LOW
#define SERVO_1_ARR_POS 3
#elif !defined(SERVO_2_HIGH)
#define SERVO_2_HIGH SERVO_4_PIN_HIGH
#define SERVO_2_LOW SERVO_4_PIN_LOW
#define SERVO_2_ARR_POS 3
#elif !defined(SERVO_3_HIGH)
#define SERVO_3_HIGH SERVO_4_PIN_HIGH
#define SERVO_3_LOW SERVO_4_PIN_LOW
#define SERVO_3_ARR_POS 3
#else
#define SERVO_4_HIGH SERVO_4_PIN_HIGH
#define SERVO_4_LOW SERVO_4_PIN_LOW
#define SERVO_4_ARR_POS 3
#endif
#endif
#if (PRI_SERVO_FROM <= 5 && PRI_SERVO_TO >= 5) || (SEC_SERVO_FROM <= 5 && SEC_SERVO_TO >= 5)
#undef LAST_LOW
#define LAST_LOW SERVO_5_PIN_LOW
#if !defined(SERVO_1_HIGH)
#define SERVO_1_HIGH SERVO_5_PIN_HIGH
#define SERVO_1_LOW SERVO_5_PIN_LOW
#define SERVO_1_ARR_POS 4
#elif !defined(SERVO_2_HIGH)
#define SERVO_2_HIGH SERVO_5_PIN_HIGH
#define SERVO_2_LOW SERVO_5_PIN_LOW
#define SERVO_2_ARR_POS 4
#elif !defined(SERVO_3_HIGH)
#define SERVO_3_HIGH SERVO_5_PIN_HIGH
#define SERVO_3_LOW SERVO_5_PIN_LOW
#define SERVO_3_ARR_POS 4
#elif !defined(SERVO_4_HIGH)
#define SERVO_4_HIGH SERVO_5_PIN_HIGH
#define SERVO_4_LOW SERVO_5_PIN_LOW
#define SERVO_4_ARR_POS 4
#else
#define SERVO_5_HIGH SERVO_5_PIN_HIGH
#define SERVO_5_LOW SERVO_5_PIN_LOW
#define SERVO_5_ARR_POS 4
#endif
#endif
#if (PRI_SERVO_FROM <= 6 && PRI_SERVO_TO >= 6) || (SEC_SERVO_FROM <= 6 && SEC_SERVO_TO >= 6)
#undef LAST_LOW
#define LAST_LOW SERVO_6_PIN_LOW
#if !defined(SERVO_1_HIGH)
#define SERVO_1_HIGH SERVO_6_PIN_HIGH
#define SERVO_1_LOW SERVO_6_PIN_LOW
#define SERVO_1_ARR_POS 5
#elif !defined(SERVO_2_HIGH)
#define SERVO_2_HIGH SERVO_6_PIN_HIGH
#define SERVO_2_LOW SERVO_6_PIN_LOW
#define SERVO_2_ARR_POS 5
#elif !defined(SERVO_3_HIGH)
#define SERVO_3_HIGH SERVO_6_PIN_HIGH
#define SERVO_3_LOW SERVO_6_PIN_LOW
#define SERVO_3_ARR_POS 5
#elif !defined(SERVO_4_HIGH)
#define SERVO_4_HIGH SERVO_6_PIN_HIGH
#define SERVO_4_LOW SERVO_6_PIN_LOW
#define SERVO_4_ARR_POS 5
#elif !defined(SERVO_5_HIGH)
#define SERVO_5_HIGH SERVO_6_PIN_HIGH
#define SERVO_5_LOW SERVO_6_PIN_LOW
#define SERVO_5_ARR_POS 5
#else
#define SERVO_6_HIGH SERVO_6_PIN_HIGH
#define SERVO_6_LOW SERVO_6_PIN_LOW
#define SERVO_6_ARR_POS 5
#endif
#endif
#if (PRI_SERVO_FROM <= 7 && PRI_SERVO_TO >= 7) || (SEC_SERVO_FROM <= 7 && SEC_SERVO_TO >= 7)
#undef LAST_LOW
#define LAST_LOW SERVO_7_PIN_LOW
#if !defined(SERVO_1_HIGH)
#define SERVO_1_HIGH SERVO_7_PIN_HIGH
#define SERVO_1_LOW SERVO_7_PIN_LOW
#define SERVO_1_ARR_POS 6
#elif !defined(SERVO_2_HIGH)
#define SERVO_2_HIGH SERVO_7_PIN_HIGH
#define SERVO_2_LOW SERVO_7_PIN_LOW
#define SERVO_2_ARR_POS 6
#elif !defined(SERVO_3_HIGH)
#define SERVO_3_HIGH SERVO_7_PIN_HIGH
#define SERVO_3_LOW SERVO_7_PIN_LOW
#define SERVO_3_ARR_POS 6
#elif !defined(SERVO_4_HIGH)
#define SERVO_4_HIGH SERVO_7_PIN_HIGH
#define SERVO_4_LOW SERVO_7_PIN_LOW
#define SERVO_4_ARR_POS 6
#elif !defined(SERVO_5_HIGH)
#define SERVO_5_HIGH SERVO_7_PIN_HIGH
#define SERVO_5_LOW SERVO_7_PIN_LOW
#define SERVO_5_ARR_POS 6
#elif !defined(SERVO_6_HIGH)
#define SERVO_6_HIGH SERVO_7_PIN_HIGH
#define SERVO_6_LOW SERVO_7_PIN_LOW
#define SERVO_6_ARR_POS 6
#else
#define SERVO_7_HIGH SERVO_7_PIN_HIGH
#define SERVO_7_LOW SERVO_7_PIN_LOW
#define SERVO_7_ARR_POS 6
#endif
#endif
#if (PRI_SERVO_FROM <= 8 && PRI_SERVO_TO >= 8) || (SEC_SERVO_FROM <= 8 && SEC_SERVO_TO >= 8)
#undef LAST_LOW
#define LAST_LOW SERVO_8_PIN_LOW
#if !defined(SERVO_1_HIGH)
#define SERVO_1_HIGH SERVO_8_PIN_HIGH
#define SERVO_1_LOW SERVO_8_PIN_LOW
#define SERVO_1_ARR_POS 7
#elif !defined(SERVO_2_HIGH)
#define SERVO_2_HIGH SERVO_8_PIN_HIGH
#define SERVO_2_LOW SERVO_8_PIN_LOW
#define SERVO_2_ARR_POS 7
#elif !defined(SERVO_3_HIGH)
#define SERVO_3_HIGH SERVO_8_PIN_HIGH
#define SERVO_3_LOW SERVO_8_PIN_LOW
#define SERVO_3_ARR_POS 7
#elif !defined(SERVO_4_HIGH)
#define SERVO_4_HIGH SERVO_8_PIN_HIGH
#define SERVO_4_LOW SERVO_8_PIN_LOW
#define SERVO_4_ARR_POS 7
#elif !defined(SERVO_5_HIGH)
#define SERVO_5_HIGH SERVO_8_PIN_HIGH
#define SERVO_5_LOW SERVO_8_PIN_LOW
#define SERVO_5_ARR_POS 7
#elif !defined(SERVO_6_HIGH)
#define SERVO_6_HIGH SERVO_8_PIN_HIGH
#define SERVO_6_LOW SERVO_8_PIN_LOW
#define SERVO_6_ARR_POS 7
#elif !defined(SERVO_7_HIGH)
#define SERVO_7_HIGH SERVO_8_PIN_HIGH
#define SERVO_7_LOW SERVO_8_PIN_LOW
#define SERVO_7_ARR_POS 7
#else
#define SERVO_8_HIGH SERVO_8_PIN_HIGH
#define SERVO_8_LOW SERVO_8_PIN_LOW
#define SERVO_8_ARR_POS 7
#endif
#endif
#if ( defined(MEGA) && defined(MEGA_HW_PWM_SERVOS) ) || (defined(PROMICRO) && defined(A32U4_4_HW_PWM_SERVOS))
#undef SERVO_1_HIGH // No software PWM's if we use hardware MEGA PWM or promicro hardware pwm
#define HW_PWM_SERVOS
#endif
/**************************************************************************************/
/*************** IMU Orientations and Sensor definitions ********************/
/**************************************************************************************/
//please submit any correction to this list.
#if defined(FFIMUv1)
#define ITG3200
#define BMA180
#define BMP085
#define HMC5843
#define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
#define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
#define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = -Z;}
#endif
#if defined(FFIMUv2)
#define ITG3200
#define BMA180
#define BMP085
#define HMC5883
#define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
#define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
#define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = Y; imu.magADC[PITCH] = -X; imu.magADC[YAW] = -Z;}
#endif
#if defined(FREEIMUv1)
#define ITG3200
#define ADXL345
#define HMC5843
#define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
#define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
#define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = -Z;}
#define ADXL345_ADDRESS 0x53
#undef INTERNAL_I2C_PULLUPS
#endif
#if defined(FREEIMUv03)
#define ITG3200
#define ADXL345 // this is actually an ADXL346 but that's just the same as ADXL345
#define HMC5883
#define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
#define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
#define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = -Z;}
#define ADXL345_ADDRESS 0x53
#undef INTERNAL_I2C_PULLUPS
#endif
#if defined(FREEIMUv035) || defined(FREEIMUv035_MS) || defined(FREEIMUv035_BMP)
#define ITG3200
#define BMA180
#define HMC5883
#define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
#define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
#define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = -Z;}
#undef INTERNAL_I2C_PULLUPS
#if defined(FREEIMUv035_MS)
#define MS561101BA
#elif defined(FREEIMUv035_BMP)
#define BMP085
#endif
#endif
#if defined(FREEIMUv04)
#define FREEIMUv043
#endif
#if defined(MultiWiiMega)
#define FREEIMUv043
#endif
#if defined(FREEIMUv043) || defined(MICROWII)
#define MPU6050
#define HMC5883
#define MS561101BA
#define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
#define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
#define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = -Z;}
#define MPU6050_I2C_AUX_MASTER // MAG connected to the AUX I2C bus of MPU6050
#undef INTERNAL_I2C_PULLUPS
#endif
#if defined(NANOWII)
#define MPU6050
#define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -Y; imu.accADC[PITCH] = X; imu.accADC[YAW] = Z;}
#define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = -X; imu.gyroADC[PITCH] = -Y; imu.gyroADC[YAW] = -Z;}
#undef INTERNAL_I2C_PULLUPS
// move motor 7 & 8 to pin 4 & A2
#undef SOFT_PWM_3_PIN_HIGH
#undef SOFT_PWM_3_PIN_LOW
#undef SOFT_PWM_4_PIN_HIGH
#undef SOFT_PWM_4_PIN_LOW
#undef SW_PWM_P3
#undef SW_PWM_P4
#define SOFT_PWM_3_PIN_HIGH PORTD |= 1<<4;
#define SOFT_PWM_3_PIN_LOW PORTD &= ~(1<<4);
#define SOFT_PWM_4_PIN_HIGH PORTF |= 1<<5;
#define SOFT_PWM_4_PIN_LOW PORTF &= ~(1<<5);
#define SW_PWM_P3 4
#define SW_PWM_P4 A2
#define HWPWM6
// move servo 3 & 4 to pin 13 & 11
#undef SERVO_3_PINMODE
#undef SERVO_3_PIN_HIGH
#undef SERVO_3_PIN_LOW
#undef SERVO_4_PINMODE
#undef SERVO_4_PIN_HIGH
#undef SERVO_4_PIN_LOW
#define SERVO_3_PINMODE DDRC |= (1<<7); // 13
#define SERVO_3_PIN_HIGH PORTC |= 1<<7;
#define SERVO_3_PIN_LOW PORTC &= ~(1<<7);
#define SERVO_4_PINMODE DDRB |= (1<<7); // 11
#define SERVO_4_PIN_HIGH PORTB |= 1<<7;
#define SERVO_4_PIN_LOW PORTB &= ~(1<<7);
// use pin 4 as status LED output if we have no octo
#if !defined(OCTOX8) && !defined(OCTOFLATP) && !defined(OCTOFLATX)
#undef LEDPIN_PINMODE
#undef LEDPIN_TOGGLE
#undef LEDPIN_OFF
#undef LEDPIN_ON
#define LEDPIN_PINMODE DDRD |= (1<<4); //D4 to output
#define LEDPIN_TOGGLE PIND |= (1<<5)|(1<<4); //switch LEDPIN state (Port D5) & pin D4
#define LEDPIN_OFF PORTD |= (1<<5); PORTD &= ~(1<<4);
#define LEDPIN_ON PORTD &= ~(1<<5); PORTD |= (1<<4);
#endif
#endif
#if defined(PIPO)
#define L3G4200D
#define ADXL345
#define HMC5883
#define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
#define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = X; imu.gyroADC[PITCH] = Y; imu.gyroADC[YAW] = -Z;}
#define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = Y; imu.magADC[PITCH] = -X; imu.magADC[YAW] = Z;}
#define ADXL345_ADDRESS 0x53
#endif
#if defined(QUADRINO)