Go to the documentation of this file.
18 #define POWERMETER_SOFT
21 #define FREEIMUv035_MS
24 #define POWERMETER_HARD
29 #define LCD_TELEMETRY_STEP "01245"
31 #define SUPPRESS_BARO_ALTHOLD
42 #define LOG_PERMANENT_SERVICE_LIFETIME 36000
46 #undef DISABLE_POWER_PIN
48 #define OLED_I2C_128x64
53 #define SERVO_RFR_160HZ
55 #define POWERMETER_SOFT
57 #define MMGYROVECTORLENGTH 15
58 #define GYRO_SMOOTHING {45, 45, 50}
59 #define INFLIGHT_ACC_CALIBRATION
61 #define LOG_PERMANENT_SHOW_AT_STARTUP
62 #define LOG_PERMANENT_SHOW_AT_L
63 #define LOG_PERMANENT_SERVICE_LIFETIME 36000
66 #define YAW_COLL_PRECOMP 15
67 #define YAW_COLL_PRECOMP_DEADBAND 130
68 #define VOLTAGEDROP_COMPENSATION
71 #define DIYFLYING_MAGE_V1
73 #define RCOPTIONSBEEP // ca. 80byte
74 #define ARMEDTIMEWARNING 480 // 8 min = 480seconds
76 #define VOLTAGEDROP_COMPENSATION
77 #define MEGA_HW_PWM_SERVOS
78 #define SERVO_RFR_RATE 300 // In Hz, you can set it from 20 to 400Hz, used only in HW PWM mode
81 #define MULTIPLE_CONFIGURATION_PROFILES
82 #define DISPLAY_FONT_DSIZE
87 #define YAW_COLL_PRECOMP 15
88 #define YAW_COLL_PRECOMP_DEADBAND 130
90 #define FORCE_ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = X; imu.accADC[PITCH] = Y; imu.accADC[YAW] = Z;}
91 #define FORCE_GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = -Y; imu.gyroADC[PITCH] = X; imu.gyroADC[YAW] = -Z;}
92 #define A32U4_4_HW_PWM_SERVOS
93 #define SERVO_RFR_RATE 200 // 200 for graupner is ok
94 #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
97 #define RCOPTIONSBEEP // ca. 80byte
100 #define DISPLAY_FONT_DSIZE
103 #define LCD_TELEMETRY
104 #define LCD_TELEMETRY_AUTO "1"
105 #define LCD_TELEMETRY_STEP "F14$5R"
106 #define LOG_PERMANENT
107 #define LOG_PERMANENT_SHOW_AFTER_CONFIG
108 #define SUPPRESS_OTHER_SERIAL_COMMANDS
109 #define SUPPRESS_DEFAULTS_FROM_GUI
110 #define NO_FLASH_CHECK
112 #elif COPTERTEST == 8
115 #define PID_CONTROLLER 2
116 #define ESC_CALIB_CANNOT_FLY
117 #elif COPTERTEST == 9
120 #define POWERMETER_HARD
124 #define VBAT_CELLS_NUM 3
125 #define VBAT_CELLS_PINS {A0, A1, A2 }
126 #define VBAT_CELLS_OFFSETS {0, 50, 83 }
127 #define VBAT_CELLS_DIVS { 75, 122, 98 }
128 #elif COPTERTEST == 10
130 #define CRIUS_AIO_PRO
132 #define SERIAL0_COM_SPEED 9600
134 #elif defined(COPTERTEST)
135 #error "*** this test is not yet defined"
143 #if defined(__AVR_ATmega168__) || defined(__AVR_ATmega328P__)
146 #if defined(__AVR_ATmega32U4__) || defined(TEENSY20)
149 #if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2560__) || defined(__AVR_ATmega2561__)
157 #define SERVO_RATES {30,30,100,100,100,100,100,100}
159 #if defined (AIRPLANE) || defined(FLYING_WING)
163 #if defined(HELI_120_CCPM) || defined(HELI_90_DEG)
167 #if defined(BI) || defined(TRI) || defined(FIXEDWING) || defined(HELICOPTER) || defined(SINGLECOPTER)|| defined(DUALCOPTER)
168 #define COPTER_WITH_SERVO
171 #if defined(COPTER_WITH_SERVO) || defined(SERVO_TILT) || defined(GIMBAL) || defined(CAMTRIG) || defined(SERVO_MIX_TILT)
175 #if defined(DYNBALANCE)
186 #if defined(MEGA) && defined(MEGA_HW_PWM_SERVOS)
193 #define NUMBER_MOTOR 0
194 #define PRI_SERVO_FROM 1 // use servo from 1 to 2
195 #define PRI_SERVO_TO 2
196 #elif defined(FLYING_WING)
197 #define PRI_SERVO_FROM 4
198 #if defined (USE_THROTTLESERVO)
199 #define NUMBER_MOTOR 0
200 #define PRI_SERVO_TO 8 // use servo from 4,5 and 8
202 #define NUMBER_MOTOR 1
203 #define PRI_SERVO_TO 5 // use servo from 4 to 5
205 #elif defined(SINGLECOPTER)
206 #define NUMBER_MOTOR 1
207 #define PRI_SERVO_FROM 4 // use servo from 4 to 7
208 #define PRI_SERVO_TO 7
209 #elif defined(DUALCOPTER)
210 #define NUMBER_MOTOR 2
211 #define PRI_SERVO_FROM 5 // use servo from 5 to 6
212 #define PRI_SERVO_TO 6
213 #elif defined(AIRPLANE)
214 #if defined (USE_THROTTLESERVO)
215 #define NUMBER_MOTOR 0
216 #define PRI_SERVO_TO 8
218 #define NUMBER_MOTOR 1
219 #define PRI_SERVO_TO 7
222 #define PRI_SERVO_FROM 3 // use servo from 3 to 8
223 #undef CAMTRIG // Disable Camtrig on A2
225 #define PRI_SERVO_FROM 4 // use servo from 4 to 8
228 #define NUMBER_MOTOR 2
229 #define PRI_SERVO_FROM 5 // use servo from 5 to 6
230 #define PRI_SERVO_TO 6
232 #define NUMBER_MOTOR 3
233 #define PRI_SERVO_FROM TRI_SERVO // use only servo 6 (or 4 with Mega HW PWM)
234 #define PRI_SERVO_TO TRI_SERVO
235 #elif defined(QUADP) || defined(QUADX) || defined(Y4)|| defined(VTAIL4)
236 #define NUMBER_MOTOR 4
237 #elif defined(Y6) || defined(HEX6) || defined(HEX6X) || defined(HEX6H)
238 #define NUMBER_MOTOR 6
239 #elif defined(OCTOX8) || defined(OCTOFLATP) || defined(OCTOFLATX)
240 #define NUMBER_MOTOR 8
241 #elif defined(HELICOPTER)
242 #define PRI_SERVO_FROM 4
243 #ifdef HELI_USE_SERVO_FOR_THROTTLE
244 #define NUMBER_MOTOR 0 // use servo to drive throttle output
245 #define PRI_SERVO_TO 8 // use servo from 4 to 8
247 #define NUMBER_MOTOR 1 // use motor1 for throttle, DO NOT SET TO 2, OR IT WILL BURN/DESTROY SERVO7 USED FOR SWASH
248 #define PRI_SERVO_TO 7 // use servo from 4 to 7
252 #if (defined(SERVO_TILT)|| defined(SERVO_MIX_TILT))&& defined(CAMTRIG)
253 #define SEC_SERVO_FROM 1 // use servo from 1 to 3
254 #define SEC_SERVO_TO 3
256 #if defined(SERVO_TILT)|| defined(SERVO_MIX_TILT)
258 #if defined(A0_A1_PIN_HEX) && (NUMBER_MOTOR == 6) && defined(PROMINI)
259 #define SEC_SERVO_FROM 3 // use servo from 3 to 4
260 #define SEC_SERVO_TO 4
262 #define SEC_SERVO_FROM 1 // use servo from 1 to 2
263 #define SEC_SERVO_TO 2
267 #define SEC_SERVO_FROM 3 // use servo 3
268 #define SEC_SERVO_TO 3
272 #if defined(SIRIUS_AIR) || defined(SIRIUS_AIR_GPS)
278 #if !defined(MONGOOSE1_0)
279 #define LEDPIN_PINMODE pinMode (13, OUTPUT);
280 #define LEDPIN_TOGGLE PINB |= 1<<5; //switch LEDPIN state (digital PIN 13)
281 #define LEDPIN_OFF PORTB &= ~(1<<5);
282 #define LEDPIN_ON PORTB |= (1<<5);
284 #if !defined(RCAUXPIN8)
285 #if !defined(MONGOOSE1_0)
286 #define BUZZERPIN_PINMODE pinMode (8, OUTPUT);
290 #if defined PILOTLAMP && NUMBER_MOTOR <5
291 #define PL_PIN_ON PORTB |= 1;
292 #define PL_PIN_OFF PORTB &= ~1;
294 #define BUZZERPIN_ON PORTB |= 1;
295 #define BUZZERPIN_OFF PORTB &= ~1;
299 #define BUZZERPIN_PINMODE ;
300 #define BUZZERPIN_ON ;
301 #define BUZZERPIN_OFF ;
304 #if !defined(RCAUXPIN12) && !defined(DISABLE_POWER_PIN)
305 #define POWERPIN_PINMODE pinMode (12, OUTPUT);
306 #define POWERPIN_ON PORTB |= 1<<4;
307 #define POWERPIN_OFF PORTB &= ~(1<<4); //switch OFF WMP, digital PIN 12
309 #define POWERPIN_PINMODE ;
310 #define POWERPIN_ON ;
311 #define POWERPIN_OFF ;
313 #if defined(RCAUXPIN12)
316 #define I2C_PULLUPS_ENABLE PORTC |= 1<<4; PORTC |= 1<<5; // PIN A4&A5 (SDA&SCL)
317 #define I2C_PULLUPS_DISABLE PORTC &= ~(1<<4); PORTC &= ~(1<<5);
318 #if !defined(MONGOOSE1_0)
319 #define PINMODE_LCD pinMode(0, OUTPUT);
320 #define LCDPIN_OFF PORTD &= ~1; //switch OFF digital PIN 0
321 #define LCDPIN_ON PORTD |= 1;
322 #define STABLEPIN_PINMODE ;
323 #define STABLEPIN_ON ;
324 #define STABLEPIN_OFF ;
326 #define PPM_PIN_INTERRUPT attachInterrupt(0, rxInt, RISING); //PIN 0
327 #define RX_SERIAL_PORT 0
329 #define THROTTLEPIN 2
334 #define AUX2PIN 0 // optional PIN 8 or PIN 12
335 #define AUX3PIN 1 // unused
336 #define AUX4PIN 3 // unused
338 #define PCINT_PIN_COUNT 5
339 #define PCINT_RX_BITS (1<<2),(1<<4),(1<<5),(1<<6),(1<<7)
340 #define PCINT_RX_PORT PORTD
341 #define PCINT_RX_MASK PCMSK2
342 #define PCIR_PORT_BIT (1<<2)
343 #define RX_PC_INTERRUPT PCINT2_vect
344 #define RX_PCINT_PIN_PORT PIND
345 #define V_BATPIN A3 // Analog PIN 3
346 #define PSENSORPIN A2 // Analog PIN 2
348 #if defined(A0_A1_PIN_HEX) || (NUMBER_MOTOR > 6)
349 #define SOFT_PWM_1_PIN_HIGH PORTC |= 1<<0;
350 #define SOFT_PWM_1_PIN_LOW PORTC &= ~(1<<0);
351 #define SOFT_PWM_2_PIN_HIGH PORTC |= 1<<1;
352 #define SOFT_PWM_2_PIN_LOW PORTC &= ~(1<<1);
354 #define SOFT_PWM_1_PIN_HIGH PORTD |= 1<<5;
355 #define SOFT_PWM_1_PIN_LOW PORTD &= ~(1<<5);
356 #define SOFT_PWM_2_PIN_HIGH PORTD |= 1<<6;
357 #define SOFT_PWM_2_PIN_LOW PORTD &= ~(1<<6);
359 #define SOFT_PWM_3_PIN_HIGH PORTC |= 1<<2;
360 #define SOFT_PWM_3_PIN_LOW PORTC &= ~(1<<2);
361 #define SOFT_PWM_4_PIN_HIGH PORTB |= 1<<4;
362 #define SOFT_PWM_4_PIN_LOW PORTB &= ~(1<<4);
364 #define SERVO_1_PINMODE pinMode(A0,OUTPUT); // TILT_PITCH - WING left
365 #define SERVO_1_PIN_HIGH PORTC |= 1<<0;
366 #define SERVO_1_PIN_LOW PORTC &= ~(1<<0);
367 #define SERVO_2_PINMODE pinMode(A1,OUTPUT); // TILT_ROLL - WING right
368 #define SERVO_2_PIN_HIGH PORTC |= 1<<1;
369 #define SERVO_2_PIN_LOW PORTC &= ~(1<<1);
370 #define SERVO_3_PINMODE pinMode(A2,OUTPUT); // CAM TRIG - alt TILT_PITCH
371 #define SERVO_3_PIN_HIGH PORTC |= 1<<2;
372 #define SERVO_3_PIN_LOW PORTC &= ~(1<<2);
373 #if !defined(MONGOOSE1_0)
374 #define SERVO_4_PINMODE pinMode(12,OUTPUT); // new - alt TILT_ROLL
375 #define SERVO_4_PIN_HIGH PORTB |= 1<<4;
376 #define SERVO_4_PIN_LOW PORTB &= ~(1<<4);
378 #define SERVO_5_PINMODE pinMode(11,OUTPUT); // BI LEFT
379 #define SERVO_5_PIN_HIGH PORTB |= 1<<3;
380 #define SERVO_5_PIN_LOW PORTB &= ~(1<<3);
381 #define SERVO_6_PINMODE pinMode(3,OUTPUT); // TRI REAR - BI RIGHT
382 #define SERVO_6_PIN_HIGH PORTD|= 1<<3;
383 #define SERVO_6_PIN_LOW PORTD &= ~(1<<3);
384 #define SERVO_7_PINMODE pinMode(10,OUTPUT); // new
385 #define SERVO_7_PIN_HIGH PORTB |= 1<<2;
386 #define SERVO_7_PIN_LOW PORTB &= ~(1<<2);
387 #define SERVO_8_PINMODE pinMode(9,OUTPUT); // new
388 #define SERVO_8_PIN_HIGH PORTB |= 1<<1;
389 #define SERVO_8_PIN_LOW PORTB &= ~(1<<1);
393 #if defined(PROMICRO)
394 #if defined(MICROWII)
397 #if !defined(TEENSY20)
398 #define LEDPIN_PINMODE //
399 #define LEDPIN_TOGGLE PIND |= 1<<5; //switch LEDPIN state (Port D5)
400 #if !defined(PROMICRO10)
401 #define LEDPIN_OFF PORTD |= (1<<5);
402 #define LEDPIN_ON PORTD &= ~(1<<5);
404 #define LEDPIN_OFF PORTD &= ~(1<<5);
405 #define LEDPIN_ON PORTD |= (1<<5);
408 #define LEDPIN_PINMODE DDRD |= (1<<6);
409 #define LEDPIN_OFF PORTD &= ~(1<<6);
410 #define LEDPIN_ON PORTD |= (1<<6);
411 #define LEDPIN_TOGGLE PIND |= 1<<6; //switch LEDPIN state (Port D6)
413 #if defined(D8BUZZER)
414 #define BUZZERPIN_PINMODE DDRB |= (1<<4);
415 #if defined PILOTLAMP
416 #define PL_PIN_ON PORTB |= 1<<4;
417 #define PL_PIN_OFF PORTB &= ~(1<<4);
419 #define BUZZERPIN_ON PORTB |= 1<<4;
420 #define BUZZERPIN_OFF PORTB &= ~(1<<4);
423 #elif defined(A32U4ALLPINS)
424 #define BUZZERPIN_PINMODE DDRD |= (1<<4);
425 #if defined PILOTLAMP
426 #define PL_PIN_ON PORTD |= 1<<4;
427 #define PL_PIN_OFF PORTD &= ~(1<<4);
429 #define BUZZERPIN_ON PORTD |= 1<<4;
430 #define BUZZERPIN_OFF PORTD &= ~(1<<4);
433 #define BUZZERPIN_PINMODE DDRD |= (1<<3);
434 #if defined PILOTLAMP
435 #define PL_PIN_ON PORTD |= 1<<3;
436 #define PL_PIN_OFF PORTD &= ~(1<<3);
438 #define BUZZERPIN_ON PORTD |= 1<<3;
439 #define BUZZERPIN_OFF PORTD &= ~(1<<3);
442 #define POWERPIN_PINMODE //
443 #define POWERPIN_ON //
444 #define POWERPIN_OFF //
445 #define I2C_PULLUPS_ENABLE PORTD |= 1<<0; PORTD |= 1<<1; // PIN 2&3 (SDA&SCL)
446 #define I2C_PULLUPS_DISABLE PORTD &= ~(1<<0); PORTD &= ~(1<<1);
447 #define PINMODE_LCD DDRD |= (1<<2);
448 #define LCDPIN_OFF PORTD &= ~1;
449 #define LCDPIN_ON PORTD |= 1;
450 #define STABLEPIN_PINMODE ;
451 #define STABLEPIN_ON ;
452 #define STABLEPIN_OFF ;
453 #define PPM_PIN_INTERRUPT DDRE &= ~(1 << 6);PORTE |= (1 << 6); EICRB |= (1 << ISC61)|(1 << ISC60); EIMSK |= (1 << INT6);
454 #if !defined(RX_SERIAL_PORT)
455 #define RX_SERIAL_PORT 1
461 #define SOFT_PWM_1_PIN_HIGH PORTD |= 1<<4;
462 #define SOFT_PWM_1_PIN_LOW PORTD &= ~(1<<4);
463 #define SOFT_PWM_2_PIN_HIGH PORTF |= 1<<5;
464 #define SOFT_PWM_2_PIN_LOW PORTF &= ~(1<<5);
465 #if !defined(A32U4ALLPINS)
466 #define SOFT_PWM_3_PIN_HIGH PORTF |= 1<<7;
467 #define SOFT_PWM_3_PIN_LOW PORTF &= ~(1<<7);
468 #define SOFT_PWM_4_PIN_HIGH PORTF |= 1<<6;
469 #define SOFT_PWM_4_PIN_LOW PORTF &= ~(1<<6);
473 #define SOFT_PWM_3_PIN_HIGH PORTF |= 1<<4;
474 #define SOFT_PWM_3_PIN_LOW PORTF &= ~(1<<4);
475 #define SOFT_PWM_4_PIN_HIGH PORTF |= 1<<5;
476 #define SOFT_PWM_4_PIN_LOW PORTF &= ~(1<<5);
482 #define SERVO_1_PINMODE DDRF |= (1<<7); // A0
483 #define SERVO_1_PIN_HIGH PORTF|= 1<<7;
484 #define SERVO_1_PIN_LOW PORTF &= ~(1<<7);
485 #define SERVO_2_PINMODE DDRF |= (1<<6); // A1
486 #define SERVO_2_PIN_HIGH PORTF |= 1<<6;
487 #define SERVO_2_PIN_LOW PORTF &= ~(1<<6);
488 #define SERVO_3_PINMODE DDRF |= (1<<5); // A2
489 #define SERVO_3_PIN_HIGH PORTF |= 1<<5;
490 #define SERVO_3_PIN_LOW PORTF &= ~(1<<5);
491 #if !defined(A32U4ALLPINS)
492 #define SERVO_4_PINMODE DDRD |= (1<<4); // 4
493 #define SERVO_4_PIN_HIGH PORTD |= 1<<4;
494 #define SERVO_4_PIN_LOW PORTD &= ~(1<<4);
496 #define SERVO_4_PINMODE DDRF |= (1<<4); // A3
497 #define SERVO_4_PIN_HIGH PORTF |= 1<<4;
498 #define SERVO_4_PIN_LOW PORTF &= ~(1<<4);
500 #define SERVO_5_PINMODE DDRC |= (1<<6); // 5
501 #define SERVO_5_PIN_HIGH PORTC|= 1<<6;
502 #define SERVO_5_PIN_LOW PORTC &= ~(1<<6);
503 #define SERVO_6_PINMODE DDRD |= (1<<7); // 6
504 #define SERVO_6_PIN_HIGH PORTD |= 1<<7;
505 #define SERVO_6_PIN_LOW PORTD &= ~(1<<7);
506 #define SERVO_7_PINMODE DDRB |= (1<<6); // 10
507 #define SERVO_7_PIN_HIGH PORTB |= 1<<6;
508 #define SERVO_7_PIN_LOW PORTB &= ~(1<<6);
509 #define SERVO_8_PINMODE DDRB |= (1<<5); // 9
510 #define SERVO_8_PIN_HIGH PORTB |= 1<<5;
511 #define SERVO_8_PIN_LOW PORTB &= ~(1<<5);
514 #define THROTTLEPIN 3
515 #if defined(A32U4ALLPINS)
527 #define AUX3PIN 1 // unused
528 #define AUX4PIN 0 // unused
529 #if !defined(RCAUX2PIND17)
530 #define PCINT_PIN_COUNT 4
531 #define PCINT_RX_BITS (1<<1),(1<<2),(1<<3),(1<<4)
533 #define PCINT_PIN_COUNT 5 // one more bit (PB0) is added in RX code
534 #define PCINT_RX_BITS (1<<1),(1<<2),(1<<3),(1<<4),(1<<0)
536 #define PCINT_RX_PORT PORTB
537 #define PCINT_RX_MASK PCMSK0
538 #define PCIR_PORT_BIT (1<<0)
539 #define RX_PC_INTERRUPT PCINT0_vect
540 #define RX_PCINT_PIN_PORT PINB
542 #if !defined(A32U4ALLPINS) && !defined(TEENSY20)
543 #define V_BATPIN A3 // Analog PIN 3
544 #elif defined(A32U4ALLPINS)
545 #define V_BATPIN A4 // Analog PIN 4
547 #define V_BATPIN A2 // Analog PIN 3
549 #if !defined(TEENSY20)
550 #define PSENSORPIN A2 // Analog PIN 2
552 #define PSENSORPIN A2 // Analog PIN 2
558 #define LEDPIN_PINMODE pinMode (13, OUTPUT);pinMode (30, OUTPUT);
559 #define LEDPIN_TOGGLE PINB |= (1<<7); PINC |= (1<<7);
560 #define LEDPIN_ON PORTB |= (1<<7); PORTC |= (1<<7);
561 #define LEDPIN_OFF PORTB &= ~(1<<7);PORTC &= ~(1<<7);
562 #define BUZZERPIN_PINMODE pinMode (32, OUTPUT);
563 #if defined PILOTLAMP
564 #define PL_PIN_ON PORTC |= 1<<5;
565 #define PL_PIN_OFF PORTC &= ~(1<<5);
567 #define BUZZERPIN_ON PORTC |= 1<<5;
568 #define BUZZERPIN_OFF PORTC &= ~(1<<5);
571 #if !defined(DISABLE_POWER_PIN)
572 #define POWERPIN_PINMODE pinMode (37, OUTPUT);
573 #define POWERPIN_ON PORTC |= 1<<0;
574 #define POWERPIN_OFF PORTC &= ~(1<<0);
576 #define POWERPIN_PINMODE ;
577 #define POWERPIN_ON ;
578 #define POWERPIN_OFF ;
580 #define I2C_PULLUPS_ENABLE PORTD |= 1<<0; PORTD |= 1<<1; // PIN 20&21 (SDA&SCL)
581 #define I2C_PULLUPS_DISABLE PORTD &= ~(1<<0); PORTD &= ~(1<<1);
582 #define PINMODE_LCD pinMode(0, OUTPUT);
583 #define LCDPIN_OFF PORTE &= ~1; //switch OFF digital PIN 0
584 #define LCDPIN_ON PORTE |= 1;
585 #define STABLEPIN_PINMODE pinMode (31, OUTPUT);
586 #define STABLEPIN_ON PORTC |= 1<<6;
587 #define STABLEPIN_OFF PORTC &= ~(1<<6);
588 #if defined(PPM_ON_THROTTLE)
590 #define PPM_PIN_INTERRUPT DDRK &= ~(1<<0); PORTK |= (1<<0); PCICR |= (1<<2); PCMSK2 |= (1<<0);
592 #define PPM_PIN_INTERRUPT attachInterrupt(4, rxInt, RISING); //PIN 19, also used for Spektrum satellite option
594 #if !defined(RX_SERIAL_PORT)
595 #define RX_SERIAL_PORT 1
598 #define THROTTLEPIN 0 //PIN 62 = PIN A8
599 #define ROLLPIN 1 //PIN 63 = PIN A9
600 #define PITCHPIN 2 //PIN 64 = PIN A10
601 #define YAWPIN 3 //PIN 65 = PIN A11
602 #define AUX1PIN 4 //PIN 66 = PIN A12
603 #define AUX2PIN 5 //PIN 67 = PIN A13
604 #define AUX3PIN 6 //PIN 68 = PIN A14
605 #define AUX4PIN 7 //PIN 69 = PIN A15
606 #define V_BATPIN A0 // Analog PIN 0
607 #define PSENSORPIN A2 // Analog PIN 2
608 #define PCINT_PIN_COUNT 8
609 #define PCINT_RX_BITS (1<<2),(1<<4),(1<<5),(1<<6),(1<<7),(1<<0),(1<<1),(1<<3)
610 #define PCINT_RX_PORT PORTK
611 #define PCINT_RX_MASK PCMSK2
612 #define PCIR_PORT_BIT (1<<2)
613 #define RX_PC_INTERRUPT PCINT2_vect
614 #define RX_PCINT_PIN_PORT PINK
616 #define SERVO_1_PINMODE pinMode(34,OUTPUT);pinMode(44,OUTPUT); // TILT_PITCH - WING left
617 #define SERVO_1_PIN_HIGH PORTC |= 1<<3;PORTL |= 1<<5;
618 #define SERVO_1_PIN_LOW PORTC &= ~(1<<3);PORTL &= ~(1<<5);
619 #define SERVO_2_PINMODE pinMode(35,OUTPUT);pinMode(45,OUTPUT); // TILT_ROLL - WING right
620 #define SERVO_2_PIN_HIGH PORTC |= 1<<2;PORTL |= 1<<4;
621 #define SERVO_2_PIN_LOW PORTC &= ~(1<<2);PORTL &= ~(1<<4);
622 #define SERVO_3_PINMODE pinMode(33,OUTPUT); pinMode(46,OUTPUT); // CAM TRIG - alt TILT_PITCH
623 #define SERVO_3_PIN_HIGH PORTC |= 1<<4;PORTL |= 1<<3;
624 #define SERVO_3_PIN_LOW PORTC &= ~(1<<4);PORTL &= ~(1<<3);
625 #define SERVO_4_PINMODE pinMode (37, OUTPUT);pinMode(7,OUTPUT); // new - alt TILT_ROLL
626 #define SERVO_4_PIN_HIGH PORTC |= 1<<0; PORTH |= 1<<4;
627 #define SERVO_4_PIN_LOW PORTC &= ~(1<<0);PORTH &= ~(1<<4);
629 #define SERVO_5_PINMODE pinMode(6,OUTPUT); // BI LEFT
630 #define SERVO_5_PIN_HIGH PORTH |= 1<<3;
631 #define SERVO_5_PIN_LOW PORTH &= ~(1<<3);
632 #define SERVO_6_PINMODE pinMode(2,OUTPUT); // TRI REAR - BI RIGHT
633 #define SERVO_6_PIN_HIGH PORTE |= 1<<4;
634 #define SERVO_6_PIN_LOW PORTE &= ~(1<<4);
635 #define SERVO_7_PINMODE pinMode(5,OUTPUT); // new
636 #define SERVO_7_PIN_HIGH PORTE |= 1<<3;
637 #define SERVO_7_PIN_LOW PORTE &= ~(1<<3);
638 #define SERVO_8_PINMODE pinMode(3,OUTPUT); // new
639 #define SERVO_8_PIN_HIGH PORTE |= 1<<5;
640 #define SERVO_8_PIN_LOW PORTE &= ~(1<<5);
647 #if defined(MONGOOSE1_0) // basically it's a PROMINI without some PINS => same code as a PROMINI board except PIN definition
650 #define LEDPIN_PINMODE pinMode (4, OUTPUT);
651 #define LEDPIN_TOGGLE PIND |= 1<<4; //switch LEDPIN state (digital PIN 13)
652 #define LEDPIN_OFF PORTD &= ~(1<<4);
653 #define LEDPIN_ON PORTD |= (1<<4);
654 #define SPEK_BAUD_SET UCSR0A = (1<<U2X0); UBRR0H = ((F_CPU / 4 / 115200 -1) / 2) >> 8; UBRR0L = ((F_CPU / 4 / 115200 -1) / 2);
655 #define RX_SERIAL_PORT 0
658 #define BUZZERPIN_PINMODE ; // D8
659 #define BUZZERPIN_ON ;
660 #define BUZZERPIN_OFF ;
661 #define POWERPIN_PINMODE ; // D12
662 #define POWERPIN_ON ;
663 #define POWERPIN_OFF ;
664 #define STABLEPIN_PINMODE ; //
665 #define STABLEPIN_ON ;
666 #define STABLEPIN_OFF ;
667 #define PINMODE_LCD ; //
672 #define SERVO_4_PINMODE ; // Not available
673 #define SERVO_4_PIN_HIGH ;
674 #define SERVO_4_PIN_LOW ;
681 #if (PRI_SERVO_FROM == 1) || (SEC_SERVO_FROM == 1)
682 #define LAST_LOW SERVO_1_PIN_LOW
683 #define SERVO_1_HIGH SERVO_1_PIN_HIGH
684 #define SERVO_1_LOW SERVO_1_PIN_LOW
685 #define SERVO_1_ARR_POS 0
687 #if (PRI_SERVO_FROM <= 2 && PRI_SERVO_TO >= 2) || (SEC_SERVO_FROM <= 2 && SEC_SERVO_TO >= 2)
689 #define LAST_LOW SERVO_2_PIN_LOW
690 #if !defined(SERVO_1_HIGH)
691 #define SERVO_1_HIGH SERVO_2_PIN_HIGH
692 #define SERVO_1_LOW SERVO_2_PIN_LOW
693 #define SERVO_1_ARR_POS 1
695 #define SERVO_2_HIGH SERVO_2_PIN_HIGH
696 #define SERVO_2_LOW SERVO_2_PIN_LOW
697 #define SERVO_2_ARR_POS 1
700 #if (PRI_SERVO_FROM <= 3 && PRI_SERVO_TO >= 3) || (SEC_SERVO_FROM <= 3 && SEC_SERVO_TO >= 3)
702 #define LAST_LOW SERVO_3_PIN_LOW
703 #if !defined(SERVO_1_HIGH)
704 #define SERVO_1_HIGH SERVO_3_PIN_HIGH
705 #define SERVO_1_LOW SERVO_3_PIN_LOW
706 #define SERVO_1_ARR_POS 2
707 #elif !defined(SERVO_2_HIGH)
708 #define SERVO_2_HIGH SERVO_3_PIN_HIGH
709 #define SERVO_2_LOW SERVO_3_PIN_LOW
710 #define SERVO_2_ARR_POS 2
712 #define SERVO_3_HIGH SERVO_3_PIN_HIGH
713 #define SERVO_3_LOW SERVO_3_PIN_LOW
714 #define SERVO_3_ARR_POS 2
717 #if (PRI_SERVO_FROM <= 4 && PRI_SERVO_TO >= 4) || (SEC_SERVO_FROM <= 4 && SEC_SERVO_TO >= 4)
719 #define LAST_LOW SERVO_4_PIN_LOW
720 #if !defined(SERVO_1_HIGH)
721 #define SERVO_1_HIGH SERVO_4_PIN_HIGH
722 #define SERVO_1_LOW SERVO_4_PIN_LOW
723 #define SERVO_1_ARR_POS 3
724 #elif !defined(SERVO_2_HIGH)
725 #define SERVO_2_HIGH SERVO_4_PIN_HIGH
726 #define SERVO_2_LOW SERVO_4_PIN_LOW
727 #define SERVO_2_ARR_POS 3
728 #elif !defined(SERVO_3_HIGH)
729 #define SERVO_3_HIGH SERVO_4_PIN_HIGH
730 #define SERVO_3_LOW SERVO_4_PIN_LOW
731 #define SERVO_3_ARR_POS 3
733 #define SERVO_4_HIGH SERVO_4_PIN_HIGH
734 #define SERVO_4_LOW SERVO_4_PIN_LOW
735 #define SERVO_4_ARR_POS 3
738 #if (PRI_SERVO_FROM <= 5 && PRI_SERVO_TO >= 5) || (SEC_SERVO_FROM <= 5 && SEC_SERVO_TO >= 5)
740 #define LAST_LOW SERVO_5_PIN_LOW
741 #if !defined(SERVO_1_HIGH)
742 #define SERVO_1_HIGH SERVO_5_PIN_HIGH
743 #define SERVO_1_LOW SERVO_5_PIN_LOW
744 #define SERVO_1_ARR_POS 4
745 #elif !defined(SERVO_2_HIGH)
746 #define SERVO_2_HIGH SERVO_5_PIN_HIGH
747 #define SERVO_2_LOW SERVO_5_PIN_LOW
748 #define SERVO_2_ARR_POS 4
749 #elif !defined(SERVO_3_HIGH)
750 #define SERVO_3_HIGH SERVO_5_PIN_HIGH
751 #define SERVO_3_LOW SERVO_5_PIN_LOW
752 #define SERVO_3_ARR_POS 4
753 #elif !defined(SERVO_4_HIGH)
754 #define SERVO_4_HIGH SERVO_5_PIN_HIGH
755 #define SERVO_4_LOW SERVO_5_PIN_LOW
756 #define SERVO_4_ARR_POS 4
758 #define SERVO_5_HIGH SERVO_5_PIN_HIGH
759 #define SERVO_5_LOW SERVO_5_PIN_LOW
760 #define SERVO_5_ARR_POS 4
763 #if (PRI_SERVO_FROM <= 6 && PRI_SERVO_TO >= 6) || (SEC_SERVO_FROM <= 6 && SEC_SERVO_TO >= 6)
765 #define LAST_LOW SERVO_6_PIN_LOW
766 #if !defined(SERVO_1_HIGH)
767 #define SERVO_1_HIGH SERVO_6_PIN_HIGH
768 #define SERVO_1_LOW SERVO_6_PIN_LOW
769 #define SERVO_1_ARR_POS 5
770 #elif !defined(SERVO_2_HIGH)
771 #define SERVO_2_HIGH SERVO_6_PIN_HIGH
772 #define SERVO_2_LOW SERVO_6_PIN_LOW
773 #define SERVO_2_ARR_POS 5
774 #elif !defined(SERVO_3_HIGH)
775 #define SERVO_3_HIGH SERVO_6_PIN_HIGH
776 #define SERVO_3_LOW SERVO_6_PIN_LOW
777 #define SERVO_3_ARR_POS 5
778 #elif !defined(SERVO_4_HIGH)
779 #define SERVO_4_HIGH SERVO_6_PIN_HIGH
780 #define SERVO_4_LOW SERVO_6_PIN_LOW
781 #define SERVO_4_ARR_POS 5
782 #elif !defined(SERVO_5_HIGH)
783 #define SERVO_5_HIGH SERVO_6_PIN_HIGH
784 #define SERVO_5_LOW SERVO_6_PIN_LOW
785 #define SERVO_5_ARR_POS 5
787 #define SERVO_6_HIGH SERVO_6_PIN_HIGH
788 #define SERVO_6_LOW SERVO_6_PIN_LOW
789 #define SERVO_6_ARR_POS 5
792 #if (PRI_SERVO_FROM <= 7 && PRI_SERVO_TO >= 7) || (SEC_SERVO_FROM <= 7 && SEC_SERVO_TO >= 7)
794 #define LAST_LOW SERVO_7_PIN_LOW
795 #if !defined(SERVO_1_HIGH)
796 #define SERVO_1_HIGH SERVO_7_PIN_HIGH
797 #define SERVO_1_LOW SERVO_7_PIN_LOW
798 #define SERVO_1_ARR_POS 6
799 #elif !defined(SERVO_2_HIGH)
800 #define SERVO_2_HIGH SERVO_7_PIN_HIGH
801 #define SERVO_2_LOW SERVO_7_PIN_LOW
802 #define SERVO_2_ARR_POS 6
803 #elif !defined(SERVO_3_HIGH)
804 #define SERVO_3_HIGH SERVO_7_PIN_HIGH
805 #define SERVO_3_LOW SERVO_7_PIN_LOW
806 #define SERVO_3_ARR_POS 6
807 #elif !defined(SERVO_4_HIGH)
808 #define SERVO_4_HIGH SERVO_7_PIN_HIGH
809 #define SERVO_4_LOW SERVO_7_PIN_LOW
810 #define SERVO_4_ARR_POS 6
811 #elif !defined(SERVO_5_HIGH)
812 #define SERVO_5_HIGH SERVO_7_PIN_HIGH
813 #define SERVO_5_LOW SERVO_7_PIN_LOW
814 #define SERVO_5_ARR_POS 6
815 #elif !defined(SERVO_6_HIGH)
816 #define SERVO_6_HIGH SERVO_7_PIN_HIGH
817 #define SERVO_6_LOW SERVO_7_PIN_LOW
818 #define SERVO_6_ARR_POS 6
820 #define SERVO_7_HIGH SERVO_7_PIN_HIGH
821 #define SERVO_7_LOW SERVO_7_PIN_LOW
822 #define SERVO_7_ARR_POS 6
825 #if (PRI_SERVO_FROM <= 8 && PRI_SERVO_TO >= 8) || (SEC_SERVO_FROM <= 8 && SEC_SERVO_TO >= 8)
827 #define LAST_LOW SERVO_8_PIN_LOW
828 #if !defined(SERVO_1_HIGH)
829 #define SERVO_1_HIGH SERVO_8_PIN_HIGH
830 #define SERVO_1_LOW SERVO_8_PIN_LOW
831 #define SERVO_1_ARR_POS 7
832 #elif !defined(SERVO_2_HIGH)
833 #define SERVO_2_HIGH SERVO_8_PIN_HIGH
834 #define SERVO_2_LOW SERVO_8_PIN_LOW
835 #define SERVO_2_ARR_POS 7
836 #elif !defined(SERVO_3_HIGH)
837 #define SERVO_3_HIGH SERVO_8_PIN_HIGH
838 #define SERVO_3_LOW SERVO_8_PIN_LOW
839 #define SERVO_3_ARR_POS 7
840 #elif !defined(SERVO_4_HIGH)
841 #define SERVO_4_HIGH SERVO_8_PIN_HIGH
842 #define SERVO_4_LOW SERVO_8_PIN_LOW
843 #define SERVO_4_ARR_POS 7
844 #elif !defined(SERVO_5_HIGH)
845 #define SERVO_5_HIGH SERVO_8_PIN_HIGH
846 #define SERVO_5_LOW SERVO_8_PIN_LOW
847 #define SERVO_5_ARR_POS 7
848 #elif !defined(SERVO_6_HIGH)
849 #define SERVO_6_HIGH SERVO_8_PIN_HIGH
850 #define SERVO_6_LOW SERVO_8_PIN_LOW
851 #define SERVO_6_ARR_POS 7
852 #elif !defined(SERVO_7_HIGH)
853 #define SERVO_7_HIGH SERVO_8_PIN_HIGH
854 #define SERVO_7_LOW SERVO_8_PIN_LOW
855 #define SERVO_7_ARR_POS 7
857 #define SERVO_8_HIGH SERVO_8_PIN_HIGH
858 #define SERVO_8_LOW SERVO_8_PIN_LOW
859 #define SERVO_8_ARR_POS 7
863 #if ( defined(MEGA) && defined(MEGA_HW_PWM_SERVOS) ) || (defined(PROMICRO) && defined(A32U4_4_HW_PWM_SERVOS))
864 #undef SERVO_1_HIGH // No software PWM's if we use hardware MEGA PWM or promicro hardware pwm
865 #define HW_PWM_SERVOS
880 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
881 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
882 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = -Z;}
890 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
891 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
892 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = Y; imu.magADC[PITCH] = -X; imu.magADC[YAW] = -Z;}
895 #if defined(FREEIMUv1)
899 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
900 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
901 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = -Z;}
902 #define ADXL345_ADDRESS 0x53
903 #undef INTERNAL_I2C_PULLUPS
906 #if defined(FREEIMUv03)
908 #define ADXL345 // this is actually an ADXL346 but that's just the same as ADXL345
910 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
911 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
912 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = -Z;}
913 #define ADXL345_ADDRESS 0x53
914 #undef INTERNAL_I2C_PULLUPS
917 #if defined(FREEIMUv035) || defined(FREEIMUv035_MS) || defined(FREEIMUv035_BMP)
921 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
922 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
923 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = -Z;}
924 #undef INTERNAL_I2C_PULLUPS
925 #if defined(FREEIMUv035_MS)
927 #elif defined(FREEIMUv035_BMP)
932 #if defined(FREEIMUv04)
936 #if defined(MultiWiiMega)
940 #if defined(FREEIMUv043) || defined(MICROWII)
944 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
945 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
946 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = -Z;}
947 #define MPU6050_I2C_AUX_MASTER // MAG connected to the AUX I2C bus of MPU6050
948 #undef INTERNAL_I2C_PULLUPS
953 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -Y; imu.accADC[PITCH] = X; imu.accADC[YAW] = Z;}
954 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = -X; imu.gyroADC[PITCH] = -Y; imu.gyroADC[YAW] = -Z;}
955 #undef INTERNAL_I2C_PULLUPS
957 #undef SOFT_PWM_3_PIN_HIGH
958 #undef SOFT_PWM_3_PIN_LOW
959 #undef SOFT_PWM_4_PIN_HIGH
960 #undef SOFT_PWM_4_PIN_LOW
963 #define SOFT_PWM_3_PIN_HIGH PORTD |= 1<<4;
964 #define SOFT_PWM_3_PIN_LOW PORTD &= ~(1<<4);
965 #define SOFT_PWM_4_PIN_HIGH PORTF |= 1<<5;
966 #define SOFT_PWM_4_PIN_LOW PORTF &= ~(1<<5);
971 #undef SERVO_3_PINMODE
972 #undef SERVO_3_PIN_HIGH
973 #undef SERVO_3_PIN_LOW
974 #undef SERVO_4_PINMODE
975 #undef SERVO_4_PIN_HIGH
976 #undef SERVO_4_PIN_LOW
977 #define SERVO_3_PINMODE DDRC |= (1<<7); // 13
978 #define SERVO_3_PIN_HIGH PORTC |= 1<<7;
979 #define SERVO_3_PIN_LOW PORTC &= ~(1<<7);
980 #define SERVO_4_PINMODE DDRB |= (1<<7); // 11
981 #define SERVO_4_PIN_HIGH PORTB |= 1<<7;
982 #define SERVO_4_PIN_LOW PORTB &= ~(1<<7);
984 #if !defined(OCTOX8) && !defined(OCTOFLATP) && !defined(OCTOFLATX)
985 #undef LEDPIN_PINMODE
989 #define LEDPIN_PINMODE DDRD |= (1<<4); //D4 to output
990 #define LEDPIN_TOGGLE PIND |= (1<<5)|(1<<4); //switch LEDPIN state (Port D5) & pin D4
991 #define LEDPIN_OFF PORTD |= (1<<5); PORTD &= ~(1<<4);
992 #define LEDPIN_ON PORTD &= ~(1<<5); PORTD |= (1<<4);
1000 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
1001 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = X; imu.gyroADC[PITCH] = Y; imu.gyroADC[YAW] = -Z;}
1002 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = Y; imu.magADC[PITCH] = -X; imu.magADC[YAW] = Z;}
1003 #define ADXL345_ADDRESS 0x53
1006 #if defined(QUADRINO)
1011 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
1012 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
1013 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = -Z;}
1016 #if defined(QUADRINO_ZOOM)
1021 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
1022 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
1023 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = -Z;}
1024 #define STABLEPIN_PINMODE pinMode (A2, OUTPUT);
1025 #define STABLEPIN_ON PORTC |= (1<<2);
1026 #define STABLEPIN_OFF PORTC &= ~(1<<2);
1029 #if defined(QUADRINO_ZOOM_MS)
1034 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
1035 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
1036 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = -Z;}
1037 #define STABLEPIN_PINMODE pinMode (A2, OUTPUT);
1038 #define STABLEPIN_ON PORTC |= (1<<2);
1039 #define STABLEPIN_OFF PORTC &= ~(1<<2);
1042 #if defined(ALLINONE)
1047 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
1048 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
1049 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = -Z;}
1050 #define BMA180_ADDRESS 0x41
1053 #if defined(AEROQUADSHIELDv2) // to confirm
1058 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
1059 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = X; imu.gyroADC[PITCH] = Y; imu.gyroADC[YAW] = -Z;}
1060 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = -Z;}
1061 #define GYRO_ADDRESS 0X69
1064 #if defined(ATAVRSBIN1)
1066 #define BMA020 //Actually it's a BMA150, but this is a drop in replacement for the discountinued BMA020
1068 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = Y; imu.accADC[PITCH] = -X; imu.accADC[YAW] = Z;}
1069 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = X; imu.gyroADC[PITCH] = Y; imu.gyroADC[YAW] = -Z;}
1070 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = -Y; imu.magADC[PITCH] = -X; imu.magADC[YAW] = Z;}
1078 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
1079 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
1080 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = -Z;}
1083 #if defined(SIRIUSGPS)
1088 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
1089 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
1090 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = -X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = Z;}
1093 #if defined(SIRIUS600)
1098 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
1099 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = -Z;}
1102 #if defined(SIRIUS_AIR)
1105 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = X; imu.accADC[PITCH] = Y; imu.accADC[YAW] = Z;}
1106 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = -Y; imu.gyroADC[PITCH] = X; imu.gyroADC[YAW] = -Z;}
1107 #undef INTERNAL_I2C_PULLUPS
1111 #if defined(SIRIUS_AIR_GPS)
1115 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = X; imu.accADC[PITCH] = Y; imu.accADC[YAW] = Z;}
1116 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = -Y; imu.gyroADC[PITCH] = X; imu.gyroADC[YAW] = -Z;}
1117 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = -X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = Z;} //normal Sirius MAG on top is X Y -Z
1118 #undef INTERNAL_I2C_PULLUPS
1122 #if defined(SIRIUS_MEGAv5_OSD)
1127 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
1128 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = -X; imu.gyroADC[PITCH] = -Y; imu.gyroADC[YAW] = -Z;}
1129 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = Y; imu.magADC[PITCH] = -X; imu.magADC[YAW] = -Z;}
1130 #undef INTERNAL_I2C_PULLUPS
1133 #if defined(MINIWII)
1136 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
1137 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
1140 #if defined(CITRUSv2_1)
1145 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
1146 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
1147 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = -Z;}
1148 #undef INTERNAL_I2C_PULLUPS
1151 #if defined(CHERRY6DOFv1_0)
1153 #define ACC_ORIENTATION(Y, X, Z) {imu.accADC[ROLL] = -Y; imu.accADC[PITCH] = -X; imu.accADC[YAW] = Z;}
1154 #define GYRO_ORIENTATION(Y, X, Z) {imu.gyroADC[ROLL] = X; imu.gyroADC[PITCH] = -Y; imu.gyroADC[YAW] = -Z;}
1155 #undef INTERNAL_I2C_PULLUPS
1158 #if defined(DROTEK_10DOF) || defined(DROTEK_10DOF_MS)
1162 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
1163 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
1164 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = -Z;}
1165 #define GYRO_ADDRESS 0X69
1166 #if defined(DROTEK_10DOF_MS)
1168 #elif defined(DROTEK_10DOF)
1173 #if defined(DROTEK_6DOFv2)
1176 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -Y; imu.accADC[PITCH] = X; imu.accADC[YAW] = Z;}
1177 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = -X; imu.gyroADC[PITCH] = -Y; imu.gyroADC[YAW] = -Z;}
1178 #define GYRO_ADDRESS 0X69
1181 #if defined(DROTEK_6DOF_MPU)
1183 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -Y; imu.accADC[PITCH] = X; imu.accADC[YAW] = Z;}
1184 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = -X; imu.gyroADC[PITCH] = -Y; imu.gyroADC[YAW] = -Z;}
1185 #define MPU6050_ADDRESS 0x69
1186 #undef INTERNAL_I2C_PULLUPS
1189 #if defined(DROTEK_10DOF_MPU)
1193 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = Y; imu.accADC[PITCH] = -X; imu.accADC[YAW] = Z;}
1194 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = X; imu.gyroADC[PITCH] = Y; imu.gyroADC[YAW] = -Z;}
1195 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = -Y; imu.magADC[PITCH] = X; imu.magADC[YAW] = -Z;}
1196 #define MPU6050_ADDRESS 0X69
1197 #define MPU6050_I2C_AUX_MASTER // MAG connected to the AUX I2C bus of MPU6050
1198 #undef INTERNAL_I2C_PULLUPS
1201 #if defined(FLYDUINO_MPU)
1203 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = X; imu.accADC[PITCH] = Y; imu.accADC[YAW] = Z;}
1204 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = -Y; imu.gyroADC[PITCH] = X; imu.gyroADC[YAW] = -Z;}
1207 #if defined(MONGOOSE1_0)
1212 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = -Y; imu.gyroADC[PITCH] = X; imu.gyroADC[YAW] = -Z;}
1213 #define ACC_ORIENTATION(Y, X, Z) {imu.accADC[ROLL] = Y; imu.accADC[PITCH] = X; imu.accADC[YAW] = Z;}
1214 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = -X; imu.magADC[PITCH] = -Y; imu.magADC[YAW] = -Z;}
1215 #define ADXL345_ADDRESS 0x53
1216 #undef INTERNAL_I2C_PULLUPS
1219 #if defined(CRIUS_LITE)
1222 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
1223 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
1226 #if defined(CRIUS_SE)
1231 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
1232 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
1233 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = -Z;}
1236 #if defined(CRIUS_SE_v2_0)
1240 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
1241 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
1242 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = -Z;}
1245 #if defined(BOARD_PROTO_1)
1249 #define ACC_ORIENTATION(Y, X, Z) {imu.accADC[ROLL] = -Y; imu.accADC[PITCH] = -X; imu.accADC[YAW] = Z;}
1250 #define GYRO_ORIENTATION(Y, X, Z) {imu.gyroADC[ROLL] = X; imu.gyroADC[PITCH] = -Y; imu.gyroADC[YAW] = -Z;}
1251 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = -Z;}
1252 #define MS561101BA_ADDRESS 0x76
1253 #define STABLEPIN_PINMODE pinMode (A2, OUTPUT);
1254 #define STABLEPIN_ON PORTC |= (1<<2);
1255 #define STABLEPIN_OFF PORTC &= ~(1<<2);
1258 #if defined(BOARD_PROTO_2)
1262 #define ACC_ORIENTATION(Y, X, Z) {imu.accADC[ROLL] = -Y; imu.accADC[PITCH] = -X; imu.accADC[YAW] = Z;}
1263 #define GYRO_ORIENTATION(Y, X, Z) {imu.gyroADC[ROLL] = X; imu.gyroADC[PITCH] = -Y; imu.gyroADC[YAW] = -Z;}
1264 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = Z;}
1265 #define MPU6050_I2C_AUX_MASTER
1266 #define MS561101BA_ADDRESS 0x76
1267 #define STABLEPIN_PINMODE pinMode (A2, OUTPUT);
1268 #define STABLEPIN_ON PORTC |= (1<<2);
1269 #define STABLEPIN_OFF PORTC &= ~(1<<2);
1277 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
1278 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
1279 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = -Z;}
1280 #undef INTERNAL_I2C_PULLUPS
1281 #define ADXL345_ADDRESS 0x53
1288 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
1289 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
1290 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = -Z;}
1291 #undef INTERNAL_I2C_PULLUPS
1292 #define ADXL345_ADDRESS 0x53
1299 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
1300 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
1301 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = -Z;}
1302 #define MPU6050_I2C_AUX_MASTER // MAG connected to the AUX I2C bus of MPU6050
1303 #undef INTERNAL_I2C_PULLUPS
1310 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
1311 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
1312 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = -Z;}
1313 #define MPU6050_I2C_AUX_MASTER // MAG connected to the AUX I2C bus of MPU6050
1314 #undef INTERNAL_I2C_PULLUPS
1319 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
1320 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
1321 #undef INTERNAL_I2C_PULLUPS
1324 #if defined(INNOVWORKS_10DOF)
1329 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
1330 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
1331 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = X; imu.magADC[PITCH] = Y; imu.imu.[YAW] = -Z;}
1332 #undef INTERNAL_I2C_PULLUPS
1335 #if defined(INNOVWORKS_6DOF)
1338 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
1339 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
1340 #undef INTERNAL_I2C_PULLUPS
1343 #if defined(PROTO_DIY)
1348 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = X; imu.accADC[PITCH] = Y; imu.accADC[YAW] = Z;}
1349 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = X; imu.gyroADC[PITCH] = Y; imu.gyroADC[YAW] = -Z;}
1350 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = -Z;}
1351 #undef INTERNAL_I2C_PULLUPS
1352 #define STABLEPIN_ON PORTC &= ~(1<<6);
1353 #define STABLEPIN_OFF PORTC |= 1<<6;
1356 #if defined(IOI_MINI_MULTIWII)
1361 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
1362 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
1363 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = -Y; imu.magADC[PITCH] = X; imu.magADC[YAW] = -Z;}
1366 #if defined(Bobs_6DOF_V1)
1369 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
1370 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
1371 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = Y; imu.magADC[PITCH] = -X; imu.magADC[YAW] = -Z;}
1372 #undef INTERNAL_I2C_PULLUPS
1375 #if defined(Bobs_9DOF_V1)
1379 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
1380 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
1381 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = Y; imu.magADC[PITCH] = -X; imu.magADC[YAW] = -Z;}
1382 #undef INTERNAL_I2C_PULLUPS
1385 #if defined(Bobs_10DOF_BMP_V1)
1388 #define BMP085 // Bobs 10DOF uses the BMP180 - BMP085 and BMP180 are software compatible
1390 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
1391 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
1392 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = Y; imu.magADC[PITCH] = -X; imu.magADC[YAW] = -Z;}
1393 #undef INTERNAL_IC2_PULLUPS
1396 #if defined(HK_MultiWii_SE_V2 )
1400 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
1401 #define GYRO_ORIENTATION(X, Y, Z){imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
1402 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = -Z;}
1403 #define MPU6050_EN_I2C_BYPASS // MAG connected to the AUX I2C bus of MPU6050
1404 #undef INTERNAL_I2C_PULLUPS
1407 #if defined(HK_MultiWii_328P )
1412 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
1413 #define GYRO_ORIENTATION(X, Y, Z){imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
1414 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = -Z;}
1415 #undef INTERNAL_I2C_PULLUPS
1418 #if defined(CRIUS_AIO_PRO)
1422 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
1423 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
1424 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = -Z;}
1425 #define MPU6050_I2C_AUX_MASTER // MAG connected to the AUX I2C bus of MPU6050
1426 #undef INTERNAL_I2C_PULLUPS
1427 #define I2C_SPEED 400000L //400kHz fast mode
1430 #define SERVO_1_PINMODE pinMode(44,OUTPUT); // TILT_PITCH
1431 #define SERVO_1_PIN_HIGH PORTL |= 1<<5;
1432 #define SERVO_1_PIN_LOW PORTL &= ~(1<<5);
1433 #define SERVO_2_PINMODE pinMode(45,OUTPUT); // TILT_ROLL
1434 #define SERVO_2_PIN_HIGH PORTL |= 1<<4;
1435 #define SERVO_2_PIN_LOW PORTL &= ~(1<<4);
1436 #define SERVO_3_PINMODE pinMode(46,OUTPUT); // CAM TRIG
1437 #define SERVO_3_PIN_HIGH PORTL |= 1<<3;
1438 #define SERVO_3_PIN_LOW PORTL &= ~(1<<3);
1441 #if defined(LADYBIRD)
1443 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
1444 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
1445 #undef INTERNAL_I2C_PULLUPS
1446 #define MINTHROTTLE 1050
1447 #define MAXTHROTTLE 2000
1448 #define EXT_MOTOR_32KHZ
1450 #define VBATSCALE 54
1451 #define VBATLEVEL_WARN1 10
1452 #define VBATLEVEL_WARN2 10
1453 #define VBATLEVEL_CRIT 10
1458 #if defined(MEGAWAP_V2_STD)
1463 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
1464 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
1465 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = -Z;}
1468 #if defined(MEGAWAP_V2_ADV)
1472 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
1473 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
1474 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = -Z;}
1475 #define MPU6050_EN_I2C_BYPASS // MAG connected to the AUX I2C bus of MPU6050
1476 #undef INTERNAL_I2C_PULLUPS
1479 #if defined(RCNet_FC_GPS)
1482 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = -X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = Z;}
1483 #define MPU6050_I2C_AUX_MASTER // MAG connected to the AUX I2C bus of MPU6050
1484 #undef INTERNAL_I2C_PULLUPS
1485 #define GPS_SERIAL 2
1486 #define GPS_BAUD 115200
1490 #if defined(RCNet_FC)
1493 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
1494 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
1495 #undef INTERNAL_I2C_PULLUPS
1497 #define SERVO_1_PINMODE pinMode(40,OUTPUT); // TILT_PITCH
1498 #define SERVO_1_PIN_HIGH PORTL |= 1<<5;
1499 #define SERVO_1_PIN_LOW PORTL &= ~(1<<5);
1500 #define SERVO_2_PINMODE pinMode(39,OUTPUT); // TILT_ROLL
1501 #define SERVO_2_PIN_HIGH PORTL |= 1<<4;
1502 #define SERVO_2_PIN_LOW PORTL &= ~(1<<4);
1503 #define SERVO_3_PINMODE pinMode(38,OUTPUT); // CAM TRIG
1504 #define SERVO_3_PIN_HIGH PORTL |= 1<<3;
1505 #define SERVO_3_PIN_LOW PORTL &= ~(1<<3);
1508 #if defined(FLYDU_ULTRA)
1514 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = X; imu.accADC[PITCH] = Y; imu.accADC[YAW] = Z;}
1515 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
1516 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = -Y; imu.magADC[PITCH] = X; imu.magADC[YAW] = Z;}
1518 #define GPS_SERIAL 2
1519 #define GPS_BAUD 57600
1520 #define MTK_BINARY19
1521 #define INIT_MTK_GPS
1524 #if defined(MultiWii_32U4_SE)
1527 #define MPU6050_I2C_AUX_MASTER // MAG connected to the AUX I2C bus of MPU6050
1529 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
1530 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
1531 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = -Z;}
1532 #undef INTERNAL_I2C_PULLUPS
1535 #if defined(MultiWii_32U4_SE_no_baro)
1538 #define MPU6050_I2C_AUX_MASTER // MAG connected to the AUX I2C bus of MPU6050
1539 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
1540 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
1541 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = -Z;}
1542 #undef INTERNAL_I2C_PULLUPS
1545 #if defined(Flyduino9DOF)
1548 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
1549 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
1550 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = -Z;}
1551 #define MPU6050_EN_I2C_BYPASS // MAG connected to the AUX I2C bus of MPU6050
1552 #undef INTERNAL_I2C_PULLUPS
1555 #if defined(Nano_Plane)
1557 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
1558 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
1559 #undef INTERNAL_I2C_PULLUPS
1562 #if defined(OPENLRSv2MULTI)
1565 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
1566 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
1567 #define ADXL345_ADDRESS 0x53
1574 #define IRQ_interrupt 0
1576 #define nIRQ_1 (PIND & 0x04)==0x04 //D2
1577 #define nIRQ_0 (PIND & 0x04)==0x00 //D2
1579 #define nSEL_on PORTD |= 0x10 //D4
1580 #define nSEL_off PORTD &= 0xEF //D4
1582 #define SCK_on PORTC |= 0x04 //C2
1583 #define SCK_off PORTC &= 0xFB //C2
1585 #define SDI_on PORTC |= 0x02 //C1
1586 #define SDI_off PORTC &= 0xFD //C1
1588 #define SDO_1 (PINC & 0x01) == 0x01 //C0
1589 #define SDO_0 (PINC & 0x01) == 0x00 //C0
1592 #define GREEN_LED_pin 13
1593 #define RED_LED_pin A3
1595 #define Red_LED_ON PORTC |= _BV(3);
1596 #define Red_LED_OFF PORTC &= ~_BV(3);
1598 #define Green_LED_ON PORTB |= _BV(5);
1599 #define Green_LED_OFF PORTB &= ~_BV(5);
1601 #define NOP() __asm__ __volatile__("nop")
1603 #define RF22B_PWRSTATE_READY 01
1604 #define RF22B_PWRSTATE_TX 0x09
1605 #define RF22B_PWRSTATE_RX 05
1606 #define RF22B_Rx_packet_received_interrupt 0x02
1607 #define RF22B_PACKET_SENT_INTERRUPT 04
1608 #define RF22B_PWRSTATE_POWERDOWN 00
1612 #if defined(DESQUARED6DOFV2GO)
1614 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
1615 #undef INTERNAL_I2C_PULLUPS
1618 #if defined(DESQUARED6DOFV4)
1620 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
1621 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
1622 #undef INTERNAL_I2C_PULLUPS
1625 #if defined(OSEPPGYRO)
1627 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
1628 #undef INTERNAL_I2C_PULLUPS
1631 #if defined(DIYFLYING_MAGE_V1)
1632 #define MPU6050 // gyro+acc
1633 #define BMP085 // baro
1634 #define HMC5883 // mag
1635 #define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = -X; imu.accADC[PITCH] = -Y; imu.accADC[YAW] = Z;}
1636 #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
1637 #define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = -Z;}
1638 #undef INTERNAL_I2C_PULLUPS
1645 #if defined(ADXL345) || defined(BMA020) || defined(BMA180) || defined(BMA280) || defined(MMA7455) || defined(ADCACC) || defined(LIS3LV02) || defined(LSM303DLx_ACC) || defined(MPU6050) || defined(LSM330) || defined(LSM9DS0) || defined(MMA8451Q)
1651 #if defined(HMC5883) || defined(HMC5843) || defined(AK8975) || defined(MAG3110) || defined(LSM9DS0)
1657 #if defined(ITG3200) || defined(ITG3050) || defined(L3G4200D) || defined(MPU6050) || defined(LSM330) || defined(LSM9DS0) || defined(MPU3050) || defined(WMP)
1663 #if defined(BMP085) || defined(BME280) || defined(MS561101BA)
1669 #if defined(GPS_SERIAL) || defined(I2C_GPS)
1675 #if defined(USE_MSP_WP)
1681 #if defined(SRF02) || defined(SRF08) || defined(SRF10) || defined(SRC235) || defined(I2C_GPS_SONAR)
1687 #if defined(EXTENDED_AUX_STATES)
1693 #if defined(RX_RSSI_CHAN)
1702 #elif defined(QUADP)
1704 #elif defined(QUADX)
1708 #define SERVO_RATES {30,30,100,100,0,1,100,100}
1709 #elif defined(GIMBAL)
1715 #elif defined(FLYING_WING)
1717 #define SERVO_RATES {30,30,100,0,1,100,100,100}
1720 #elif defined(HEX6X)
1721 #define MULTITYPE 10
1722 #elif defined(OCTOX8)
1723 #define MULTITYPE 11 //the JAVA GUI is the same for all 8 motor configs
1724 #elif defined(OCTOFLATP)
1725 #define MULTITYPE 12 //12 for MultiWinGui
1726 #elif defined(OCTOFLATX)
1727 #define MULTITYPE 13 //13 for MultiWinGui
1728 #elif defined(AIRPLANE)
1729 #define MULTITYPE 14
1730 #define SERVO_RATES {30,30,100,100,-100,100,100,100}
1731 #elif defined (HELI_120_CCPM)
1732 #define MULTITYPE 15
1733 #elif defined (HELI_90_DEG)
1734 #define MULTITYPE 16
1735 #define SERVO_RATES {30,30,100,-100,-100,100,100,100}
1736 #elif defined(VTAIL4)
1737 #define MULTITYPE 17
1738 #elif defined(HEX6H)
1739 #define MULTITYPE 18
1740 #elif defined(SINGLECOPTER)
1741 #define MULTITYPE 21
1742 #define SERVO_RATES {30,30,100,0,1,0,1,100}
1743 #elif defined(DUALCOPTER)
1744 #define MULTITYPE 20
1751 #if defined (AIRPLANE) || defined(HELICOPTER)|| defined(SINGLECOPTER)|| defined(DUALCOPTER) && defined(PROMINI)
1752 #if defined(D12_POWER)
1753 #define SERVO_4_PINMODE ; // D12
1754 #define SERVO_4_PIN_HIGH ;
1755 #define SERVO_4_PIN_LOW ;
1757 #undef POWERPIN_PINMODE
1760 #define POWERPIN_PINMODE ;
1761 #define POWERPIN_ON ;
1762 #define POWERPIN_OFF ;
1766 #if defined(POWERMETER_HARD) || defined(POWERMETER_SOFT)
1768 #define PLEVELSCALE 50 // step size you can use to set alarm
1769 #define PLEVELDIVSOFT 100000
1770 #define PLEVELDIV 36000
1773 #if defined PILOTLAMP
1774 #define PL_CHANNEL OCR0B //use B since A can be used by camstab
1775 #define PL_ISR TIMER0_COMPB_vect
1776 #define PL_INIT TCCR0A=0;TIMSK0|=(1<<OCIE0B);PL_CHANNEL=PL_IDLE;PilotLamp(PL_GRN_OFF);PilotLamp(PL_BLU_OFF);PilotLamp(PL_RED_OFF);PilotLamp(PL_BZR_OFF);
1777 #define BUZZERPIN_ON PilotLamp(PL_BZR_ON);
1778 #define BUZZERPIN_OFF PilotLamp(PL_BZR_OFF);
1779 #define PL_GRN_ON 25 // 100us
1780 #define PL_GRN_OFF 50 // 200us
1781 #define PL_BLU_ON 75 // 300us
1782 #define PL_BLU_OFF 100 // 400us
1783 #define PL_RED_ON 125 // 500us
1784 #define PL_RED_OFF 150 // 600us
1785 #define PL_BZR_ON 175 // 700us
1786 #define PL_BZR_OFF 200 // 800us
1787 #define PL_IDLE 125 // 100us
1790 #if defined(PILOTLAMP)
1796 #if !defined(SERIAL_SUM_PPM) && !defined(SPEKTRUM) && !defined(SBUS) && !defined(SUMD)
1800 #if defined(SPEKTRUM) || defined(SBUS) || defined(SUMD)
1805 #define BIND_CAPABLE 0 //Used for Spektrum today; can be used in the future for any RX type that needs a bind and has a MultiWii module.
1806 #if defined(SPEKTRUM)
1807 #define SPEK_FRAME_SIZE 16
1808 #if (SPEKTRUM == 1024)
1809 #define SPEK_CHAN_SHIFT 2 // Assumes 10 bit frames, that is 1024 mode.
1810 #define SPEK_CHAN_MASK 0x03 // Assumes 10 bit frames, that is 1024 mode.
1811 #define SPEK_DATA_SHIFT // Assumes 10 bit frames, that is 1024 mode.
1812 #define SPEK_BIND_PULSES 3
1814 #if (SPEKTRUM == 2048)
1815 #define SPEK_CHAN_SHIFT 3 // Assumes 11 bit frames, that is 2048 mode.
1816 #define SPEK_CHAN_MASK 0x07 // Assumes 11 bit frames, that is 2048 mode.
1817 #define SPEK_DATA_SHIFT >> 1 // Assumes 11 bit frames, that is 2048 mode.
1818 #define SPEK_BIND_PULSES 5
1820 #if defined(SPEK_BIND)
1821 #define BIND_CAPABLE 1
1822 #if !defined(SPEK_BIND_GROUND)
1823 #define SPEK_BIND_GROUND 4
1825 #if !defined(SPEK_BIND_POWER)
1826 #define SPEK_BIND_POWER 5
1828 #if !defined(SPEK_BIND_DATA)
1829 #define SPEK_BIND_DATA 6
1836 #elif defined(SPEKTRUM) || defined(SERIAL_SUM_PPM)
1842 #if !(defined(DISPLAY_2LINES)) && !(defined(DISPLAY_MULTILINE))
1843 #if (defined(LCD_VT100)) || (defined(OLED_I2C_128x64) || defined(OLED_DIGOLE) )
1844 #define DISPLAY_MULTILINE
1846 #define DISPLAY_2LINES
1850 #if (defined(LCD_VT100))
1851 #if !(defined(MULTILINE_PRE))
1852 #define MULTILINE_PRE 6
1854 #if !(defined(MULTILINE_POST))
1855 #define MULTILINE_POST 9
1857 #if !(defined(DISPLAY_COLUMNS))
1858 #define DISPLAY_COLUMNS 40
1860 #elif (defined(OLED_I2C_128x64) && defined(DISPLAY_FONT_DSIZE))
1861 #if !(defined(MULTILINE_PRE))
1862 #define MULTILINE_PRE 1
1864 #if !(defined(MULTILINE_POST))
1865 #define MULTILINE_POST 3
1867 #if !(defined(DISPLAY_COLUMNS))
1868 #define DISPLAY_COLUMNS 21
1870 #elif (defined(OLED_I2C_128x64))
1871 #if !(defined(MULTILINE_PRE))
1872 #define MULTILINE_PRE 3
1874 #if !(defined(MULTILINE_POST))
1875 #define MULTILINE_POST 5
1877 #if !(defined(DISPLAY_COLUMNS))
1878 #define DISPLAY_COLUMNS 21
1880 #elif (defined(OLED_DIGOLE) && defined(DISPLAY_FONT_DSIZE))
1881 #if !(defined(MULTILINE_PRE))
1882 #define MULTILINE_PRE 2
1884 #if !(defined(MULTILINE_POST))
1885 #define MULTILINE_POST 3
1887 #elif (defined(OLED_DIGOLE))
1888 #if !(defined(MULTILINE_PRE))
1889 #define MULTILINE_PRE 3
1891 #if !(defined(MULTILINE_POST))
1892 #define MULTILINE_POST 4
1894 #if !(defined(DISPLAY_COLUMNS))
1895 #define DISPLAY_COLUMNS 21
1899 #if !(defined(DISPLAY_COLUMNS))
1900 #define DISPLAY_COLUMNS 16
1909 #ifdef OVERRIDE_V_BATPIN
1911 #define V_BATPIN OVERRIDE_V_BATPIN
1913 #ifdef OVERRIDE_PSENSORPIN
1915 #define PSENSORPIN OVERRIDE_PSENSORPIN
1917 #ifdef OVERRIDE_LEDPIN_PINMODE
1918 #undef LEDPIN_PINMODE
1919 #undef LEDPIN_TOGGLE
1922 #define LEDPIN_PINMODE OVERRIDE_LEDPIN_PINMODE
1923 #define LEDPIN_TOGGLE OVERRIDE_LEDPIN_TOGGLE
1924 #define LEDPIN_OFF OVERRIDE_LEDPIN_OFF
1925 #define LEDPIN_ON OVERRIDE_LEDPIN_ON
1927 #ifdef OVERRIDE_BUZZERPIN_PINMODE
1928 #undef BUZZERPIN_PINMODE
1930 #undef BUZZERPIN_OFF
1931 #define BUZZERPIN_PINMODE OVERRIDE_BUZZERPIN_PINMODE
1932 #define BUZZERPIN_ON OVERRIDE_BUZZERPIN_ON
1933 #define BUZZERPIN_OFF OVERRIDE_BUZZERPIN_OFF
1937 #ifdef FORCE_GYRO_ORIENTATION
1938 #undef GYRO_ORIENTATION
1939 #define GYRO_ORIENTATION FORCE_GYRO_ORIENTATION
1941 #ifdef FORCE_ACC_ORIENTATION
1942 #undef ACC_ORIENTATION
1943 #define ACC_ORIENTATION FORCE_ACC_ORIENTATION
1945 #ifdef FORCE_MAG_ORIENTATION
1946 #undef MAG_ORIENTATION
1947 #define MAG_ORIENTATION FORCE_MAG_ORIENTATION
1951 #ifdef FORCE_SERVO_RATES
1953 #define SERVO_RATES FORCE_SERVO_RATES
1959 #ifndef NUMBER_MOTOR
1960 #error "NUMBER_MOTOR is not set, most likely you have not defined any type of multicopter"
1963 #if (defined(LCD_DUMMY) || defined(LCD_SERIAL3W) || defined(LCD_TEXTSTAR) || defined(LCD_VT100) || defined(LCD_TTY) || defined(LCD_ETPP) || defined(LCD_LCD03) || defined(LCD_LCD03S) || defined(OLED_I2C_128x64) ) || defined(OLED_DIGOLE)
1967 #if (defined(LCD_CONF) || defined(LCD_TELEMETRY)) && !(defined(HAS_LCD) )
1968 #error "LCD_CONF or LCD_TELEMETRY defined, and choice of LCD not defined. Uncomment one of LCD_SERIAL3W, LCD_TEXTSTAR, LCD_VT100, LCD_TTY or LCD_ETPP, LCD_LCD03, LCD_LCD03S, OLED_I2C_128x64, OLED_DIGOLE"
1971 #if defined(POWERMETER_SOFT) && !(defined(VBAT))
1972 #error "to use powermeter, you must also define and configure VBAT"
1975 #if defined(WATTS) && !(defined(POWERMETER_HARD)) && !(defined(VBAT))
1976 #error "to compute WATTS, you must also define and configure both POWERMETER_HARD and VBAT"
1979 #if defined(LCD_TELEMETRY_AUTO) && !(defined(LCD_TELEMETRY))
1980 #error "to use automatic telemetry, you MUST also define and configure LCD_TELEMETRY"
1983 #if defined(LCD_TELEMETRY_STEP) && !(defined(LCD_TELEMETRY))
1984 #error "to use single step telemetry, you MUST also define and configure LCD_TELEMETRY"
1987 #if defined(A32U4_4_HW_PWM_SERVOS) && !(defined(HELI_120_CCPM))
1988 #error "for your protection: A32U4_4_HW_PWM_SERVOS was not tested with your coptertype"
1991 #if GPS && !defined(NMEA) && !defined(UBLOX) && !defined(MTK_BINARY16) && !defined(MTK_BINARY19) && !defined(INIT_MTK_GPS) && !defined(I2C_GPS)
1992 #error "when using GPS you must specify the protocol NMEA, UBLOX..."
1995 #if defined(NUNCHUK) || \
1996 defined( MPU6050_LPF_256HZ) || defined(MPU6050_LPF_188HZ) || defined( MPU6050_LPF_98HZ) || defined( MPU6050_LPF_42HZ) || \
1997 defined( MPU6050_LPF_20HZ) || defined( MPU6050_LPF_10HZ) || defined( MPU6050_LPF_5HZ) || \
1998 defined( ITG3200_LPF_256HZ) || defined( ITG3200_LPF_188HZ) || defined( ITG3200_LPF_98HZ) || defined( ITG3200_LPF_42HZ) || \
1999 defined( ITG3200_LPF_20HZ) || defined( ITG3200_LPF_10HZ)
2000 #error "you use one feature that is no longer supported or has undergone a name change"