-
Notifications
You must be signed in to change notification settings - Fork 25
/
Serial.ino
1089 lines (1019 loc) · 33.5 KB
/
Serial.ino
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
#if defined(MEGA)
#define UART_NUMBER 4
#elif defined(PROMICRO)
#define UART_NUMBER 2
#else
#define UART_NUMBER 1
#endif
#if defined(GPS_SERIAL)
#define RX_BUFFER_SIZE 256 // 256 RX buffer is needed for GPS communication (64 or 128 was too short)
#else
#define RX_BUFFER_SIZE 256
#endif
#define TX_BUFFER_SIZE 128
#define INBUF_SIZE 64
static volatile uint8_t serialHeadRX[UART_NUMBER],serialTailRX[UART_NUMBER];
static uint8_t serialBufferRX[RX_BUFFER_SIZE][UART_NUMBER];
static volatile uint8_t serialHeadTX[UART_NUMBER],serialTailTX[UART_NUMBER];
static uint8_t serialBufferTX[TX_BUFFER_SIZE][UART_NUMBER];
static uint8_t inBuf[INBUF_SIZE][UART_NUMBER];
#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.
#if defined(SPEK_BIND)
#define BIND_CAPABLE 1;
#endif
// Capability is bit flags; next defines should be 2, 4, 8...
const uint32_t PROGMEM capability = 0+BIND_CAPABLE;
#ifdef DEBUGMSG
#define DEBUG_MSG_BUFFER_SIZE 128
static char debug_buf[DEBUG_MSG_BUFFER_SIZE];
static uint8_t head_debug;
static uint8_t tail_debug;
#endif
// Multiwii Serial Protocol 0
#define MSP_VERSION 0
//to multiwii developpers/committers : do not add new MSP messages without a proper argumentation/agreement on the forum
#define MSP_IDENT 100 //out message multitype + multiwii version + protocol version + capability variable
#define MSP_STATUS 101 //out message cycletime & errors_count & sensor present & box activation & current setting number
#define MSP_RAW_IMU 102 //out message 9 DOF
#define MSP_SERVO 103 //out message 8 servos
#define MSP_MOTOR 104 //out message 8 motors
#define MSP_RC 105 //out message 8 rc chan and more
#define MSP_RAW_GPS 106 //out message fix, numsat, lat, lon, alt, speed, ground course
#define MSP_COMP_GPS 107 //out message distance home, direction home
#define MSP_ATTITUDE 108 //out message 2 angles 1 heading
#define MSP_ALTITUDE 109 //out message altitude, variometer
#define MSP_ANALOG 110 //out message vbat, powermetersum, rssi if available on RX
#define MSP_RC_TUNING 111 //out message rc rate, rc expo, rollpitch rate, yaw rate, dyn throttle PID
#define MSP_PID 112 //out message P I D coeff (9 are used currently)
#define MSP_BOX 113 //out message BOX setup (number is dependant of your setup)
#define MSP_MISC 114 //out message powermeter trig
#define MSP_MOTOR_PINS 115 //out message which pins are in use for motors & servos, for GUI
#define MSP_BOXNAMES 116 //out message the aux switch names
#define MSP_PIDNAMES 117 //out message the PID names
#define MSP_WP 118 //out message get a WP, WP# is in the payload, returns (WP#, lat, lon, alt, flags) WP#0-home, WP#16-poshold
#define MSP_BOXIDS 119 //out message get the permanent IDs associated to BOXes
#if defined(HEX_NANO)
#define MSP_SET_RAW_RC_TINY 150 //in message 4 rc chan
#define MSP_ARM 151
#define MSP_DISARM 152
#define MSP_TRIM_UP 153
#define MSP_TRIM_DOWN 154
#define MSP_TRIM_LEFT 155
#define MSP_TRIM_RIGHT 156
#define MSP_TRIM_UP_FAST 157
#define MSP_TRIM_DOWN_FAST 158
#define MSP_TRIM_LEFT_FAST 159
#define MSP_TRIM_RIGHT_FAST 160
#define MSP_READ_TEST_PARAM 189
#define MSP_SET_TEST_PARAM 190
#define MSP_READ_TEST_PARAM 189
#define MSP_HEX_NANO 199
#endif
#define MSP_SET_RAW_RC 200 //in message 8 rc chan
#define MSP_SET_RAW_GPS 201 //in message fix, numsat, lat, lon, alt, speed
#define MSP_SET_PID 202 //in message P I D coeff (9 are used currently)
#define MSP_SET_BOX 203 //in message BOX setup (number is dependant of your setup)
#define MSP_SET_RC_TUNING 204 //in message rc rate, rc expo, rollpitch rate, yaw rate, dyn throttle PID
#define MSP_ACC_CALIBRATION 205 //in message no param
#define MSP_MAG_CALIBRATION 206 //in message no param
#define MSP_SET_MISC 207 //in message powermeter trig + 8 free for future use
#define MSP_RESET_CONF 208 //in message no param
#define MSP_SET_WP 209 //in message sets a given WP (WP#,lat, lon, alt, flags)
#define MSP_SELECT_SETTING 210 //in message Select Setting Number (0-2)
#define MSP_SET_HEAD 211 //in message define a new heading hold direction
#define MSP_BIND 240 //in message no param
#define MSP_EEPROM_WRITE 250 //in message no param
#define MSP_DEBUGMSG 253 //out message debug string buffer
#define MSP_DEBUG 254 //out message debug1,debug2,debug3,debug4
static uint8_t checksum[UART_NUMBER];
static uint8_t indRX[UART_NUMBER];
static uint8_t cmdMSP[UART_NUMBER];
#if defined(PROMINI)
#define CURRENTPORT 0
#else
static uint8_t CURRENTPORT=0;
#endif
uint32_t read32() {
uint32_t t = read16();
t+= (uint32_t)read16()<<16;
return t;
}
uint16_t read16() {
uint16_t t = read8();
t+= (uint16_t)read8()<<8;
return t;
}
uint8_t read8() {
return inBuf[indRX[CURRENTPORT]++][CURRENTPORT]&0xff;
}
void headSerialResponse(uint8_t err, uint8_t s) {
serialize8('$');
serialize8('M');
serialize8(err ? '!' : '>');
checksum[CURRENTPORT] = 0; // start calculating a new checksum
serialize8(s);
serialize8(cmdMSP[CURRENTPORT]);
}
void headSerialReply(uint8_t s) {
headSerialResponse(0, s);
}
void inline headSerialError(uint8_t s) {
headSerialResponse(1, s);
}
void tailSerialReply() {
serialize8(checksum[CURRENTPORT]);UartSendData();
}
void serializeNames(PGM_P s) {
for (PGM_P c = s; pgm_read_byte(c); c++) {
serialize8(pgm_read_byte(c));
}
}
void serialCom() {
uint8_t c,n;
static uint8_t offset[UART_NUMBER];
static uint8_t dataSize[UART_NUMBER];
static enum _serial_state {
IDLE,
HEADER_START,
HEADER_M,
HEADER_ARROW,
HEADER_SIZE,
HEADER_CMD,
} c_state[UART_NUMBER];// = IDLE;
for(n=0;n<UART_NUMBER;n++) {
#if !defined(PROMINI)
CURRENTPORT=n;
#endif
#define GPS_COND
#if defined(GPS_SERIAL)
#if defined(GPS_PROMINI)
#define GPS_COND
#else
#define GPS_COND && (GPS_SERIAL != CURRENTPORT)
#endif
#endif
#define SPEK_COND
#if defined(SPEKTRUM) && (UART_NUMBER > 1)
#define SPEK_COND && (SPEK_SERIAL_PORT != CURRENTPORT)
#endif
while (SerialAvailable(CURRENTPORT) GPS_COND SPEK_COND) {
uint8_t bytesTXBuff = ((uint8_t)(serialHeadTX[CURRENTPORT]-serialTailTX[CURRENTPORT]))%TX_BUFFER_SIZE; // indicates the number of occupied bytes in TX buffer
if (bytesTXBuff > TX_BUFFER_SIZE - 50 ) return; // ensure there is enough free TX buffer to go further (50 bytes margin)
c = SerialRead(CURRENTPORT);
#ifdef SUPPRESS_ALL_SERIAL_MSP
// no MSP handling, so go directly
evaluateOtherData(c);
#else
// regular data handling to detect and handle MSP and other data
if (c_state[CURRENTPORT] == IDLE) {
c_state[CURRENTPORT] = (c=='$') ? HEADER_START : IDLE;
if (c_state[CURRENTPORT] == IDLE) evaluateOtherData(c); // evaluate all other incoming serial data
} else if (c_state[CURRENTPORT] == HEADER_START) {
c_state[CURRENTPORT] = (c=='M') ? HEADER_M : IDLE;
} else if (c_state[CURRENTPORT] == HEADER_M) {
c_state[CURRENTPORT] = (c=='<') ? HEADER_ARROW : IDLE;
} else if (c_state[CURRENTPORT] == HEADER_ARROW) {
if (c > INBUF_SIZE) { // now we are expecting the payload size
c_state[CURRENTPORT] = IDLE;
continue;
}
dataSize[CURRENTPORT] = c;
offset[CURRENTPORT] = 0;
checksum[CURRENTPORT] = 0;
indRX[CURRENTPORT] = 0;
checksum[CURRENTPORT] ^= c;
c_state[CURRENTPORT] = HEADER_SIZE; // the command is to follow
} else if (c_state[CURRENTPORT] == HEADER_SIZE) {
cmdMSP[CURRENTPORT] = c;
checksum[CURRENTPORT] ^= c;
c_state[CURRENTPORT] = HEADER_CMD;
} else if (c_state[CURRENTPORT] == HEADER_CMD && offset[CURRENTPORT] < dataSize[CURRENTPORT]) {
checksum[CURRENTPORT] ^= c;
inBuf[offset[CURRENTPORT]++][CURRENTPORT] = c;
} else if (c_state[CURRENTPORT] == HEADER_CMD && offset[CURRENTPORT] >= dataSize[CURRENTPORT]) {
if (checksum[CURRENTPORT] == c) { // compare calculated and transferred checksum
evaluateCommand(); // we got a valid packet, evaluate it
}
c_state[CURRENTPORT] = IDLE;
}
#endif // SUPPRESS_ALL_SERIAL_MSP
}
}
}
#ifndef SUPPRESS_ALL_SERIAL_MSP
void evaluateCommand() {
#if defined(HEX_NANO)
unsigned char auxChannels;
unsigned char aux;
#endif
switch(cmdMSP[CURRENTPORT]) {
case MSP_SET_RAW_RC:
for(uint8_t i=0;i<8;i++) {
rcData[i] = read16();
}
failsafeCnt = 0;
headSerialReply(0);
break;
#if defined(HEX_NANO)
case MSP_READ_TEST_PARAM:
headSerialReply(12);
blinkLED(15,20,1);
paramList[0] = alpha * 250.f;
paramList[1] = conf.P8[PIDALT] * 250.f / 200;
paramList[2] = conf.I8[PIDALT];
paramList[3] = conf.D8[PIDALT] * 250.f / 100;
for(int idx = 0; idx < 12; idx++){
serialize8(paramList[idx]);
}
break;
case MSP_SET_TEST_PARAM:
for(int idx = 0; idx < 12; idx++){
paramList[idx] = read8();
}
blinkLED(15,20,1);
alpha = paramList[0] / 250.f;
conf.P8[PIDALT] = paramList[1] / 250.f * 200; //0~200
conf.I8[PIDALT] = paramList[2]; //0~250
conf.D8[PIDALT] = paramList[3] / 250.f * 100; //0~100
writeParams(0);
return;
break;
case MSP_SET_RAW_RC_TINY:
for(uint8_t i = 0;i < 4;i++) {
serialRcValue[i] = 1000 + read8() * 4;
}
auxChannels = read8();
aux = (auxChannels & 0xc0) >> 6;
if(aux == 0){
serialRcValue[4] = 1000;
}
else if(aux == 1){
serialRcValue[4] = 1500;
}
else{
serialRcValue[4] = 2000;
}
aux = (auxChannels & 0x30) >> 4;
if(aux == 0){
serialRcValue[5] = 1000;
}
else if(aux == 1){
serialRcValue[5] = 1500;
}
else{
serialRcValue[5] = 2000;
}
aux = (auxChannels & 0x0c) >> 2;
if(aux == 0){
serialRcValue[6] = 1000;
}
else if(aux == 1){
serialRcValue[6] = 1500;
}
else{
serialRcValue[6] = 2000;
}
aux = (auxChannels & 0x03);
if(aux == 0){
serialRcValue[7] = 1000;
}
else if(aux == 1){
serialRcValue[7] = 1500;
}
else{
serialRcValue[7] = 2000;
}
failsafeCnt = 0;
return;
/*
headSerialReply(8);
for(uint8_t i = 0; i < 4; i++) {
serialize16(serialRcValue[i]);
}*/
break;
case MSP_ARM:
go_arm();
break;
case MSP_DISARM:
go_disarm();
break;
case MSP_TRIM_UP:
if(conf.angleTrim[PITCH] < 120){
conf.angleTrim[PITCH]+=1;
writeParams(1);
#if defined(LED_RING)
blinkLedRing();
#endif
}
break;
case MSP_TRIM_DOWN:
if(conf.angleTrim[PITCH] > -120){
conf.angleTrim[PITCH]-=1;
writeParams(1);
#if defined(LED_RING)
blinkLedRing();
#endif
}
break;
case MSP_TRIM_LEFT:
if(conf.angleTrim[ROLL] > -120){
conf.angleTrim[ROLL]-=1;
writeParams(1);
#if defined(LED_RING)
blinkLedRing();
#endif
}
break;
case MSP_TRIM_RIGHT:
if(conf.angleTrim[ROLL] < 120){
conf.angleTrim[ROLL]+=1;
writeParams(1);
#if defined(LED_RING)
blinkLedRing();
#endif
}
break;
case MSP_TRIM_UP_FAST:
if(conf.angleTrim[PITCH] < 120){
conf.angleTrim[PITCH]+=10;
writeParams(1);
#if defined(LED_RING)
blinkLedRing();
#endif
}
break;
case MSP_TRIM_DOWN_FAST:
if(conf.angleTrim[PITCH] > -120){
conf.angleTrim[PITCH]-=10;
writeParams(1);
#if defined(LED_RING)
blinkLedRing();
#endif
}
break;
case MSP_TRIM_LEFT_FAST:
if(conf.angleTrim[ROLL] > -120){
conf.angleTrim[ROLL]-=10;
writeParams(1);
#if defined(LED_RING)
blinkLedRing();
#endif
}
break;
case MSP_TRIM_RIGHT_FAST:
if(conf.angleTrim[ROLL] < 120){
conf.angleTrim[ROLL]+=10;
writeParams(1);
#if defined(LED_RING)
blinkLedRing();
#endif
}
break;
case MSP_HEX_NANO:
headSerialReply(14);
serialize8(flightState);
serialize16(absolutedAccZ);
//serialize32(EstAlt);
serialize16((int16_t)EstAlt);
for(uint8_t i=0;i<2;i++) serialize16(angle[i]);
serialize16((int16_t)AltHold);
serialize8(vbat);
serialize8((int8_t)(conf.angleTrim[PITCH]));
serialize8((int8_t)(conf.angleTrim[ROLL]));
break;
#endif
#if GPS
case MSP_SET_RAW_GPS:
f.GPS_FIX = read8();
GPS_numSat = read8();
GPS_coord[LAT] = read32();
GPS_coord[LON] = read32();
GPS_altitude = read16();
GPS_speed = read16();
GPS_update |= 2; // New data signalisation to GPS functions
headSerialReply(0);
break;
#endif
case MSP_SET_PID:
for(uint8_t i=0;i<PIDITEMS;i++) {
conf.P8[i]=read8();
conf.I8[i]=read8();
conf.D8[i]=read8();
}
headSerialReply(0);
break;
case MSP_SET_BOX:
for(uint8_t i=0;i<CHECKBOXITEMS;i++) {
conf.activate[i]=read16();
}
headSerialReply(0);
break;
case MSP_SET_RC_TUNING:
conf.rcRate8 = read8();
conf.rcExpo8 = read8();
conf.rollPitchRate = read8();
conf.yawRate = read8();
conf.dynThrPID = read8();
conf.thrMid8 = read8();
conf.thrExpo8 = read8();
headSerialReply(0);
break;
case MSP_SET_MISC:
#if defined(POWERMETER)
conf.powerTrigger1 = read16() / PLEVELSCALE;
#endif
headSerialReply(0);
break;
#ifdef MULTIPLE_CONFIGURATION_PROFILES
case MSP_SELECT_SETTING:
if(!f.ARMED) {
global_conf.currentSet = read8();
if(global_conf.currentSet>2) global_conf.currentSet = 0;
writeGlobalSet(0);
readEEPROM();
}
headSerialReply(0);
break;
#endif
case MSP_SET_HEAD:
magHold = read16();
headSerialReply(0);
break;
case MSP_IDENT:
headSerialReply(7);
serialize8(VERSION); // multiwii version
serialize8(MULTITYPE); // type of multicopter
serialize8(MSP_VERSION); // MultiWii Serial Protocol Version
serialize32(pgm_read_dword(&(capability))); // "capability"
break;
case MSP_STATUS:
headSerialReply(11);
serialize16(cycleTime);
serialize16(i2c_errors_count);
serialize16(ACC|BARO<<1|MAG<<2|GPS<<3|SONAR<<4);
serialize32(
#if ACC
f.ANGLE_MODE<<BOXANGLE|
f.HORIZON_MODE<<BOXHORIZON|
#endif
#if HEX_NANO_SONAR && (!defined(SUPPRESS_BARO_ALTHOLD))
f.BARO_MODE<<BOXBARO|
#endif
#if MAG
f.MAG_MODE<<BOXMAG|f.HEADFREE_MODE<<BOXHEADFREE|rcOptions[BOXHEADADJ]<<BOXHEADADJ|
#endif
#if defined(SERVO_TILT) || defined(GIMBAL)|| defined(SERVO_MIX_TILT)
rcOptions[BOXCAMSTAB]<<BOXCAMSTAB|
#endif
#if defined(CAMTRIG)
rcOptions[BOXCAMTRIG]<<BOXCAMTRIG|
#endif
#if GPS
f.GPS_HOME_MODE<<BOXGPSHOME|f.GPS_HOLD_MODE<<BOXGPSHOLD|
#endif
#if defined(FIXEDWING) || defined(HELICOPTER)
f.PASSTHRU_MODE<<BOXPASSTHRU|
#endif
#if defined(BUZZER)
rcOptions[BOXBEEPERON]<<BOXBEEPERON|
#endif
#if defined(LED_FLASHER)
rcOptions[BOXLEDMAX]<<BOXLEDMAX|
#endif
#if defined(LANDING_LIGHTS_DDR)
rcOptions[BOXLLIGHTS]<<BOXLLIGHTS |
#endif
#if defined(VARIOMETER)
rcOptions[BOXVARIO]<<BOXVARIO |
#endif
#if defined(INFLIGHT_ACC_CALIBRATION)
rcOptions[BOXCALIB]<<BOXCALIB |
#endif
#if defined(GOVERNOR_P)
rcOptions[BOXGOV]<<BOXGOV |
#endif
#if defined(OSD_SWITCH)
rcOptions[BOXOSD]<<BOXOSD |
#endif
f.ARMED<<BOXARM);
serialize8(global_conf.currentSet); // current setting
break;
case MSP_RAW_IMU:
headSerialReply(18);
for(uint8_t i=0;i<3;i++) serialize16(accSmooth[i]);
for(uint8_t i=0;i<3;i++) serialize16(gyroData[i]);
for(uint8_t i=0;i<3;i++) serialize16(magADC[i]);
break;
case MSP_SERVO:
headSerialReply(16);
for(uint8_t i=0;i<8;i++)
#if defined(SERVO)
serialize16(servo[i]);
#else
serialize16(0);
#endif
break;
case MSP_MOTOR:
headSerialReply(16);
for(uint8_t i=0;i<8;i++) {
serialize16( (i < NUMBER_MOTOR) ? motor[i] : 0 );
}
break;
case MSP_RC:
headSerialReply(RC_CHANS * 2);
for(uint8_t i=0;i<RC_CHANS;i++) serialize16(rcData[i]);
break;
#if GPS
case MSP_RAW_GPS:
headSerialReply(16);
serialize8(f.GPS_FIX);
serialize8(GPS_numSat);
serialize32(GPS_coord[LAT]);
serialize32(GPS_coord[LON]);
serialize16(GPS_altitude);
serialize16(GPS_speed);
serialize16(GPS_ground_course); // added since r1172
break;
case MSP_COMP_GPS:
headSerialReply(5);
serialize16(GPS_distanceToHome);
serialize16(GPS_directionToHome);
serialize8(GPS_update & 1);
break;
#endif
case MSP_ATTITUDE:
headSerialReply(8);
for(uint8_t i=0;i<2;i++) serialize16(angle[i]);
serialize16(heading);
serialize16(headFreeModeHold);
break;
case MSP_ALTITUDE:
headSerialReply(6);
serialize32(EstAlt);
serialize16(vario); // added since r1172
break;
case MSP_ANALOG:
headSerialReply(5);
serialize8(vbat);
serialize16(intPowerMeterSum);
serialize16(rssi);
break;
case MSP_RC_TUNING:
headSerialReply(7);
serialize8(conf.rcRate8);
serialize8(conf.rcExpo8);
serialize8(conf.rollPitchRate);
serialize8(conf.yawRate);
serialize8(conf.dynThrPID);
serialize8(conf.thrMid8);
serialize8(conf.thrExpo8);
break;
case MSP_PID:
headSerialReply(3*PIDITEMS);
for(uint8_t i=0;i<PIDITEMS;i++) {
serialize8(conf.P8[i]);
serialize8(conf.I8[i]);
serialize8(conf.D8[i]);
}
break;
case MSP_PIDNAMES:
headSerialReply(strlen_P(pidnames));
serializeNames(pidnames);
break;
case MSP_BOX:
headSerialReply(2*CHECKBOXITEMS);
for(uint8_t i=0;i<CHECKBOXITEMS;i++) {
serialize16(conf.activate[i]);
}
break;
case MSP_BOXNAMES:
headSerialReply(strlen_P(boxnames));
serializeNames(boxnames);
break;
case MSP_BOXIDS:
headSerialReply(CHECKBOXITEMS);
for(uint8_t i=0;i<CHECKBOXITEMS;i++) {
serialize8(pgm_read_byte(&(boxids[i])));
}
break;
case MSP_MISC:
headSerialReply(2);
serialize16(intPowerTrigger1);
break;
case MSP_MOTOR_PINS:
headSerialReply(8);
for(uint8_t i=0;i<8;i++) {
serialize8(PWM_PIN[i]);
}
break;
#if defined(USE_MSP_WP)
case MSP_WP:
{
int32_t lat = 0,lon = 0;
uint8_t wp_no = read8(); //get the wp number
headSerialReply(18);
if (wp_no == 0) {
lat = GPS_home[LAT];
lon = GPS_home[LON];
} else if (wp_no == 16) {
lat = GPS_hold[LAT];
lon = GPS_hold[LON];
}
serialize8(wp_no);
serialize32(lat);
serialize32(lon);
serialize32(AltHold); //altitude (cm) will come here -- temporary implementation to test feature with apps
serialize16(0); //heading will come here (deg)
serialize16(0); //time to stay (ms) will come here
serialize8(0); //nav flag will come here
}
break;
case MSP_SET_WP:
{
int32_t lat = 0,lon = 0,alt = 0;
uint8_t wp_no = read8(); //get the wp number
lat = read32();
lon = read32();
alt = read32(); // to set altitude (cm)
read16(); // future: to set heading (deg)
read16(); // future: to set time to stay (ms)
read8(); // future: to set nav flag
if (wp_no == 0) {
GPS_home[LAT] = lat;
GPS_home[LON] = lon;
f.GPS_HOME_MODE = 0; // with this flag, GPS_set_next_wp will be called in the next loop -- OK with SERIAL GPS / OK with I2C GPS
f.GPS_FIX_HOME = 1;
if (alt != 0) AltHold = alt; // temporary implementation to test feature with apps
} else if (wp_no == 16) { // OK with SERIAL GPS -- NOK for I2C GPS / needs more code dev in order to inject GPS coord inside I2C GPS
GPS_hold[LAT] = lat;
GPS_hold[LON] = lon;
if (alt != 0) AltHold = alt; // temporary implementation to test feature with apps
#if !defined(I2C_GPS)
nav_mode = NAV_MODE_WP;
GPS_set_next_wp(&GPS_hold[LAT],&GPS_hold[LON]);
#endif
}
}
headSerialReply(0);
break;
#endif
case MSP_RESET_CONF:
if(!f.ARMED) LoadDefaults();
headSerialReply(0);
break;
case MSP_ACC_CALIBRATION:
if(!f.ARMED) calibratingA=512;
headSerialReply(0);
break;
case MSP_MAG_CALIBRATION:
if(!f.ARMED) f.CALIBRATE_MAG = 1;
headSerialReply(0);
break;
#if defined(SPEK_BIND)
case MSP_BIND:
spekBind();
headSerialReply(0);
break;
#endif
case MSP_EEPROM_WRITE:
writeParams(0);
headSerialReply(0);
break;
case MSP_DEBUG:
headSerialReply(8);
for(uint8_t i=0;i<4;i++) {
serialize16(debug[i]); // 4 variables are here for general monitoring purpose
}
break;
#ifdef DEBUGMSG
case MSP_DEBUGMSG:
{
uint8_t size = debugmsg_available();
if (size > 16) size = 16;
headSerialReply(size);
debugmsg_serialize(size);
}
break;
#endif
default: // we do not know how to handle the (valid) message, indicate error MSP $M!
headSerialError(0);
break;
}
tailSerialReply();
}
#endif // SUPPRESS_ALL_SERIAL_MSP
// evaluate all other incoming serial data
void evaluateOtherData(uint8_t sr) {
#ifndef SUPPRESS_OTHER_SERIAL_COMMANDS
switch (sr) {
// Note: we may receive weird characters here which could trigger unwanted features during flight.
// this could lead to a crash easily.
// Please use if (!f.ARMED) where neccessary
#ifdef LCD_CONF
case 's':
case 'S':
if (!f.ARMED) configurationLoop();
break;
#endif
#ifdef LOG_PERMANENT_SHOW_AT_L
case 'L':
if (!f.ARMED) dumpPLog(1);
break;
#endif
#if defined(LCD_TELEMETRY) && defined(LCD_TEXTSTAR)
case 'A': // button A press
toggle_telemetry(1);
break;
case 'B': // button B press
toggle_telemetry(2);
break;
case 'C': // button C press
toggle_telemetry(3);
break;
case 'D': // button D press
toggle_telemetry(4);
break;
case 'a': // button A release
case 'b': // button B release
case 'c': // button C release
case 'd': // button D release
break;
#endif
#ifdef LCD_TELEMETRY
case '0':
case '1':
case '2':
case '3':
case '4':
case '5':
case '6':
case '7':
case '8':
case '9':
#if defined(LOG_VALUES) || defined(DEBUG)
case 'R':
#endif
#ifdef DEBUG
case 'F':
#endif
toggle_telemetry(sr);
break;
#endif // LCD_TELEMETRY
}
#endif // SUPPRESS_OTHER_SERIAL_COMMANDS
}
// *******************************************************
// For Teensy 2.0, these function emulate the API used for ProMicro
// it cant have the same name as in the arduino API because it wont compile for the promini (eaven if it will be not compiled)
// *******************************************************
#if defined(TEENSY20)
unsigned char T_USB_Available(){
int n = Serial.available();
if (n > 255) n = 255;
return n;
}
#endif
// *******************************************************
// Interrupt driven UART transmitter - using a ring buffer
// *******************************************************
void serialize32(uint32_t a) {
serialize8((a ) & 0xFF);
serialize8((a>> 8) & 0xFF);
serialize8((a>>16) & 0xFF);
serialize8((a>>24) & 0xFF);
}
void serialize16(int16_t a) {
serialize8((a ) & 0xFF);
serialize8((a>>8) & 0xFF);
}
void serialize8(uint8_t a) {
uint8_t t = serialHeadTX[CURRENTPORT];
if (++t >= TX_BUFFER_SIZE) t = 0;
serialBufferTX[t][CURRENTPORT] = a;
checksum[CURRENTPORT] ^= a;
serialHeadTX[CURRENTPORT] = t;
}
#if defined(PROMINI) || defined(MEGA)
#if defined(PROMINI)
ISR(USART_UDRE_vect) { // Serial 0 on a PROMINI
#endif
#if defined(MEGA)
ISR(USART0_UDRE_vect) { // Serial 0 on a MEGA
#endif
uint8_t t = serialTailTX[0];
if (serialHeadTX[0] != t) {
if (++t >= TX_BUFFER_SIZE) t = 0;
UDR0 = serialBufferTX[t][0]; // Transmit next byte in the ring
serialTailTX[0] = t;
}
if (t == serialHeadTX[0]) UCSR0B &= ~(1<<UDRIE0); // Check if all data is transmitted . if yes disable transmitter UDRE interrupt
}
#endif
#if defined(MEGA) || defined(PROMICRO)
ISR(USART1_UDRE_vect) { // Serial 1 on a MEGA or on a PROMICRO
uint8_t t = serialTailTX[1];
if (serialHeadTX[1] != t) {
if (++t >= TX_BUFFER_SIZE) t = 0;
UDR1 = serialBufferTX[t][1]; // Transmit next byte in the ring
serialTailTX[1] = t;
}
if (t == serialHeadTX[1]) UCSR1B &= ~(1<<UDRIE1);
}
#endif
#if defined(MEGA)
ISR(USART2_UDRE_vect) { // Serial 2 on a MEGA
uint8_t t = serialTailTX[2];
if (serialHeadTX[2] != t) {
if (++t >= TX_BUFFER_SIZE) t = 0;
UDR2 = serialBufferTX[t][2];
serialTailTX[2] = t;
}
if (t == serialHeadTX[2]) UCSR2B &= ~(1<<UDRIE2);
}
ISR(USART3_UDRE_vect) { // Serial 3 on a MEGA
uint8_t t = serialTailTX[3];
if (serialHeadTX[3] != t) {
if (++t >= TX_BUFFER_SIZE) t = 0;
UDR3 = serialBufferTX[t][3];
serialTailTX[3] = t;
}
if (t == serialHeadTX[3]) UCSR3B &= ~(1<<UDRIE3);
}
#endif
void UartSendData() {
#if defined(PROMINI)
UCSR0B |= (1<<UDRIE0);
#endif
#if defined(PROMICRO)
switch (CURRENTPORT) {
case 0:
while(serialHeadTX[0] != serialTailTX[0]) {
if (++serialTailTX[0] >= TX_BUFFER_SIZE) serialTailTX[0] = 0;
#if !defined(TEENSY20)
USB_Send(USB_CDC_TX,serialBufferTX[serialTailTX[0]],1);
#else
Serial.write(serialBufferTX[serialTailTX[0]],1);
#endif
}
break;
case 1: UCSR1B |= (1<<UDRIE1); break;
}
#endif
#if defined(MEGA)
switch (CURRENTPORT) {
case 0: UCSR0B |= (1<<UDRIE0); break;
case 1: UCSR1B |= (1<<UDRIE1); break;
case 2: UCSR2B |= (1<<UDRIE2); break;
case 3: UCSR3B |= (1<<UDRIE3); break;
}
#endif
}
#if defined(GPS_SERIAL)
bool SerialTXfree(uint8_t port) {
return (serialHeadTX[port] == serialTailTX[port]);
}
#endif
void SerialOpen(uint8_t port, uint32_t baud) {
uint8_t h = ((F_CPU / 4 / baud -1) / 2) >> 8;
uint8_t l = ((F_CPU / 4 / baud -1) / 2);
switch (port) {
#if defined(PROMINI)
case 0: UCSR0A = (1<<U2X0); UBRR0H = h; UBRR0L = l; UCSR0B |= (1<<RXEN0)|(1<<TXEN0)|(1<<RXCIE0); break;
#endif
#if defined(PROMICRO)
#if (ARDUINO >= 100) && !defined(TEENSY20)
case 0: UDIEN &= ~(1<<SOFE); break;// disable the USB frame interrupt of arduino (it causes strong jitter and we dont need it)
#endif
case 1: UCSR1A = (1<<U2X1); UBRR1H = h; UBRR1L = l; UCSR1B |= (1<<RXEN1)|(1<<TXEN1)|(1<<RXCIE1); break;
#endif
#if defined(MEGA)
case 0: UCSR0A = (1<<U2X0); UBRR0H = h; UBRR0L = l; UCSR0B |= (1<<RXEN0)|(1<<TXEN0)|(1<<RXCIE0); break;
case 1: UCSR1A = (1<<U2X1); UBRR1H = h; UBRR1L = l; UCSR1B |= (1<<RXEN1)|(1<<TXEN1)|(1<<RXCIE1); break;
case 2: UCSR2A = (1<<U2X2); UBRR2H = h; UBRR2L = l; UCSR2B |= (1<<RXEN2)|(1<<TXEN2)|(1<<RXCIE2); break;
case 3: UCSR3A = (1<<U2X3); UBRR3H = h; UBRR3L = l; UCSR3B |= (1<<RXEN3)|(1<<TXEN3)|(1<<RXCIE3); break;
#endif
}
}
static void inline SerialEnd(uint8_t port) {
switch (port) {
#if defined(PROMINI)
case 0: UCSR0B &= ~((1<<RXEN0)|(1<<TXEN0)|(1<<RXCIE0)|(1<<UDRIE0)); break;
#endif
#if defined(PROMICRO)
case 1: UCSR1B &= ~((1<<RXEN1)|(1<<TXEN1)|(1<<RXCIE1)|(1<<UDRIE1)); break;
#endif
#if defined(MEGA)
case 0: UCSR0B &= ~((1<<RXEN0)|(1<<TXEN0)|(1<<RXCIE0)|(1<<UDRIE0)); break;
case 1: UCSR1B &= ~((1<<RXEN1)|(1<<TXEN1)|(1<<RXCIE1)|(1<<UDRIE1)); break;
case 2: UCSR2B &= ~((1<<RXEN2)|(1<<TXEN2)|(1<<RXCIE2)|(1<<UDRIE2)); break;
case 3: UCSR3B &= ~((1<<RXEN3)|(1<<TXEN3)|(1<<RXCIE3)|(1<<UDRIE3)); break;
#endif
}
}
static void inline store_uart_in_buf(uint8_t data, uint8_t portnum) {
#if defined(SPEKTRUM)
if (portnum == SPEK_SERIAL_PORT) {
if (!spekFrameFlags) {
sei();
uint32_t spekTimeNow = (timer0_overflow_count << 8) * (64 / clockCyclesPerMicrosecond()); //Move timer0_overflow_count into registers so we don't touch a volatile twice
uint32_t spekInterval = spekTimeNow - spekTimeLast; //timer0_overflow_count will be slightly off because of the way the Arduino core timer interrupt handler works; that is acceptable for this use. Using the core variable avoids an expensive call to millis() or micros()
spekTimeLast = spekTimeNow;
if (spekInterval > 5000) { //Potential start of a Spektrum frame, they arrive every 11 or every 22 ms. Mark it, and clear the buffer.
serialTailRX[portnum] = 0;
serialHeadRX[portnum] = 0;
spekFrameFlags = 0x01;
}
cli();
}
}
#endif
uint8_t h = serialHeadRX[portnum];
if (++h >= RX_BUFFER_SIZE) h = 0;
if (h == serialTailRX[portnum]) return; // we did not bite our own tail?
serialBufferRX[serialHeadRX[portnum]][portnum] = data;
serialHeadRX[portnum] = h;
}
#if defined(PROMINI)
ISR(USART_RX_vect) { store_uart_in_buf(UDR0, 0); }