-
-
Notifications
You must be signed in to change notification settings - Fork 2.9k
/
gps.c
1954 lines (1743 loc) · 65.4 KB
/
gps.c
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
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software 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.
*
* Cleanflight and Betaflight are distributed in the hope that they
* 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 software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#include <ctype.h>
#include <string.h>
#include <math.h>
#include "platform.h"
#ifdef USE_GPS
#include "build/build_config.h"
#include "build/debug.h"
#include "common/axis.h"
#include "common/gps_conversion.h"
#include "common/maths.h"
#include "common/utils.h"
#include "config/feature.h"
#include "drivers/light_led.h"
#include "drivers/time.h"
#include "io/beeper.h"
#include "io/dashboard.h"
#include "io/gps.h"
#include "io/serial.h"
#include "config/config.h"
#include "fc/runtime_config.h"
#include "flight/imu.h"
#include "flight/pid.h"
#include "flight/gps_rescue.h"
#include "scheduler/scheduler.h"
#include "sensors/sensors.h"
#define LOG_ERROR '?'
#define LOG_IGNORED '!'
#define LOG_SKIPPED '>'
#define LOG_NMEA_GGA 'g'
#define LOG_NMEA_GSA 's'
#define LOG_NMEA_RMC 'r'
#define LOG_UBLOX_DOP 'D'
#define LOG_UBLOX_SOL 'O'
#define LOG_UBLOX_STATUS 'S'
#define LOG_UBLOX_SVINFO 'I'
#define LOG_UBLOX_POSLLH 'P'
#define LOG_UBLOX_VELNED 'V'
#define DEBUG_SERIAL_BAUD 0 // set to 1 to debug serial port baud config (/100)
#define DEBUG_UBLOX_INIT 0 // set to 1 to debug ublox initialization
#define DEBUG_UBLOX_FRAMES 0 // set to 1 to debug ublox received frames
char gpsPacketLog[GPS_PACKET_LOG_ENTRY_COUNT];
static char *gpsPacketLogChar = gpsPacketLog;
// **********************
// GPS
// **********************
int32_t GPS_home[2];
uint16_t GPS_distanceToHome; // distance to home point in meters
uint32_t GPS_distanceToHomeCm;
int16_t GPS_directionToHome; // direction to home or hol point in degrees * 10
uint32_t GPS_distanceFlownInCm; // distance flown since armed in centimeters
int16_t GPS_verticalSpeedInCmS; // vertical speed in cm/s
int16_t nav_takeoff_bearing;
#define GPS_DISTANCE_FLOWN_MIN_SPEED_THRESHOLD_CM_S 15 // 0.54 km/h 0.335 mph
gpsSolutionData_t gpsSol;
uint32_t GPS_packetCount = 0;
uint32_t GPS_svInfoReceivedCount = 0; // SV = Space Vehicle, counter increments each time SV info is received.
uint8_t GPS_update = 0; // toogle to distinct a GPS position update (directly or via MSP)
uint8_t GPS_numCh; // Details on numCh/svinfo in gps.h
uint8_t GPS_svinfo_chn[GPS_SV_MAXSATS_M8N];
uint8_t GPS_svinfo_svid[GPS_SV_MAXSATS_M8N];
uint8_t GPS_svinfo_quality[GPS_SV_MAXSATS_M8N];
uint8_t GPS_svinfo_cno[GPS_SV_MAXSATS_M8N];
// GPS timeout for wrong baud rate/disconnection/etc in milliseconds (default 2.5second)
#define GPS_TIMEOUT (2500)
// How many entries in gpsInitData array below
#define GPS_INIT_ENTRIES (GPS_BAUDRATE_MAX + 1)
#define GPS_BAUDRATE_CHANGE_DELAY (200)
// Timeout for waiting ACK/NAK in GPS task cycles (0.25s at 100Hz)
#define UBLOX_ACK_TIMEOUT_MAX_COUNT (25)
static serialPort_t *gpsPort;
static float gpsSampleRateHz;
typedef struct gpsInitData_s {
uint8_t index;
uint8_t baudrateIndex; // see baudRate_e
const char *ubx;
const char *mtk;
} gpsInitData_t;
// NMEA will cycle through these until valid data is received
static const gpsInitData_t gpsInitData[] = {
{ GPS_BAUDRATE_115200, BAUD_115200, "$PUBX,41,1,0003,0001,115200,0*1E\r\n", "$PMTK251,115200*1F\r\n" },
{ GPS_BAUDRATE_57600, BAUD_57600, "$PUBX,41,1,0003,0001,57600,0*2D\r\n", "$PMTK251,57600*2C\r\n" },
{ GPS_BAUDRATE_38400, BAUD_38400, "$PUBX,41,1,0003,0001,38400,0*26\r\n", "$PMTK251,38400*27\r\n" },
{ GPS_BAUDRATE_19200, BAUD_19200, "$PUBX,41,1,0003,0001,19200,0*23\r\n", "$PMTK251,19200*22\r\n" },
// 9600 is not enough for 5Hz updates - leave for compatibility to dumb NMEA that only runs at this speed
{ GPS_BAUDRATE_9600, BAUD_9600, "$PUBX,41,1,0003,0001,9600,0*16\r\n", "" }
};
#define GPS_INIT_DATA_ENTRY_COUNT ARRAYLEN(gpsInitData)
#define DEFAULT_BAUD_RATE_INDEX 0
#ifdef USE_GPS_UBLOX
typedef enum {
PREAMBLE1 = 0xB5,
PREAMBLE2 = 0x62,
CLASS_NAV = 0x01,
CLASS_ACK = 0x05,
CLASS_CFG = 0x06,
MSG_ACK_NACK = 0x00,
MSG_ACK_ACK = 0x01,
MSG_POSLLH = 0x02,
MSG_STATUS = 0x03,
MSG_DOP = 0x04,
MSG_SOL = 0x06,
MSG_PVT = 0x07,
MSG_VELNED = 0x12,
MSG_SVINFO = 0x30,
MSG_SAT = 0x35,
MSG_CFG_MSG = 0x01,
MSG_CFG_PRT = 0x00,
MSG_CFG_RATE = 0x08,
MSG_CFG_SET_RATE = 0x01,
MSG_CFG_SBAS = 0x16,
MSG_CFG_NAV_SETTINGS = 0x24,
MSG_CFG_GNSS = 0x3E
} ubxProtocolBytes_e;
#define UBLOX_MODE_ENABLED 0x1
#define UBLOX_MODE_TEST 0x2
#define UBLOX_USAGE_RANGE 0x1
#define UBLOX_USAGE_DIFFCORR 0x2
#define UBLOX_USAGE_INTEGRITY 0x4
#define UBLOX_GNSS_ENABLE 0x1
#define UBLOX_GNSS_DEFAULT_SIGCFGMASK 0x10000
#define UBLOX_DYNMODE_PEDESTRIAN 3
#define UBLOX_DYNMODE_AIRBORNE_1G 6
#define UBLOX_DYNMODE_AIRBORNE_4G 8
typedef struct ubxHeader_s {
uint8_t preamble1;
uint8_t preamble2;
uint8_t msg_class;
uint8_t msg_id;
uint16_t length;
} ubxHeader_t;
typedef struct ubxConfigblock_s {
uint8_t gnssId;
uint8_t resTrkCh;
uint8_t maxTrkCh;
uint8_t reserved1;
uint32_t flags;
} ubxConfigblock_t;
typedef struct ubxPollMsg_s {
uint8_t msgClass;
uint8_t msgID;
} ubxPollMsg_t;
typedef struct ubxCfgMsg_s {
uint8_t msgClass;
uint8_t msgID;
uint8_t rate;
} ubxCfgMsg_t;
typedef struct ubxCfgRate_s {
uint16_t measRate;
uint16_t navRate;
uint16_t timeRef;
} ubxCfgRate_t;
typedef struct ubxCfgSbas_s {
uint8_t mode;
uint8_t usage;
uint8_t maxSBAS;
uint8_t scanmode2;
uint32_t scanmode1;
} ubxCfgSbas_t;
typedef struct ubxCfgGnss_s {
uint8_t msgVer;
uint8_t numTrkChHw;
uint8_t numTrkChUse;
uint8_t numConfigBlocks;
ubxConfigblock_t configblocks[7];
} ubxCfgGnss_t;
typedef struct ubxCfgNav5_s {
uint16_t mask;
uint8_t dynModel;
uint8_t fixMode;
int32_t fixedAlt;
uint32_t fixedAltVar;
int8_t minElev;
uint8_t drLimit;
uint16_t pDOP;
uint16_t tDOP;
uint16_t pAcc;
uint16_t tAcc;
uint8_t staticHoldThresh;
uint8_t dgnssTimeout;
uint8_t cnoThreshNumSVs;
uint8_t cnoThresh;
uint8_t reserved0[2];
uint16_t staticHoldMaxDist;
uint8_t utcStandard;
uint8_t reserved1[5];
} ubxCfgNav5_t;
typedef union ubxPayload_s {
ubxPollMsg_t poll_msg;
ubxCfgMsg_t cfg_msg;
ubxCfgRate_t cfg_rate;
ubxCfgNav5_t cfg_nav5;
ubxCfgSbas_t cfg_sbas;
ubxCfgGnss_t cfg_gnss;
} ubxPayload_t;
typedef struct ubxMessage_s {
ubxHeader_t header;
ubxPayload_t payload;
} __attribute__((packed)) ubxMessage_t;
#endif // USE_GPS_UBLOX
typedef enum {
GPS_STATE_UNKNOWN,
GPS_STATE_INITIALIZING,
GPS_STATE_INITIALIZED,
GPS_STATE_CHANGE_BAUD,
GPS_STATE_CONFIGURE,
GPS_STATE_RECEIVING_DATA,
GPS_STATE_LOST_COMMUNICATION,
GPS_STATE_COUNT
} gpsState_e;
// Max time to wait for received data
#define GPS_MAX_WAIT_DATA_RX 30
gpsData_t gpsData;
static void shiftPacketLog(void)
{
uint32_t i;
for (i = ARRAYLEN(gpsPacketLog) - 1; i > 0 ; i--) {
gpsPacketLog[i] = gpsPacketLog[i-1];
}
}
static bool isConfiguratorConnected(void)
{
return (getArmingDisableFlags() & ARMING_DISABLED_MSP);
}
static void gpsNewData(uint16_t c);
#ifdef USE_GPS_NMEA
static bool gpsNewFrameNMEA(char c);
#endif
#ifdef USE_GPS_UBLOX
static bool gpsNewFrameUBLOX(uint8_t data);
#endif
static void gpsSetState(gpsState_e state)
{
gpsData.lastMessage = millis();
sensorsClear(SENSOR_GPS);
gpsData.state = state;
gpsData.state_position = 0;
gpsData.state_ts = millis();
gpsData.ackState = UBLOX_ACK_IDLE;
}
void gpsInit(void)
{
gpsSampleRateHz = 0.0f;
gpsData.baudrateIndex = 0;
gpsData.errors = 0;
gpsData.timeouts = 0;
memset(gpsPacketLog, 0x00, sizeof(gpsPacketLog));
// init gpsData structure. if we're not actually enabled, don't bother doing anything else
gpsSetState(GPS_STATE_UNKNOWN);
gpsData.lastMessage = millis();
if (gpsConfig()->provider == GPS_MSP) { // no serial ports used when GPS_MSP is configured
gpsSetState(GPS_STATE_INITIALIZED);
return;
}
const serialPortConfig_t *gpsPortConfig = findSerialPortConfig(FUNCTION_GPS);
if (!gpsPortConfig) {
return;
}
while (gpsInitData[gpsData.baudrateIndex].baudrateIndex != gpsPortConfig->gps_baudrateIndex) {
gpsData.baudrateIndex++;
if (gpsData.baudrateIndex >= GPS_INIT_DATA_ENTRY_COUNT) {
gpsData.baudrateIndex = DEFAULT_BAUD_RATE_INDEX;
break;
}
}
portMode_e mode = MODE_RXTX;
#if defined(GPS_NMEA_TX_ONLY)
if (gpsConfig()->provider == GPS_NMEA) {
mode &= ~MODE_TX;
}
#endif
// no callback - buffer will be consumed in gpsUpdate()
gpsPort = openSerialPort(gpsPortConfig->identifier, FUNCTION_GPS, NULL, NULL, baudRates[gpsInitData[gpsData.baudrateIndex].baudrateIndex], mode, SERIAL_NOT_INVERTED);
if (!gpsPort) {
return;
}
// signal GPS "thread" to initialize when it gets to it
gpsSetState(GPS_STATE_INITIALIZING);
}
#ifdef USE_GPS_NMEA
void gpsInitNmea(void)
{
static bool atgmRestartDone = false;
#if !defined(GPS_NMEA_TX_ONLY)
uint32_t now;
#endif
switch (gpsData.state) {
case GPS_STATE_INITIALIZING:
#if !defined(GPS_NMEA_TX_ONLY)
now = millis();
if (now - gpsData.state_ts < 1000) {
return;
}
gpsData.state_ts = now;
if (gpsData.state_position < 1) {
serialSetBaudRate(gpsPort, 4800);
gpsData.state_position++;
} else if (gpsData.state_position < 2) {
// print our FIXED init string for the baudrate we want to be at
serialPrint(gpsPort, "$PSRF100,1,115200,8,1,0*05\r\n");
gpsData.state_position++;
} else {
// we're now (hopefully) at the correct rate, next state will switch to it
gpsSetState(GPS_STATE_CHANGE_BAUD);
}
break;
#endif
case GPS_STATE_CHANGE_BAUD:
#if !defined(GPS_NMEA_TX_ONLY)
now = millis();
if (now - gpsData.state_ts < 1000) {
return;
}
gpsData.state_ts = now;
if (gpsData.state_position < 1) {
serialSetBaudRate(gpsPort, baudRates[gpsInitData[gpsData.baudrateIndex].baudrateIndex]);
gpsData.state_position++;
} else if (gpsData.state_position < 2) {
serialPrint(gpsPort, "$PSRF103,00,6,00,0*23\r\n");
// special initialization for NMEA ATGM336 and similar GPS recivers - should be done only once
if (!atgmRestartDone) {
atgmRestartDone = true;
serialPrint(gpsPort, "$PCAS02,100*1E\r\n"); // 10Hz refresh rate
serialPrint(gpsPort, "$PCAS10,0*1C\r\n"); // hot restart
}
gpsData.state_position++;
} else
#else
{
serialSetBaudRate(gpsPort, baudRates[gpsInitData[gpsData.baudrateIndex].baudrateIndex]);
}
#endif
gpsSetState(GPS_STATE_RECEIVING_DATA);
break;
}
}
#endif // USE_GPS_NMEA
#ifdef USE_GPS_UBLOX
static void ubloxSendByteUpdateChecksum(const uint8_t data, uint8_t *checksumA, uint8_t *checksumB)
{
*checksumA += data;
*checksumB += *checksumA;
serialWrite(gpsPort, data);
}
static void ubloxSendDataUpdateChecksum(const uint8_t *data, uint8_t len, uint8_t *checksumA, uint8_t *checksumB)
{
while (len--) {
ubloxSendByteUpdateChecksum(*data, checksumA, checksumB);
data++;
}
}
static void ubloxSendMessage(const uint8_t *data, uint8_t len)
{
uint8_t checksumA = 0, checksumB = 0;
serialWrite(gpsPort, data[0]);
serialWrite(gpsPort, data[1]);
ubloxSendDataUpdateChecksum(&data[2], len - 2, &checksumA, &checksumB);
serialWrite(gpsPort, checksumA);
serialWrite(gpsPort, checksumB);
// Save state for ACK waiting
gpsData.ackWaitingMsgId = data[3]; //save message id for ACK
gpsData.ackTimeoutCounter = 0;
gpsData.ackState = UBLOX_ACK_WAITING;
}
static void ubloxSendConfigMessage(ubxMessage_t *message, uint8_t msg_id, uint8_t length)
{
message->header.preamble1 = PREAMBLE1;
message->header.preamble2 = PREAMBLE2;
message->header.msg_class = CLASS_CFG;
message->header.msg_id = msg_id;
message->header.length = length;
ubloxSendMessage((const uint8_t *) message, length + 6);
}
static void ubloxSendPollMessage(uint8_t msg_id)
{
ubxMessage_t tx_buffer;
tx_buffer.header.preamble1 = PREAMBLE1;
tx_buffer.header.preamble2 = PREAMBLE2;
tx_buffer.header.msg_class = CLASS_CFG;
tx_buffer.header.msg_id = msg_id;
tx_buffer.header.length = 0;
ubloxSendMessage((const uint8_t *) &tx_buffer, 6);
}
static void ubloxSendNAV5Message(bool airborne)
{
ubxMessage_t tx_buffer;
tx_buffer.payload.cfg_nav5.mask = 0xFFFF;
if (airborne) {
#if defined(GPS_UBLOX_MODE_AIRBORNE_1G)
tx_buffer.payload.cfg_nav5.dynModel = UBLOX_DYNMODE_AIRBORNE_1G;
#else
tx_buffer.payload.cfg_nav5.dynModel = UBLOX_DYNMODE_AIRBORNE_4G;
#endif
} else {
tx_buffer.payload.cfg_nav5.dynModel = UBLOX_DYNMODE_PEDESTRIAN;
}
tx_buffer.payload.cfg_nav5.fixMode = 3;
tx_buffer.payload.cfg_nav5.fixedAlt = 0;
tx_buffer.payload.cfg_nav5.fixedAltVar = 10000;
tx_buffer.payload.cfg_nav5.minElev = 5;
tx_buffer.payload.cfg_nav5.drLimit = 0;
tx_buffer.payload.cfg_nav5.pDOP = 250;
tx_buffer.payload.cfg_nav5.tDOP = 250;
tx_buffer.payload.cfg_nav5.pAcc = 100;
tx_buffer.payload.cfg_nav5.tAcc = 300;
tx_buffer.payload.cfg_nav5.staticHoldThresh = 0;
tx_buffer.payload.cfg_nav5.dgnssTimeout = 60;
tx_buffer.payload.cfg_nav5.cnoThreshNumSVs = 0;
tx_buffer.payload.cfg_nav5.cnoThresh = 0;
tx_buffer.payload.cfg_nav5.reserved0[0] = 0;
tx_buffer.payload.cfg_nav5.reserved0[1] = 0;
tx_buffer.payload.cfg_nav5.staticHoldMaxDist = 200;
tx_buffer.payload.cfg_nav5.utcStandard = 0;
tx_buffer.payload.cfg_nav5.reserved1[0] = 0;
tx_buffer.payload.cfg_nav5.reserved1[1] = 0;
tx_buffer.payload.cfg_nav5.reserved1[2] = 0;
tx_buffer.payload.cfg_nav5.reserved1[3] = 0;
tx_buffer.payload.cfg_nav5.reserved1[4] = 0;
ubloxSendConfigMessage(&tx_buffer, MSG_CFG_NAV_SETTINGS, sizeof(ubxCfgNav5_t));
}
static void ubloxSetMessageRate(uint8_t messageClass, uint8_t messageID, uint8_t rate)
{
ubxMessage_t tx_buffer;
tx_buffer.payload.cfg_msg.msgClass = messageClass;
tx_buffer.payload.cfg_msg.msgID = messageID;
tx_buffer.payload.cfg_msg.rate = rate;
ubloxSendConfigMessage(&tx_buffer, MSG_CFG_MSG, sizeof(ubxCfgMsg_t));
}
static void ubloxSetNavRate(uint16_t measRate, uint16_t navRate, uint16_t timeRef)
{
ubxMessage_t tx_buffer;
tx_buffer.payload.cfg_rate.measRate = measRate;
tx_buffer.payload.cfg_rate.navRate = navRate;
tx_buffer.payload.cfg_rate.timeRef = timeRef;
ubloxSendConfigMessage(&tx_buffer, MSG_CFG_RATE, sizeof(ubxCfgRate_t));
}
static void ubloxSetSbas(void)
{
ubxMessage_t tx_buffer;
//NOTE: default ublox config for sbas mode is: UBLOX_MODE_ENABLED, test is disabled
tx_buffer.payload.cfg_sbas.mode = UBLOX_MODE_TEST;
if (gpsConfig()->sbasMode != SBAS_NONE) {
tx_buffer.payload.cfg_sbas.mode |= UBLOX_MODE_ENABLED;
}
//NOTE: default ublox config for sbas mode is: UBLOX_USAGE_RANGE | UBLOX_USAGE_DIFFCORR, integrity is disabled
tx_buffer.payload.cfg_sbas.usage = UBLOX_USAGE_RANGE | UBLOX_USAGE_DIFFCORR;
if (gpsConfig()->sbas_integrity) {
tx_buffer.payload.cfg_sbas.usage |= UBLOX_USAGE_INTEGRITY;
}
tx_buffer.payload.cfg_sbas.maxSBAS = 3;
tx_buffer.payload.cfg_sbas.scanmode2 = 0;
switch (gpsConfig()->sbasMode) {
case SBAS_AUTO:
tx_buffer.payload.cfg_sbas.scanmode1 = 0;
break;
case SBAS_EGNOS:
tx_buffer.payload.cfg_sbas.scanmode1 = 0x00010048; //PRN123, PRN126, PRN136
break;
case SBAS_WAAS:
tx_buffer.payload.cfg_sbas.scanmode1 = 0x0004A800; //PRN131, PRN133, PRN135, PRN138
break;
case SBAS_MSAS:
tx_buffer.payload.cfg_sbas.scanmode1 = 0x00020200; //PRN129, PRN137
break;
case SBAS_GAGAN:
tx_buffer.payload.cfg_sbas.scanmode1 = 0x00001180; //PRN127, PRN128, PRN132
break;
default:
tx_buffer.payload.cfg_sbas.scanmode1 = 0;
break;
}
ubloxSendConfigMessage(&tx_buffer, MSG_CFG_SBAS, sizeof(ubxCfgSbas_t));
}
void gpsInitUblox(void)
{
uint32_t now;
// UBX will run at the serial port's baudrate, it shouldn't be "autodetected". So here we force it to that rate
// Wait until GPS transmit buffer is empty
if (!isSerialTransmitBufferEmpty(gpsPort))
return;
switch (gpsData.state) {
case GPS_STATE_INITIALIZING:
now = millis();
if (now - gpsData.state_ts < GPS_BAUDRATE_CHANGE_DELAY)
return;
if (gpsData.state_position < GPS_INIT_ENTRIES) {
// try different speed to INIT
baudRate_e newBaudRateIndex = gpsInitData[gpsData.state_position].baudrateIndex;
gpsData.state_ts = now;
if (lookupBaudRateIndex(serialGetBaudRate(gpsPort)) != newBaudRateIndex) {
// change the rate if needed and wait a little
serialSetBaudRate(gpsPort, baudRates[newBaudRateIndex]);
#if DEBUG_SERIAL_BAUD
debug[0] = baudRates[newBaudRateIndex] / 100;
#endif
return;
}
// print our FIXED init string for the baudrate we want to be at
serialPrint(gpsPort, gpsInitData[gpsData.baudrateIndex].ubx);
gpsData.state_position++;
} else {
// we're now (hopefully) at the correct rate, next state will switch to it
gpsSetState(GPS_STATE_CHANGE_BAUD);
}
break;
case GPS_STATE_CHANGE_BAUD:
serialSetBaudRate(gpsPort, baudRates[gpsInitData[gpsData.baudrateIndex].baudrateIndex]);
#if DEBUG_SERIAL_BAUD
debug[0] = baudRates[gpsInitData[gpsData.baudrateIndex].baudrateIndex] / 100;
#endif
gpsSetState(GPS_STATE_CONFIGURE);
break;
case GPS_STATE_CONFIGURE:
// Either use specific config file for GPS or let dynamically upload config
if (gpsConfig()->autoConfig == GPS_AUTOCONFIG_OFF) {
gpsSetState(GPS_STATE_RECEIVING_DATA);
break;
}
if (gpsData.ackState == UBLOX_ACK_IDLE) {
switch (gpsData.state_position) {
case 0:
gpsData.ubloxUsePVT = true;
gpsData.ubloxUseSAT = true;
ubloxSendNAV5Message(gpsConfig()->gps_ublox_mode == UBLOX_AIRBORNE);
break;
case 1: //Disable NMEA Messages
ubloxSetMessageRate(0xF0, 0x05, 0); // VGS: Course over ground and Ground speed
break;
case 2:
ubloxSetMessageRate(0xF0, 0x03, 0); // GSV: GNSS Satellites in View
break;
case 3:
ubloxSetMessageRate(0xF0, 0x01, 0); // GLL: Latitude and longitude, with time of position fix and status
break;
case 4:
ubloxSetMessageRate(0xF0, 0x00, 0); // GGA: Global positioning system fix data
break;
case 5:
ubloxSetMessageRate(0xF0, 0x02, 0); // GSA: GNSS DOP and Active Satellites
break;
case 6:
ubloxSetMessageRate(0xF0, 0x04, 0); // RMC: Recommended Minimum data
break;
case 7: //Enable UBLOX Messages
if (gpsData.ubloxUsePVT) {
ubloxSetMessageRate(CLASS_NAV, MSG_PVT, 1); // set PVT MSG rate
} else {
ubloxSetMessageRate(CLASS_NAV, MSG_SOL, 1); // set SOL MSG rate
}
break;
case 8:
if (gpsData.ubloxUsePVT) {
gpsData.state_position++;
} else {
ubloxSetMessageRate(CLASS_NAV, MSG_POSLLH, 1); // set POSLLH MSG rate
}
break;
case 9:
if (gpsData.ubloxUsePVT) {
gpsData.state_position++;
} else {
ubloxSetMessageRate(CLASS_NAV, MSG_STATUS, 1); // set STATUS MSG rate
}
break;
case 10:
if (gpsData.ubloxUsePVT) {
gpsData.state_position++;
} else {
ubloxSetMessageRate(CLASS_NAV, MSG_VELNED, 1); // set VELNED MSG rate
}
break;
case 11:
if (gpsData.ubloxUseSAT) {
ubloxSetMessageRate(CLASS_NAV, MSG_SAT, 5); // set SAT MSG rate (every 5 cycles)
} else {
ubloxSetMessageRate(CLASS_NAV, MSG_SVINFO, 5); // set SVINFO MSG rate (every 5 cycles)
}
break;
case 12:
ubloxSetMessageRate(CLASS_NAV, MSG_DOP, 1); // set DOP MSG rate
break;
case 13:
ubloxSetNavRate(0x64, 1, 1); // set rate to 10Hz (measurement period: 100ms, navigation rate: 1 cycle) (for 5Hz use 0xC8)
break;
case 14:
ubloxSetSbas();
break;
case 15:
if ((gpsConfig()->sbasMode == SBAS_NONE) || (gpsConfig()->gps_ublox_use_galileo)) {
ubloxSendPollMessage(MSG_CFG_GNSS);
} else {
gpsSetState(GPS_STATE_RECEIVING_DATA);
}
break;
default:
break;
}
}
switch (gpsData.ackState) {
case UBLOX_ACK_IDLE:
break;
case UBLOX_ACK_WAITING:
if ((++gpsData.ackTimeoutCounter) == UBLOX_ACK_TIMEOUT_MAX_COUNT) {
gpsSetState(GPS_STATE_LOST_COMMUNICATION);
}
break;
case UBLOX_ACK_GOT_ACK:
if (gpsData.state_position == 15) {
// ublox should be initialised, try receiving
gpsSetState(GPS_STATE_RECEIVING_DATA);
} else {
gpsData.state_position++;
gpsData.ackState = UBLOX_ACK_IDLE;
}
break;
case UBLOX_ACK_GOT_NACK:
if (gpsData.state_position == 7) { // If we were asking for NAV-PVT...
gpsData.ubloxUsePVT = false; // ...retry asking for NAV-SOL
gpsData.ackState = UBLOX_ACK_IDLE;
} else {
if (gpsData.state_position == 11) { // If we were asking for NAV-SAT...
gpsData.ubloxUseSAT = false; // ...retry asking for NAV-SVINFO
gpsData.ackState = UBLOX_ACK_IDLE;
} else {
gpsSetState(GPS_STATE_CONFIGURE);
}
}
break;
}
break;
}
}
#endif // USE_GPS_UBLOX
void gpsInitHardware(void)
{
switch (gpsConfig()->provider) {
case GPS_NMEA:
#ifdef USE_GPS_NMEA
gpsInitNmea();
#endif
break;
case GPS_UBLOX:
#ifdef USE_GPS_UBLOX
gpsInitUblox();
#endif
break;
default:
break;
}
}
static void updateGpsIndicator(timeUs_t currentTimeUs)
{
static uint32_t GPSLEDTime;
if ((int32_t)(currentTimeUs - GPSLEDTime) >= 0 && STATE(GPS_FIX) && (gpsSol.numSat >= gpsRescueConfig()->minSats)) {
GPSLEDTime = currentTimeUs + 150000;
LED1_TOGGLE;
}
}
void gpsUpdate(timeUs_t currentTimeUs)
{
static gpsState_e gpsStateDurationUs[GPS_STATE_COUNT];
timeUs_t executeTimeUs;
gpsState_e gpsCurrentState = gpsData.state;
// read out available GPS bytes
if (gpsPort) {
while (serialRxBytesWaiting(gpsPort)) {
if (cmpTimeUs(micros(), currentTimeUs) > GPS_MAX_WAIT_DATA_RX) {
// Wait 1ms and come back
rescheduleTask(TASK_SELF, TASK_PERIOD_HZ(TASK_GPS_RATE_FAST));
return;
}
gpsNewData(serialRead(gpsPort));
}
// Restore default task rate
rescheduleTask(TASK_SELF, TASK_PERIOD_HZ(TASK_GPS_RATE));
} else if (GPS_update & GPS_MSP_UPDATE) { // GPS data received via MSP
gpsSetState(GPS_STATE_RECEIVING_DATA);
onGpsNewData();
GPS_update &= ~GPS_MSP_UPDATE;
}
#if DEBUG_UBLOX_INIT
debug[0] = gpsData.state;
debug[1] = gpsData.state_position;
debug[2] = gpsData.ackState;
#endif
switch (gpsData.state) {
case GPS_STATE_UNKNOWN:
case GPS_STATE_INITIALIZED:
break;
case GPS_STATE_INITIALIZING:
case GPS_STATE_CHANGE_BAUD:
case GPS_STATE_CONFIGURE:
gpsInitHardware();
break;
case GPS_STATE_LOST_COMMUNICATION:
gpsData.timeouts++;
if (gpsConfig()->autoBaud) {
// try another rate
gpsData.baudrateIndex++;
gpsData.baudrateIndex %= GPS_INIT_ENTRIES;
}
gpsSol.numSat = 0;
DISABLE_STATE(GPS_FIX);
gpsSetState(GPS_STATE_INITIALIZING);
break;
case GPS_STATE_RECEIVING_DATA:
// check for no data/gps timeout/cable disconnection etc
if (millis() - gpsData.lastMessage > GPS_TIMEOUT) {
gpsSetState(GPS_STATE_LOST_COMMUNICATION);
#ifdef USE_GPS_UBLOX
} else {
if (gpsConfig()->autoConfig == GPS_AUTOCONFIG_ON) { // Only if autoconfig is enabled
switch (gpsData.state_position) {
case 0:
if (!isConfiguratorConnected()) {
if (gpsData.ubloxUseSAT) {
ubloxSetMessageRate(CLASS_NAV, MSG_SAT, 0); // disable SAT MSG
} else {
ubloxSetMessageRate(CLASS_NAV, MSG_SVINFO, 0); // disable SVINFO MSG
}
gpsData.state_position = 1;
}
break;
case 1:
if (STATE(GPS_FIX) && (gpsConfig()->gps_ublox_mode == UBLOX_DYNAMIC)) {
ubloxSendNAV5Message(true);
gpsData.state_position = 2;
}
if (isConfiguratorConnected()) {
gpsData.state_position = 2;
}
break;
case 2:
if (isConfiguratorConnected()) {
if (gpsData.ubloxUseSAT) {
ubloxSetMessageRate(CLASS_NAV, MSG_SAT, 5); // set SAT MSG rate (every 5 cycles)
} else {
ubloxSetMessageRate(CLASS_NAV, MSG_SVINFO, 5); // set SVINFO MSG rate (every 5 cycles)
}
gpsData.state_position = 0;
}
break;
}
}
#endif //USE_GPS_UBLOX
}
break;
}
if (sensors(SENSOR_GPS)) {
updateGpsIndicator(currentTimeUs);
}
if (!ARMING_FLAG(ARMED) && !gpsConfig()->gps_set_home_point_once) {
// clear the home fix icon between arms if the user configuration is to reset home point between arms
DISABLE_STATE(GPS_FIX_HOME);
}
static bool hasBeeped = false;
if (!ARMING_FLAG(ARMED)) {
// while disarmed, beep when requirements for a home fix are met
// ?? should we also beep if home fix requirements first appear after arming?
if (!hasBeeped && STATE(GPS_FIX) && gpsSol.numSat >= gpsRescueConfig()->minSats) {
beeper(BEEPER_READY_BEEP);
hasBeeped = true;
}
}
DEBUG_SET(DEBUG_GPS_DOP, 0, gpsSol.numSat);
DEBUG_SET(DEBUG_GPS_DOP, 1, gpsSol.dop.pdop);
DEBUG_SET(DEBUG_GPS_DOP, 2, gpsSol.dop.hdop);
DEBUG_SET(DEBUG_GPS_DOP, 3, gpsSol.dop.vdop);
executeTimeUs = micros() - currentTimeUs;
if (executeTimeUs > gpsStateDurationUs[gpsCurrentState]) {
gpsStateDurationUs[gpsCurrentState] = executeTimeUs;
}
schedulerSetNextStateTime(gpsStateDurationUs[gpsData.state]);
}
static void gpsNewData(uint16_t c)
{
if (!gpsNewFrame(c)) {
return;
}
if (gpsData.state == GPS_STATE_RECEIVING_DATA) {
// new data received and parsed, we're in business
gpsData.lastLastMessage = gpsData.lastMessage;
gpsData.lastMessage = millis();
sensorsSet(SENSOR_GPS);
}
GPS_update ^= GPS_DIRECT_TICK;
#if DEBUG_UBLOX_INIT
debug[3] = GPS_update;
#endif
onGpsNewData();
}
bool gpsNewFrame(uint8_t c)
{
switch (gpsConfig()->provider) {
case GPS_NMEA: // NMEA
#ifdef USE_GPS_NMEA
return gpsNewFrameNMEA(c);
#endif
break;
case GPS_UBLOX: // UBX binary
#ifdef USE_GPS_UBLOX
return gpsNewFrameUBLOX(c);
#endif
break;
default:
break;
}
return false;
}
// Check for healthy communications
bool gpsIsHealthy(void)
{
return (gpsData.state == GPS_STATE_RECEIVING_DATA);
}
/* This is a light implementation of a GPS frame decoding
This should work with most of modern GPS devices configured to output 5 frames.
It assumes there are some NMEA GGA frames to decode on the serial bus
Now verifies checksum correctly before applying data
Here we use only the following data :
- latitude
- longitude
- GPS fix is/is not ok
- GPS num sat (4 is enough to be +/- reliable)
// added by Mis
- GPS altitude (for OSD displaying)
- GPS speed (for OSD displaying)
*/
#define NO_FRAME 0
#define FRAME_GGA 1
#define FRAME_RMC 2
#define FRAME_GSV 3
#define FRAME_GSA 4
// This code is used for parsing NMEA data
/* Alex optimization
The latitude or longitude is coded this way in NMEA frames
dm.f coded as degrees + minutes + minute decimal
Where:
- d can be 1 or more char long. generally: 2 char long for latitude, 3 char long for longitude
- m is always 2 char long
- f can be 1 or more char long
This function converts this format in a unique unsigned long where 1 degree = 10 000 000
EOS increased the precision here, even if we think that the gps is not precise enough, with 10e5 precision it has 76cm resolution
with 10e7 it's around 1 cm now. Increasing it further is irrelevant, since even 1cm resolution is unrealistic, however increased
resolution also increased precision of nav calculations
static uint32_t GPS_coord_to_degrees(char *coordinateString)
{
char *p = s, *d = s;
uint8_t min, deg = 0;
uint16_t frac = 0, mult = 10000;
while (*p) { // parse the string until its end
if (d != s) {
frac += (*p - '0') * mult; // calculate only fractional part on up to 5 digits (d != s condition is true when the . is located)
mult /= 10;
}
if (*p == '.')
d = p; // locate '.' char in the string
p++;
}
if (p == s)
return 0;
while (s < d - 2) {
deg *= 10; // convert degrees : all chars before minutes ; for the first iteration, deg = 0
deg += *(s++) - '0';
}