forked from AeroQuad/AeroQuad
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathAeroQuad.pde
804 lines (724 loc) · 27.8 KB
/
AeroQuad.pde
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
/*
AeroQuad v2.5 Beta 1 - July 2011
www.AeroQuad.com
Copyright (c) 2011 Ted Carancho. All rights reserved.
An Open Source Arduino based multicopter.
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/****************************************************************************
Before flight, select the different user options for your AeroQuad below
If you need additional assitance go to http://AeroQuad.com/forum
*****************************************************************************/
/****************************************************************************
************************* Hardware Configuration ***************************
****************************************************************************/
// Select which hardware you wish to use with the AeroQuad Flight Software
//#define DEBUG_LOOP
//#define AeroQuad_v1 // Arduino 2009 with AeroQuad Shield v1.7 and below
//#define AeroQuad_v1_IDG // Arduino 2009 with AeroQuad Shield v1.7 and below using IDG yaw gyro
//#define AeroQuad_v18 // Arduino 2009 with AeroQuad Shield v1.8 or greater
//#define AeroQuad_Mini // Arduino Pro Mini with AeroQuad Mini Shield v1.0
//#define AeroQuad_Wii // Arduino 2009 with Wii Sensors and AeroQuad Shield v1.x
//#define AeroQuad_Paris_v3 // Define along with either AeroQuad_Wii to include specific changes for MultiWiiCopter Paris v3.0 board
//#define AeroQuadMega_v1 // Arduino Mega with AeroQuad Shield v1.7 and below
#define AeroQuadMega_v2 // Arduino Mega with AeroQuad Shield v2.x
//#define AeroQuadMega_Wii // Arduino Mega with Wii Sensors and AeroQuad Shield v2.x
//#define ArduCopter // ArduPilot Mega (APM) with APM Sensor Board
//#define AeroQuadMega_CHR6DM // Clean Arduino Mega with CHR6DM as IMU/heading ref.
//#define APM_OP_CHR6DM // ArduPilot Mega with CHR6DM as IMU/heading ref., Oilpan for barometer (just uncomment AltitudeHold for baro), and voltage divider
/****************************************************************************
*********************** Define Flight Configuration ************************
****************************************************************************/
// Use only one of the following definitions
#define XConfig
//#define plusConfig
//#define HEXACOAXIAL
//#define HEXARADIAL
// *******************************************************************************************************************************
// Optional Sensors
// Warning: If you enable HeadingHold or AltitudeHold and do not have the correct sensors connected, the flight software may hang
// *******************************************************************************************************************************
#define HeadingMagHold // Enables HMC5843 Magnetometer, gets automatically selected if CHR6DM is defined
#define AltitudeHold // Enables BMP085 Barometer (experimental, use at your own risk)
#define BattMonitor //define your personal specs in BatteryMonitor.h! Full documentation with schematic there
//#define RateModeOnly // Use this if you only have a gyro sensor, this will disable any attitude modes.
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// You must define *only* one of the following 2 flightAngle calculations
// If you only want DCM, then don't define either of the below
// Use FlightAngleARG if you do not have a magnetometer, use DCM if you have a magnetometer installed
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
//#define FlightAngleMARG // Experimental! Fly at your own risk! Use this if you have a magnetometer installed and enabled HeadingMagHold above
//#define FlightAngleARG // Use this if you do not have a magnetometer installed
//#define WirelessTelemetry // Enables Wireless telemetry on Serial3 // Wireless telemetry enable
//#define BinaryWrite // Enables fast binary transfer of flight data to Configurator
//#define BinaryWritePID // Enables fast binary transfer of attitude PID data
//#define OpenlogBinaryWrite // Enables fast binary transfer to serial1 and openlog hardware
// *******************************************************************************************************************************
// Define how many channels that are connected from your R/C receiver
// Please note that the flight software currently only supports 6 channels, additional channels will be supported in the future
// Additionally 8 receiver channels are only available when not using the Arduino Uno
// *******************************************************************************************************************************
#define LASTCHANNEL 6
//#define LASTCHANNEL 8
// *******************************************************************************************************************************
// Camera Stabilization
// Servo output goes to D11(pitch), D12(roll), D13(yaw) on AeroQuad v1.8 shield
// If using v2.0 Shield place jumper between:
// D12 to D33 for roll, connect servo to SERVO1
// D11 to D34 for pitch, connect servo to SERVO2
// D13 to D35 for yaw, connect servo to SERVO3
// Please note that you will need to have battery connected to power on servos with v2.0 shield
// *******************************************************************************************************************************
//#define CameraControl
// *******************************************************************************************************************************
// On screen display implementation using MAX7456 chip. See OSD.h for more info and configuration.
// *******************************************************************************************************************************
//#define MAX7456_OSD
/****************************************************************************
********************* End of User Definition Section ***********************
****************************************************************************/
// Checks to make sure we have the right combinations defined
#if defined(FlightAngleMARG) && !defined(HeadingMagHold)
#undef FlightAngleMARG
#endif
#if defined(HeadingMagHold) && defined(FlightAngleMARG) && defined(FlightAngleARG)
#undef FlightAngleARG
#endif
#if defined(MAX7456_OSD) && !defined(AeroQuadMega_v2) && !defined(AeroQuadMega_Wii) && !defined(AeroQuadMega_CHR6DM)
#undef MAX7456_OSD
#endif
#include <EEPROM.h>
#include <Wire.h>
#include "AeroQuad.h"
#include "I2C.h"
#include "PID.h"
#include "AQMath.h"
#include "Receiver.h"
#include "DataAcquisition.h"
#include "Accel.h"
#include "Gyro.h"
#include "Motors.h"
// Create objects defined from Configuration Section above
#ifdef AeroQuad_v1
Accel_AeroQuad_v1 accel;
Gyro_AeroQuad_v1 gyro;
Receiver_AeroQuad receiver;
Motors_PWM motors;
#include "FlightAngle.h"
#ifdef FlightAngleARG
FlightAngle_ARG tempFlightAngle;
#elif defined FlightAngleMARG
FlightAngle_MARG tempFlightAngle;
#else
FlightAngle_DCM tempFlightAngle;
#endif
FlightAngle *flightAngle = &tempFlightAngle;
#ifdef CameraControl
#include "Camera.h"
Camera_AeroQuad camera;
#endif
#endif
#ifdef AeroQuad_v1_IDG
Accel_AeroQuad_v1 accel;
Gyro_AeroQuad_v1 gyro;
Receiver_AeroQuad receiver;
Motors_PWM motors;
#include "FlightAngle.h"
#ifdef FlightAngleARG
FlightAngle_ARG tempFlightAngle;
#elif defined FlightAngleMARG
FlightAngle_MARG tempFlightAngle;
#else
FlightAngle_DCM tempFlightAngle;
#endif
FlightAngle *flightAngle = &tempFlightAngle;
#ifdef CameraControl
#include "Camera.h"
Camera_AeroQuad camera;
#endif
#endif
#ifdef AeroQuad_v18
Accel_AeroQuadMega_v2 accel;
Gyro_AeroQuadMega_v2 gyro;
Receiver_AeroQuad receiver;
Motors_PWMtimer motors;
//Motors_AeroQuadI2C motors; // Use for I2C based ESC's
#include "FlightAngle.h"
#ifdef FlightAngleARG
FlightAngle_ARG tempFlightAngle;
#elif defined FlightAngleMARG
FlightAngle_MARG tempFlightAngle;
#else
FlightAngle_DCM tempFlightAngle;
#endif
FlightAngle *flightAngle = &tempFlightAngle;
#ifdef HeadingMagHold
#include "Compass.h"
Magnetometer_HMC5843 compass;
#endif
#ifdef AltitudeHold
#include "Altitude.h"
Altitude_AeroQuad_v2 altitude;
#endif
#ifdef BattMonitor
#include "BatteryMonitor.h"
BatteryMonitor_AeroQuad batteryMonitor;
#endif
#ifdef CameraControl
#include "Camera.h"
Camera_AeroQuad camera;
#endif
#endif
#ifdef AeroQuad_Mini
Accel_AeroQuadMini accel;
Gyro_AeroQuadMega_v2 gyro;
Receiver_AeroQuad receiver;
Motors_PWMtimer motors;
//Motors_AeroQuadI2C motors; // Use for I2C based ESC's
#include "FlightAngle.h"
#ifdef FlightAngleARG
FlightAngle_ARG tempFlightAngle;
#elif defined FlightAngleMARG
FlightAngle_MARG tempFlightAngle;
#else
FlightAngle_DCM tempFlightAngle;
#endif
FlightAngle *flightAngle = &tempFlightAngle;
#ifdef BattMonitor
#include "BatteryMonitor.h"
BatteryMonitor_AeroQuad batteryMonitor;
#endif
#ifdef CameraControl
#include "Camera.h"
Camera_AeroQuad camera;
#endif
#endif
#ifdef AeroQuadMega_v1
// Special thanks to Wilafau for fixes for this setup
// http://aeroquad.com/showthread.php?991-AeroQuad-Flight-Software-v2.0&p=11466&viewfull=1#post11466
Receiver_AeroQuadMega receiver;
Accel_AeroQuad_v1 accel;
Gyro_AeroQuad_v1 gyro;
Motors_PWM motors;
#include "FlightAngle.h"
#ifdef FlightAngleARG
FlightAngle_ARG tempFlightAngle;
#elif defined FlightAngleMARG
FlightAngle_MARG tempFlightAngle;
#else
FlightAngle_DCM tempFlightAngle;
#endif
FlightAngle *flightAngle = &tempFlightAngle;
#ifdef CameraControl
#include "Camera.h"
Camera_AeroQuad camera;
#endif
#endif
#ifdef AeroQuadMega_v2
Receiver_AeroQuadMega receiver;
Motors_PWMtimer motors;
//Motors_AeroQuadI2C motors; // Use for I2C based ESC's
Accel_AeroQuadMega_v2 accel;
Gyro_AeroQuadMega_v2 gyro;
#include "FlightAngle.h"
#ifdef FlightAngleARG
FlightAngle_ARG tempFlightAngle;
#elif defined FlightAngleMARG
FlightAngle_MARG tempFlightAngle;
#else
FlightAngle_DCM tempFlightAngle;
#endif
FlightAngle *flightAngle = &tempFlightAngle;
#ifdef HeadingMagHold
#include "Compass.h"
Magnetometer_HMC5843 compass;
#endif
#ifdef AltitudeHold
#include "Altitude.h"
Altitude_AeroQuad_v2 altitude;
#endif
#ifdef BattMonitor
#include "BatteryMonitor.h"
BatteryMonitor_AeroQuad batteryMonitor;
#endif
#ifdef CameraControl
#include "Camera.h"
Camera_AeroQuad camera;
#endif
#ifdef MAX7456_OSD
#include "OSD.h"
OSD osd;
#endif
#endif
#ifdef ArduCopter
Gyro_ArduCopter gyro;
Accel_ArduCopter accel;
Receiver_ArduCopter receiver;
Motors_ArduCopter motors;
#include "FlightAngle.h"
#ifdef FlightAngleARG
FlightAngle_ARG tempFlightAngle;
#elif defined FlightAngleMARG
FlightAngle_MARG tempFlightAngle;
#else
FlightAngle_DCM tempFlightAngle;
#endif
FlightAngle *flightAngle = &tempFlightAngle;
#ifdef HeadingMagHold
#include "Compass.h"
Magnetometer_HMC5843 compass;
#endif
#ifdef AltitudeHold
#include "Altitude.h"
Altitude_AeroQuad_v2 altitude;
#endif
#ifdef BattMonitor
#include "BatteryMonitor.h"
BatteryMonitor_APM batteryMonitor;
#endif
#endif
#ifdef AeroQuad_Wii
Accel_Wii accel;
Gyro_Wii gyro;
Receiver_AeroQuad receiver;
Motors_PWMtimer motors;
#include "FlightAngle.h"
// FlightAngle_CompFilter tempFlightAngle;
#ifdef FlightAngleARG
FlightAngle_ARG tempFlightAngle;
#elif defined FlightAngleMARG
FlightAngle_MARG tempFlightAngle;
#else
FlightAngle_DCM tempFlightAngle;
#endif
FlightAngle *flightAngle = &tempFlightAngle;
#ifdef HeadingMagHold
#include "Compass.h"
Magnetometer_HMC5843 compass;
#endif
#ifdef AltitudeHold
#include "Altitude.h"
Altitude_AeroQuad_v2 altitude;
#endif
#ifdef BattMonitor
#include "BatteryMonitor.h"
BatteryMonitor_AeroQuad batteryMonitor;
#endif
#ifdef CameraControl
#include "Camera.h"
Camera_AeroQuad camera;
#endif
#endif
#ifdef AeroQuadMega_Wii
Accel_Wii accel;
Gyro_Wii gyro;
Receiver_AeroQuadMega receiver;
Motors_PWMtimer motors;
#include "FlightAngle.h"
#ifdef FlightAngleARG
FlightAngle_ARG tempFlightAngle;
#elif defined FlightAngleMARG
FlightAngle_MARG tempFlightAngle;
#else
FlightAngle_DCM tempFlightAngle;
#endif
FlightAngle *flightAngle = &tempFlightAngle;
#ifdef HeadingMagHold
#include "Compass.h"
Magnetometer_HMC5843 compass;
#endif
#ifdef AltitudeHold
#include "Altitude.h"
Altitude_AeroQuad_v2 altitude;
#endif
#ifdef BattMonitor
#include "BatteryMonitor.h"
BatteryMonitor_AeroQuad batteryMonitor;
#endif
#ifdef CameraControl
#include "Camera.h"
Camera_AeroQuad camera;
#endif
#ifdef MAX7456_OSD
#include "OSD.h"
OSD osd;
#endif
#endif
#ifdef AeroQuadMega_CHR6DM
Accel_CHR6DM accel;
Gyro_CHR6DM gyro;
Receiver_AeroQuadMega receiver;
Motors_PWM motors;
#include "FlightAngle.h"
FlightAngle_CHR6DM tempFlightAngle;
FlightAngle *flightAngle = &tempFlightAngle;
#include "Compass.h"
Compass_CHR6DM compass;
#ifdef AltitudeHold
#include "Altitude.h"
Altitude_AeroQuad_v2 altitude;
#endif
#ifdef BattMonitor
#include "BatteryMonitor.h"
BatteryMonitor_APM batteryMonitor;
#endif
#ifdef CameraControl
#include "Camera.h"
Camera_AeroQuad camera;
#endif
#ifdef MAX7456_OSD
#include "OSD.h"
OSD osd;
#endif
#endif
#ifdef APM_OP_CHR6DM
Accel_CHR6DM accel;
Gyro_CHR6DM gyro;
Receiver_ArduCopter receiver;
Motors_ArduCopter motors;
#include "FlightAngle.h"
FlightAngle_CHR6DM tempFlightAngle;
FlightAngle *flightAngle = &tempFlightAngle;
#include "Compass.h"
Compass_CHR6DM compass;
#ifdef AltitudeHold
#include "Altitude.h"
Altitude_AeroQuad_v2 altitude;
#endif
#ifdef BattMonitor
#include "BatteryMonitor.h"
BatteryMonitor_APM batteryMonitor;
#endif
#ifdef CameraControl
#include "Camera.h"
Camera_AeroQuad camera;
#endif
#endif
#ifdef XConfig
void (*processFlightControl)() = &processFlightControlXMode;
#endif
#ifdef plusConfig
void (*processFlightControl)() = &processFlightControlPlusMode;
#endif
// Include this last as it contains objects from above declarations
#include "DataStorage.h"
// ************************************************************
// ********************** Setup AeroQuad **********************
// ************************************************************
void setup() {
SERIAL_BEGIN(BAUD);
pinMode(LEDPIN, OUTPUT);
digitalWrite(LEDPIN, LOW);
#ifdef DEBUG_LOOP
pinMode(12, OUTPUT);
pinMode(11, OUTPUT);
pinMode(10, OUTPUT);
pinMode(9, OUTPUT);
pinMode(8, OUTPUT);
digitalWrite(12, LOW);
digitalWrite(11, LOW);
digitalWrite(10, LOW);
digitalWrite(9, LOW);
digitalWrite(8, LOW);
#endif
#if defined(AeroQuadMega_CHR6DM) || defined(APM_OP_CHR6DM)
Serial1.begin(BAUD);
PORTD = B00000100;
#endif
#if defined(AeroQuad_v18) || defined(AeroQuadMega_v2) || defined(AeroQuad_Mini)
pinMode(LED2PIN, OUTPUT);
digitalWrite(LED2PIN, LOW);
pinMode(LED3PIN, OUTPUT);
digitalWrite(LED3PIN, LOW);
#endif
#ifdef AeroQuadMega_v2
// pins set to INPUT for camera stabilization so won't interfere with new camera class
pinMode(33, INPUT); // disable SERVO 1, jumper D12 for roll
pinMode(34, INPUT); // disable SERVO 2, jumper D11 for pitch
pinMode(35, INPUT); // disable SERVO 3, jumper D13 for yaw
pinMode(43, OUTPUT); // LED 1
pinMode(44, OUTPUT); // LED 2
pinMode(45, OUTPUT); // LED 3
pinMode(46, OUTPUT); // LED 4
digitalWrite(43, HIGH); // LED 1 on
digitalWrite(44, HIGH); // LED 2 on
digitalWrite(45, HIGH); // LED 3 on
digitalWrite(46, HIGH); // LED 4 on
#endif
#if defined(APM_OP_CHR6DM) || defined(ArduCopter)
pinMode(LED_Red, OUTPUT);
pinMode(LED_Yellow, OUTPUT);
pinMode(LED_Green, OUTPUT);
#endif
#ifdef IRdistance
analogReference(EXTERNAL); //use strict 3V3 AREF for SHARP IR sensors
#endif
#if defined(AeroQuad_v18) || defined(AeroQuadMega_v2) || defined(AeroQuad_Mini) || defined(AeroQuad_Wii) || defined(AeroQuadMega_Wii) || defined(AeroQuadMega_CHR6DM) || defined(APM_OP_CHR6DM) || defined(ArduCopter)
Wire.begin();
#endif
#if defined(AeroQuad_v18) || defined(AeroQuadMega_v2) || defined(AeroQuad_Mini)
// Recommendation from Mgros to increase I2C speed to 400kHz
// http://aeroquad.com/showthread.php?991-AeroQuad-Flight-Software-v2.0&p=11262&viewfull=1#post11262
TWBR = 12;
#endif
// Read user values from EEPROM
readEEPROM(); // defined in DataStorage.h
// Configure motors
motors.initialize(); // defined in Motors.h
// Setup receiver pins for pin change interrupts
if (receiverLoop == ON) receiver.initialize(); // defined in Received.h
// Initialize sensors
// If sensors have a common initialization routine
// insert it into the gyro class because it executes first
gyro.initialize(); // defined in Gyro.h
accel.initialize(); // defined in Accel.h
// Calibrate sensors
gyro.autoZero(); // defined in Gyro.h
zeroIntegralError();
// levelAdjust[ROLL] = 0;
// levelAdjust[PITCH] = 0;
// Flight angle estimation
#ifdef HeadingMagHold
compass.initialize();
//setHeading = compass.getHeading();
flightAngle->initialize(compass.getHdgXY(XAXIS), compass.getHdgXY(YAXIS));
#else
flightAngle->initialize(1.0, 0.0); // with no compass, DCM matrix initalizes to a heading of 0 degrees
#endif
// Integral Limit for attitude mode
// This overrides default set in readEEPROM()
// Set for 1/2 max attitude command (+/-0.75 radians)
// Rate integral not used for now
PID[LEVELROLL].windupGuard = 0.375;
PID[LEVELPITCH].windupGuard = 0.375;
// Optional Sensors
#ifdef AltitudeHold
altitude.initialize();
#endif
// Battery Monitor
#ifdef BattMonitor
batteryMonitor.initialize();
#endif
// Camera stabilization setup
#ifdef CameraControl
camera.initialize();
camera.setmCameraRoll(11.11); // Need to figure out nice way to reverse servos
camera.setCenterRoll(1500); // Need to figure out nice way to set center position
camera.setmCameraPitch(11.11);
camera.setCenterPitch(1300);
#endif
//initialising OSD
#if defined(MAX7456_OSD)
osd.initialize();
#endif
#if defined(BinaryWrite) || defined(BinaryWritePID)
#ifdef OpenlogBinaryWrite
binaryPort = &Serial1;
binaryPort->begin(115200);
delay(1000);
#else
binaryPort = &Serial;
#endif
#endif
// AKA use a new low pass filter called a Lag Filter uncomment only if using DCM LAG filters
// setupFilters(accel.accelOneG);
previousTime = micros();
digitalWrite(LEDPIN, HIGH);
safetyCheck = 0;
}
/*******************************************************************
// tasks (microseconds of interval)
ReadGyro readGyro ( 5000); // 200hz
ReadAccel readAccel ( 5000); // 200hz
RunDCM runDCM ( 10000); // 100hz
FlightControls flightControls( 10000); // 100hz
ReadReceiver readReceiver ( 20000); // 50hz
ReadBaro readBaro ( 40000); // 25hz
ReadCompass readCompass ( 100000); // 10Hz
ProcessTelem processTelem ( 100000); // 10Hz
ReadBattery readBattery ( 100000); // 10Hz
Task *tasks[] = {&readGyro, &readAccel, &runDCM, &flightControls, \
&readReceiver, &readBaro, &readCompass, \
&processTelem, &readBattery};
TaskScheduler sched(tasks, NUM_TASKS(tasks));
sched.run();
*******************************************************************/
void loop () {
currentTime = micros();
deltaTime = currentTime - previousTime;
// Main scheduler loop set for 100hz
if (deltaTime >= 10000) {
#ifdef DEBUG_LOOP
testSignal ^= HIGH;
digitalWrite(LEDPIN, testSignal);
#endif
frameCounter++;
// ================================================================
// 100hz task loop
// ================================================================
if (frameCounter % 1 == 0) { // 100 Hz tasks
#ifdef DEBUG_LOOP
digitalWrite(11, HIGH);
#endif
G_Dt = (currentTime - hundredHZpreviousTime) / 1000000.0;
hundredHZpreviousTime = currentTime;
if (sensorLoop == ON) {
// measure critical sensors
gyro.measure();
accel.measure();
// ****************** Calculate Absolute Angle *****************
#if defined HeadingMagHold && defined FlightAngleMARG
flightAngle->calculate(gyro.getData(ROLL), \
gyro.getData(PITCH), \
gyro.getData(YAW), \
accel.getData(XAXIS), \
accel.getData(YAXIS), \
accel.getData(ZAXIS), \
compass.getRawData(XAXIS), \
compass.getRawData(YAXIS), \
compass.getRawData(ZAXIS));
#endif
#if defined HeadingMagHold && defined FlightAngleARG
flightAngle->calculate(gyro.getData(ROLL), \
gyro.getData(PITCH), \
gyro.getData(YAW), \
accel.getData(XAXIS), \
accel.getData(YAXIS), \
accel.getData(ZAXIS), \
0.0, \
0.0, \
0.0);
#endif
#if !defined HeadingMagHold && defined FlightAngleARG
flightAngle->calculate(gyro.getData(ROLL), \
gyro.getData(PITCH), \
gyro.getData(YAW), \
accel.getData(XAXIS), \
accel.getData(YAXIS), \
accel.getData(ZAXIS), \
0.0, \
0.0, \
0.0);
#endif
#if defined HeadingMagHold && !defined FlightAngleMARG && !defined FlightAngleARG
flightAngle->calculate(gyro.getData(ROLL), \
gyro.getData(PITCH), \
gyro.getData(YAW), \
accel.getData(XAXIS), \
accel.getData(YAXIS), \
accel.getData(ZAXIS), \
accel.getOneG(), \
compass.getHdgXY(XAXIS), \
compass.getHdgXY(YAXIS));
#endif
#if !defined HeadingMagHold && !defined FlightAngleMARG && !defined FlightAngleARG
flightAngle->calculate(gyro.getData(ROLL), \
gyro.getData(PITCH), \
gyro.getData(YAW), \
accel.getData(XAXIS), \
accel.getData(YAXIS), \
accel.getData(ZAXIS), \
accel.getOneG(), \
0.0, \
0.0);
#endif
}
// Combines external pilot commands and measured sensor data to generate motor commands
if (controlLoop == ON) {
processFlightControl();
}
#ifdef BinaryWrite
if (fastTransfer == ON) {
// write out fastTelemetry to Configurator or openLog
fastTelemetry();
}
#endif
#ifdef DEBUG_LOOP
digitalWrite(11, LOW);
#endif
}
// ================================================================
// 50hz task loop
// ================================================================
if (frameCounter % 2 == 0) { // 50 Hz tasks
#ifdef DEBUG_LOOP
digitalWrite(10, HIGH);
#endif
G_Dt = (currentTime - fiftyHZpreviousTime) / 1000000.0;
fiftyHZpreviousTime = currentTime;
// Reads external pilot commands and performs functions based on stick configuration
if (receiverLoop == ON) {
readPilotCommands(); // defined in FlightCommand.pde
}
if (sensorLoop == ON) {
#ifdef AltitudeHold
altitude.measure(); // defined in altitude.h
#endif
}
#if defined(CameraControl)
camera.setPitch(degrees(flightAngle->getData(PITCH)));
camera.setRoll(degrees(flightAngle->getData(ROLL)));
camera.setYaw(degrees(flightAngle->getData(YAW)));
camera.move();
#endif
#ifdef DEBUG_LOOP
digitalWrite(10, LOW);
#endif
}
// ================================================================
// 25hz task loop
// ================================================================
if (frameCounter % 4 == 0) { // 25 Hz tasks
#ifdef DEBUG_LOOP
digitalWrite(9, HIGH);
#endif
G_Dt = (currentTime - twentyFiveHZpreviousTime) / 1000000.0;
twentyFiveHZpreviousTime = currentTime;
#ifdef DEBUG_LOOP
digitalWrite(9, LOW);
#endif
}
// ================================================================
// 10hz task loop
// ================================================================
if (frameCounter % 10 == 0) { // 10 Hz tasks
#ifdef DEBUG_LOOP
digitalWrite(8, HIGH);
#endif
G_Dt = (currentTime - tenHZpreviousTime) / 1000000.0;
tenHZpreviousTime = currentTime;
if (sensorLoop == ON) {
#ifdef HeadingMagHold
compass.measure(flightAngle->getData(ROLL), flightAngle->getData(PITCH)); // defined in compass.h
#endif
#ifdef BattMonitor
batteryMonitor.measure(armed);
#endif
processAltitudeHold();
}
// Listen for configuration commands and reports telemetry
if (telemetryLoop == ON) {
readSerialCommand(); // defined in SerialCom.pde
sendSerialTelemetry(); // defined in SerialCom.pde
}
#ifdef MAX7456_OSD
osd.update();
#endif
#ifdef DEBUG_LOOP
digitalWrite(8, LOW);
#endif
}
previousTime = currentTime;
}
if (frameCounter >= 100)
frameCounter = 0;
}