forked from cyoung/stratux
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathgps.go
2140 lines (1831 loc) · 76.7 KB
/
gps.go
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
/*
Copyright (c) 2015-2016 Christopher Young
Distributable under the terms of The "BSD New" License
that can be found in the LICENSE file, herein included
as part of this header.
gps.go: GPS functions, GPS init, AHRS status messages, other external sensor monitoring.
*/
package main
import (
"fmt"
"log"
"math"
"strconv"
"strings"
"sync"
"time"
"bufio"
"github.com/tarm/serial"
"os"
"os/exec"
)
const (
SAT_TYPE_UNKNOWN = 0 // default type
SAT_TYPE_GPS = 1 // GPxxx; NMEA IDs 1-32
SAT_TYPE_GLONASS = 2 // GLxxx; NMEA IDs 65-88
SAT_TYPE_GALILEO = 3 // GAxxx; NMEA IDs
SAT_TYPE_BEIDOU = 4 // GBxxx; NMEA IDs 201-235
SAT_TYPE_SBAS = 10 // NMEA IDs 33-54
)
type SatelliteInfo struct {
SatelliteNMEA uint8 // NMEA ID of the satellite. 1-32 is GPS, 33-54 is SBAS, 65-88 is Glonass.
SatelliteID string // Formatted code indicating source and PRN code. e.g. S138==WAAS satellite 138, G2==GPS satellites 2
Elevation int16 // Angle above local horizon, -xx to +90
Azimuth int16 // Bearing (degrees true), 0-359
Signal int8 // Signal strength, 0 - 99; -99 indicates no reception
Type uint8 // Type of satellite (GPS, GLONASS, Galileo, SBAS)
TimeLastSolution time.Time // Time (system ticker) a solution was last calculated using this satellite
TimeLastSeen time.Time // Time (system ticker) a signal was last received from this satellite
TimeLastTracked time.Time // Time (system ticker) this satellite was tracked (almanac data)
InSolution bool // True if satellite is used in the position solution (reported by GSA message or PUBX,03)
}
type SituationData struct {
// From GPS.
muGPS *sync.Mutex
muGPSPerformance *sync.Mutex
muSatellite *sync.Mutex
GPSLastFixSinceMidnightUTC float32
GPSLatitude float32
GPSLongitude float32
GPSFixQuality uint8
GPSHeightAboveEllipsoid float32 // GPS height above WGS84 ellipsoid, ft. This is specified by the GDL90 protocol, but most EFBs use MSL altitude instead. HAE is about 70-100 ft below GPS MSL altitude over most of the US.
GPSGeoidSep float32 // geoid separation, ft, MSL minus HAE (used in altitude calculation)
GPSSatellites uint16 // satellites used in solution
GPSSatellitesTracked uint16 // satellites tracked (almanac data received)
GPSSatellitesSeen uint16 // satellites seen (signal received)
GPSHorizontalAccuracy float32 // 95% confidence for horizontal position, meters.
GPSNACp uint8 // NACp categories are defined in AC 20-165A
GPSAltitudeMSL float32 // Feet MSL
GPSVerticalAccuracy float32 // 95% confidence for vertical position, meters
GPSVerticalSpeed float32 // GPS vertical velocity, feet per second
GPSLastFixLocalTime time.Time
GPSTrueCourse float32
GPSTurnRate float64 // calculated GPS rate of turn, degrees per second
GPSGroundSpeed float64
GPSLastGroundTrackTime time.Time
GPSTime time.Time
GPSLastGPSTimeStratuxTime time.Time // stratuxClock time since last GPS time received.
GPSLastValidNMEAMessageTime time.Time // time valid NMEA message last seen
GPSLastValidNMEAMessage string // last NMEA message processed.
GPSPositionSampleRate float64 // calculated sample rate of GPS positions
// From pressure sensor.
muBaro *sync.Mutex
BaroTemperature float32
BaroPressureAltitude float32
BaroVerticalSpeed float32
BaroLastMeasurementTime time.Time
// From AHRS source.
muAttitude *sync.Mutex
AHRSPitch float64
AHRSRoll float64
AHRSGyroHeading float64
AHRSMagHeading float64
AHRSSlipSkid float64
AHRSTurnRate float64
AHRSGLoad float64
AHRSGLoadMin float64
AHRSGLoadMax float64
AHRSLastAttitudeTime time.Time
AHRSStatus uint8
}
/*
myGPSPerfStats used to track short-term position / velocity trends, used to feed dynamic AHRS model. Use floats for better resolution of calculated data.
*/
type gpsPerfStats struct {
stratuxTime uint64 // time since Stratux start, msec
nmeaTime float32 // timestamp from NMEA message
msgType string // NMEA message type
gsf float32 // knots
coursef float32 // true course [degrees]
alt float32 // gps altitude, ft msl
vv float32 // vertical velocity, ft/sec
gpsTurnRate float64 // calculated turn rate, deg/sec. Right turn is positive.
gpsPitch float64 // estimated pitch angle, deg. Calculated from gps ground speed and VV. Equal to flight path angle.
gpsRoll float64 // estimated roll angle from turn rate and groundspeed, deg. Assumes airplane in coordinated turns.
gpsLoadFactor float64 // estimated load factor from turn rate and groundspeed, "gee". Assumes airplane in coordinated turns.
//TODO: valid/invalid flag.
}
var gpsPerf gpsPerfStats
var myGPSPerfStats []gpsPerfStats
var serialConfig *serial.Config
var serialPort *serial.Port
var readyToInitGPS bool //TODO: replace with channel control to terminate goroutine when complete
var Satellites map[string]SatelliteInfo
/*
u-blox5_Referenzmanual.pdf
Platform settings
Airborne <2g Recommended for typical airborne environment. No 2D position fixes supported.
p.91 - CFG-MSG
Navigation/Measurement Rate Settings
Header 0xB5 0x62
ID 0x06 0x08
0x0064 (100 ms)
0x0001
0x0001 (GPS time)
{0xB5, 0x62, 0x06, 0x08, 0x00, 0x64, 0x00, 0x01, 0x00, 0x01}
p.109 CFG-NAV5 (0x06 0x24)
Poll Navigation Engine Settings
*/
/*
chksumUBX()
returns the two-byte Fletcher algorithm checksum of byte array msg.
This is used in configuration messages for the u-blox GPS. See p. 97 of the
u-blox M8 Receiver Description.
*/
func chksumUBX(msg []byte) []byte {
ret := make([]byte, 2)
for i := 0; i < len(msg); i++ {
ret[0] = ret[0] + msg[i]
ret[1] = ret[1] + ret[0]
}
return ret
}
/*
makeUBXCFG()
creates a UBX-formatted package consisting of two sync characters,
class, ID, payload length in bytes (2-byte little endian), payload, and checksum.
See p. 95 of the u-blox M8 Receiver Description.
*/
func makeUBXCFG(class, id byte, msglen uint16, msg []byte) []byte {
ret := make([]byte, 6)
ret[0] = 0xB5
ret[1] = 0x62
ret[2] = class
ret[3] = id
ret[4] = byte(msglen & 0xFF)
ret[5] = byte((msglen >> 8) & 0xFF)
ret = append(ret, msg...)
chk := chksumUBX(ret[2:])
ret = append(ret, chk[0])
ret = append(ret, chk[1])
return ret
}
func makeNMEACmd(cmd string) []byte {
chk_sum := byte(0)
for i := range cmd {
chk_sum = chk_sum ^ byte(cmd[i])
}
return []byte(fmt.Sprintf("$%s*%02x\x0d\x0a", cmd, chk_sum))
}
func initGPSSerial() bool {
var device string
baudrate := int(9600)
isSirfIV := bool(false)
globalStatus.GPS_detected_type = 0 // reset detected type on each initialization
if _, err := os.Stat("/dev/ublox9"); err == nil { // u-blox 8 (RY83xAI over USB).
device = "/dev/ublox9"
globalStatus.GPS_detected_type = GPS_TYPE_UBX9
} else if _, err := os.Stat("/dev/ublox8"); err == nil { // u-blox 8 (RY83xAI or GPYes 2.0).
device = "/dev/ublox8"
globalStatus.GPS_detected_type = GPS_TYPE_UBX8
} else if _, err := os.Stat("/dev/ublox7"); err == nil { // u-blox 7 (VK-172, VK-162 Rev 2, GPYes, RY725AI over USB).
device = "/dev/ublox7"
globalStatus.GPS_detected_type = GPS_TYPE_UBX7
} else if _, err := os.Stat("/dev/ublox6"); err == nil { // u-blox 6 (VK-162 Rev 1).
device = "/dev/ublox6"
globalStatus.GPS_detected_type = GPS_TYPE_UBX6
} else if _, err := os.Stat("/dev/prolific0"); err == nil { // Assume it's a BU-353-S4 SIRF IV.
//TODO: Check a "serialout" flag and/or deal with multiple prolific devices.
isSirfIV = true
baudrate = 4800
device = "/dev/prolific0"
globalStatus.GPS_detected_type = GPS_TYPE_PROLIFIC
} else if _, err := os.Stat("/dev/ttyAMA0"); err == nil { // ttyAMA0 is PL011 UART (GPIO pins 8 and 10) on all RPi.
device = "/dev/ttyAMA0"
globalStatus.GPS_detected_type = GPS_TYPE_UART
} else {
if globalSettings.DEBUG {
log.Printf("No GPS device found.\n")
}
return false
}
if globalSettings.DEBUG {
log.Printf("Using %s for GPS\n", device)
}
// Open port at default baud for config.
serialConfig = &serial.Config{Name: device, Baud: baudrate}
p, err := serial.OpenPort(serialConfig)
if err != nil {
log.Printf("serial port err: %s\n", err.Error())
return false
}
if isSirfIV {
log.Printf("Using SiRFIV config.\n")
// Enable 38400 baud.
p.Write(makeNMEACmd("PSRF100,1,38400,8,1,0"))
baudrate = 38400
p.Close()
time.Sleep(250 * time.Millisecond)
// Re-open port at newly configured baud so we can configure 5Hz messages.
serialConfig = &serial.Config{Name: device, Baud: baudrate}
p, err = serial.OpenPort(serialConfig)
// Enable 5Hz. (To switch back to 1Hz: $PSRF103,00,7,00,0*22)
p.Write(makeNMEACmd("PSRF103,00,6,00,0"))
// Enable GGA.
p.Write(makeNMEACmd("PSRF103,00,00,01,01"))
// Enable GSA.
p.Write(makeNMEACmd("PSRF103,02,00,01,01"))
// Enable RMC.
p.Write(makeNMEACmd("PSRF103,04,00,01,01"))
// Enable VTG.
p.Write(makeNMEACmd("PSRF103,05,00,01,01"))
// Enable GSV (once every 5 position updates)
p.Write(makeNMEACmd("PSRF103,03,00,05,01"))
if globalSettings.DEBUG {
log.Printf("Finished writing SiRF GPS config to %s. Opening port to test connection.\n", device)
}
} else {
// Byte order for UBX configuration is little endian.
// Set 10 Hz update to make gpsattitude more responsive for ublox7.
updatespeed := []byte{0x64, 0x00, 0x01, 0x00, 0x01, 0x00} // 10 Hz
// Set navigation settings.
nav := make([]byte, 36)
nav[0] = 0x05 // Set dyn and fixMode only.
nav[1] = 0x00
// dyn.
nav[2] = 0x07 // "Airborne with >2g Acceleration".
nav[3] = 0x02 // 3D only.
p.Write(makeUBXCFG(0x06, 0x24, 36, nav))
// Turn off "time pulse" (usually drives an LED).
tp5 := make([]byte, 32)
tp5[4] = 0x32
tp5[8] = 0x40
tp5[9] = 0x42
tp5[10] = 0x0F
tp5[12] = 0x40
tp5[13] = 0x42
tp5[14] = 0x0F
tp5[28] = 0xE7
p.Write(makeUBXCFG(0x06, 0x31, 32, tp5))
// GNSS configuration CFG-GNSS for ublox 7 higher, p. 125 (v8)
// Notes: ublox8 is multi-GNSS capable (simultaneous decoding of GPS and GLONASS, or
// GPS and Galileo) if SBAS (e.g. WAAS) is unavailable. This may provide robustness
// against jamming / interference on one set of frequencies. However, this will drop the
// position reporting rate to 5 Hz during times multi-GNSS is in use. This shouldn't affect
// gpsattitude too much -- without WAAS corrections, the algorithm could get jumpy at higher
// sampling rates.
cfgGnss := []byte{0x00, 0x20, 0x20, 0x06}
gps := []byte{0x00, 0x08, 0x10, 0x00, 0x01, 0x00, 0x01, 0x01} // enable GPS with 8-16 tracking channels
sbas := []byte{0x01, 0x02, 0x03, 0x00, 0x01, 0x00, 0x01, 0x01} // enable SBAS (WAAS) with 2-3 tracking channels
beidou := []byte{0x03, 0x00, 0x10, 0x00, 0x00, 0x00, 0x01, 0x01}
qzss := []byte{0x05, 0x00, 0x03, 0x00, 0x00, 0x00, 0x01, 0x01}
glonass := []byte{0x06, 0x04, 0x0E, 0x00, 0x00, 0x00, 0x01, 0x01} // this disables GLONASS
galileo := []byte{0x02, 0x04, 0x08, 0x00, 0x00, 0x00, 0x01, 0x01} // this disables Galileo
if (globalStatus.GPS_detected_type == GPS_TYPE_UBX8) || (globalStatus.GPS_detected_type == GPS_TYPE_UBX9) || (globalStatus.GPS_detected_type == GPS_TYPE_UART) { // assume that any GPS connected to serial GPIO is ublox8 (RY835/6AI)
if globalSettings.DEBUG {
log.Printf("UBX8/9/unknown device detected on USB, or GPS serial connection in use. Attempting GLONASS and Galelio configuration.\n")
}
glonass = []byte{0x06, 0x08, 0x0E, 0x00, 0x01, 0x00, 0x01, 0x01} // this enables GLONASS with 8-14 tracking channels
galileo = []byte{0x02, 0x04, 0x08, 0x00, 0x01, 0x00, 0x01, 0x01} // this enables Galileo with 4-8 tracking channels
updatespeed = []byte{0x06, 0x00, 0xF4, 0x01, 0x01, 0x00} // Nav speed 2Hz
}
cfgGnss = append(cfgGnss, gps...)
cfgGnss = append(cfgGnss, sbas...)
cfgGnss = append(cfgGnss, beidou...)
cfgGnss = append(cfgGnss, qzss...)
cfgGnss = append(cfgGnss, glonass...)
cfgGnss = append(cfgGnss, galileo...)
p.Write(makeUBXCFG(0x06, 0x3E, uint16(len(cfgGnss)), cfgGnss))
// SBAS configuration for ublox 6 and higher
p.Write(makeUBXCFG(0x06, 0x16, 8, []byte{0x01, 0x07, 0x03, 0x00, 0x00, 0x00, 0x00, 0x00}))
//Navigation Rate 10Hz for <= UBX7 2Hz for UBX8
p.Write(makeUBXCFG(0x06, 0x08, 6, updatespeed))
// Message output configuration: UBX,00 (position) on each calculated fix; UBX,03 (satellite info) every 5th fix,
// UBX,04 (timing) every 10th, GGA (NMEA position) every 5th. All other NMEA messages disabled.
// Msg DDC UART1 UART2 USB I2C Res
p.Write(makeUBXCFG(0x06, 0x01, 8, []byte{0xF0, 0x00, 0x00, 0x05, 0x00, 0x05, 0x00, 0x01})) // GGA enabled every 5th message
p.Write(makeUBXCFG(0x06, 0x01, 8, []byte{0xF0, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01})) // GLL disabled
p.Write(makeUBXCFG(0x06, 0x01, 8, []byte{0xF0, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01})) // GSA disabled
p.Write(makeUBXCFG(0x06, 0x01, 8, []byte{0xF0, 0x03, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01})) // GSV disabled
p.Write(makeUBXCFG(0x06, 0x01, 8, []byte{0xF0, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01})) // RMC
p.Write(makeUBXCFG(0x06, 0x01, 8, []byte{0xF0, 0x05, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01})) // VGT
p.Write(makeUBXCFG(0x06, 0x01, 8, []byte{0xF0, 0x06, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00})) // GRS
p.Write(makeUBXCFG(0x06, 0x01, 8, []byte{0xF0, 0x07, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00})) // GST
p.Write(makeUBXCFG(0x06, 0x01, 8, []byte{0xF0, 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00})) // ZDA
p.Write(makeUBXCFG(0x06, 0x01, 8, []byte{0xF0, 0x09, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00})) // GBS
p.Write(makeUBXCFG(0x06, 0x01, 8, []byte{0xF0, 0x0A, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00})) // DTM
p.Write(makeUBXCFG(0x06, 0x01, 8, []byte{0xF0, 0x0D, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00})) // GNS
p.Write(makeUBXCFG(0x06, 0x01, 8, []byte{0xF0, 0x0E, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00})) // ???
p.Write(makeUBXCFG(0x06, 0x01, 8, []byte{0xF0, 0x0F, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00})) // VLW
p.Write(makeUBXCFG(0x06, 0x01, 8, []byte{0xF1, 0x00, 0x00, 0x01, 0x00, 0x01, 0x00, 0x00})) // Ublox,0
p.Write(makeUBXCFG(0x06, 0x01, 8, []byte{0xF1, 0x03, 0x00, 0x05, 0x00, 0x05, 0x00, 0x00})) // Ublox,3
p.Write(makeUBXCFG(0x06, 0x01, 8, []byte{0xF1, 0x04, 0x00, 0x0A, 0x00, 0x0A, 0x00, 0x00})) // Ublox,4
// Reconfigure serial port.
cfg := make([]byte, 20)
cfg[0] = 0x01 // portID.
cfg[1] = 0x00 // res0.
cfg[2] = 0x00 // res1.
cfg[3] = 0x00 // res1.
// [ 7 ] [ 6 ] [ 5 ] [ 4 ]
// 0000 0000 0000 0000 0000 10x0 1100 0000
// UART mode. 0 stop bits, no parity, 8 data bits. Little endian order.
cfg[4] = 0xC0
cfg[5] = 0x08
cfg[6] = 0x00
cfg[7] = 0x00
// Baud rate. Little endian order.
bdrt := uint32(38400)
cfg[11] = byte((bdrt >> 24) & 0xFF)
cfg[10] = byte((bdrt >> 16) & 0xFF)
cfg[9] = byte((bdrt >> 8) & 0xFF)
cfg[8] = byte(bdrt & 0xFF)
// inProtoMask. NMEA and UBX. Little endian.
cfg[12] = 0x03
cfg[13] = 0x00
// outProtoMask. NMEA. Little endian.
cfg[14] = 0x02
cfg[15] = 0x00
cfg[16] = 0x00 // flags.
cfg[17] = 0x00 // flags.
cfg[18] = 0x00 //pad.
cfg[19] = 0x00 //pad.
p.Write(makeUBXCFG(0x06, 0x00, 20, cfg))
// time.Sleep(100* time.Millisecond) // pause and wait for the GPS to finish configuring itself before closing / reopening the port
baudrate = 38400
if globalSettings.DEBUG {
log.Printf("Finished writing u-blox GPS config to %s. Opening port to test connection.\n", device)
}
}
p.Close()
time.Sleep(250 * time.Millisecond)
// Re-open port at newly configured baud so we can read messages. ReadTimeout is set to keep from blocking the gpsSerialReader() on misconfigures or ttyAMA disconnects
serialConfig = &serial.Config{Name: device, Baud: baudrate, ReadTimeout: time.Millisecond * 2500}
p, err = serial.OpenPort(serialConfig)
if err != nil {
log.Printf("serial port err: %s\n", err.Error())
return false
}
serialPort = p
return true
}
// func validateNMEAChecksum determines if a string is a properly formatted NMEA sentence with a valid checksum.
//
// If the input string is valid, output is the input stripped of the "$" token and checksum, along with a boolean 'true'
// If the input string is the incorrect format, the checksum is missing/invalid, or checksum calculation fails, an error string and
// boolean 'false' are returned
//
// Checksum is calculated as XOR of all bytes between "$" and "*"
func validateNMEAChecksum(s string) (string, bool) {
//validate format. NMEA sentences start with "$" and end in "*xx" where xx is the XOR value of all bytes between
if !(strings.HasPrefix(s, "$") && strings.Contains(s, "*")) {
return "Invalid NMEA message", false
}
// strip leading "$" and split at "*"
s_split := strings.Split(strings.TrimPrefix(s, "$"), "*")
s_out := s_split[0]
s_cs := s_split[1]
if len(s_cs) < 2 {
return "Missing checksum. Fewer than two bytes after asterisk", false
}
cs, err := strconv.ParseUint(s_cs[:2], 16, 8)
if err != nil {
return "Invalid checksum", false
}
cs_calc := byte(0)
for i := range s_out {
cs_calc = cs_calc ^ byte(s_out[i])
}
if cs_calc != byte(cs) {
return fmt.Sprintf("Checksum failed. Calculated %#X; expected %#X", cs_calc, cs), false
}
return s_out, true
}
// Only count this heading if a "sustained" >7 kts is obtained. This filters out a lot of heading
// changes while on the ground and "movement" is really only changes in GPS fix as it settles down.
//TODO: Some more robust checking above current and last speed.
//TODO: Dynamic adjust for gain based on groundspeed
func setTrueCourse(groundSpeed uint16, trueCourse float64) {
if mySituation.GPSGroundSpeed >= 7 && groundSpeed >= 7 {
// This was previously used to filter small ground speed spikes caused by GPS position drift.
// It was passed to the previous AHRS heading calculator. Currently unused, maybe in the future it will be.
_ = trueCourse
_ = groundSpeed
}
}
/*
calcGPSAttitude estimates turn rate, pitch, and roll based on recent GPS groundspeed, track, and altitude / vertical speed.
Method uses stored performance statistics from myGPSPerfStats[]. Ideally, calculation is based on most recent 1.5 seconds of data,
assuming 10 Hz sampling frequency. Lower frequency sample rates will increase calculation window for smoother response, at the
cost of slightly increased lag.
(c) 2016 Keith Tschohl. All rights reserved.
Distributable under the terms of the "BSD-New" License that can be found in
the LICENSE file, herein included as part of this header.
*/
func calcGPSAttitude() bool {
// check slice length. Return error if empty set or set zero values
mySituation.muGPSPerformance.Lock()
defer mySituation.muGPSPerformance.Unlock()
length := len(myGPSPerfStats)
index := length - 1
if length == 0 {
log.Printf("GPS attitude: No data received yet. Not calculating attitude.\n")
return false
} else if length == 1 {
//log.Printf("myGPSPerfStats has one data point. Setting statistics to zero.\n")
myGPSPerfStats[index].gpsTurnRate = 0
myGPSPerfStats[index].gpsPitch = 0
myGPSPerfStats[index].gpsRoll = 0
return false
}
// check if GPS data was put in the structure more than three seconds ago -- this shouldn't happen unless something is wrong.
if (stratuxClock.Milliseconds - myGPSPerfStats[index].stratuxTime) > 3000 {
myGPSPerfStats[index].gpsTurnRate = 0
myGPSPerfStats[index].gpsPitch = 0
myGPSPerfStats[index].gpsRoll = 0
log.Printf("GPS attitude: GPS data is more than three seconds old. Setting attitude to zero.\n")
return false
}
// check time interval between samples
t1 := myGPSPerfStats[index].nmeaTime
t0 := myGPSPerfStats[index-1].nmeaTime
dt := t1 - t0
// first time error case: index is more than three seconds ahead of index-1
if dt > 3 {
log.Printf("GPS attitude: Can't calculate GPS attitude. Reference data is old. dt = %v\n", dt)
return false
}
// second case: index is behind index-1. This could be result of day rollover. If time is within n seconds of UTC,
// we rebase to the previous day, and will re-rebase the entire slice forward to the current day once all values roll over.
//TODO: Validate by testing at 0000Z
if dt < 0 {
log.Printf("GPS attitude: Current GPS time (%.2f) is older than last GPS time (%.2f). Checking for 0000Z rollover.\n", t1, t0)
if myGPSPerfStats[index-1].nmeaTime > 86300 && myGPSPerfStats[index].nmeaTime < 100 { // be generous with the time window at rollover
myGPSPerfStats[index].nmeaTime += 86400
} else {
// time decreased, but not due to a recent rollover. Something odd is going on.
log.Printf("GPS attitude: Time isn't near 0000Z. Unknown reason for offset. Can't calculate GPS attitude.\n")
return false
}
// check time array to see if all timestamps are > 86401 seconds since midnight
var tempTime []float64
tempTime = make([]float64, length, length)
for i := 0; i < length; i++ {
tempTime[i] = float64(myGPSPerfStats[i].nmeaTime)
}
minTime, _ := arrayMin(tempTime)
if minTime > 86401.0 {
log.Printf("GPS attitude: Rebasing GPS time since midnight to current day.\n")
for i := 0; i < length; i++ {
myGPSPerfStats[i].nmeaTime -= 86400
}
}
// Verify adjustment
dt = myGPSPerfStats[index].nmeaTime - myGPSPerfStats[index-1].nmeaTime
log.Printf("GPS attitude: New dt = %f\n", dt)
if dt > 3 {
log.Printf("GPS attitude: Can't calculate GPS attitude. Reference data is old. dt = %v\n", dt)
return false
} else if dt < 0 {
log.Printf("GPS attitude: Something went wrong rebasing the time.\n")
return false
}
}
// If all of the bounds checks pass, begin processing the GPS data.
// local variables
var headingAvg, dh, v_x, v_z, a_c, omega, slope, intercept, dt_avg float64
var tempHdg, tempHdgUnwrapped, tempHdgTime, tempSpeed, tempVV, tempSpeedTime, tempRegWeights []float64 // temporary arrays for regression calculation
var valid bool
var lengthHeading, lengthSpeed int
var halfwidth float64 // width of regression evaluation window. Minimum of 1.5 seconds and maximum of 3.5 seconds.
center := float64(myGPSPerfStats[index].nmeaTime) // current time for calculating regression weights
// frequency detection
tempSpeedTime = make([]float64, 0)
for i := 1; i < length; i++ {
dt = myGPSPerfStats[i].nmeaTime - myGPSPerfStats[i-1].nmeaTime
if dt > 0.05 { // avoid double counting messages with same / similar timestamps
tempSpeedTime = append(tempSpeedTime, float64(dt))
}
}
//log.Printf("Delta time array is %v.\n",tempSpeedTime)
dt_avg, valid = mean(tempSpeedTime)
if valid && dt_avg > 0 {
if globalSettings.DEBUG {
log.Printf("GPS attitude: Average delta time is %.2f s (%.1f Hz)\n", dt_avg, 1/dt_avg)
}
halfwidth = 9 * dt_avg
mySituation.GPSPositionSampleRate = 1 / dt_avg
} else {
if globalSettings.DEBUG {
log.Printf("GPS attitude: Couldn't determine sample rate\n")
}
halfwidth = 3.5
mySituation.GPSPositionSampleRate = 0
}
if halfwidth > 3.5 {
halfwidth = 3.5 // limit calculation window to 3.5 seconds of data for 1 Hz or slower samples
} else if halfwidth < 1.5 {
halfwidth = 1.5 // use minimum of 1.5 seconds for sample rates faster than 5 Hz
}
if (globalStatus.GPS_detected_type & 0xf0) == GPS_PROTOCOL_UBX { // UBX reports vertical speed, so we can just walk through all of the PUBX messages in order
// Speed and VV. Use all values in myGPSPerfStats; perform regression.
tempSpeedTime = make([]float64, length, length) // all are length of original slice
tempSpeed = make([]float64, length, length)
tempVV = make([]float64, length, length)
tempRegWeights = make([]float64, length, length)
for i := 0; i < length; i++ {
tempSpeed[i] = float64(myGPSPerfStats[i].gsf)
tempVV[i] = float64(myGPSPerfStats[i].vv)
tempSpeedTime[i] = float64(myGPSPerfStats[i].nmeaTime)
tempRegWeights[i] = triCubeWeight(center, halfwidth, tempSpeedTime[i])
}
// Groundspeed regression estimate.
slope, intercept, valid = linRegWeighted(tempSpeedTime, tempSpeed, tempRegWeights)
if !valid {
log.Printf("GPS attitude: Error calculating speed regression from UBX position messages")
return false
} else {
v_x = (slope*float64(myGPSPerfStats[index].nmeaTime) + intercept) * 1.687810 // units are knots, converted to feet/sec
}
// Vertical speed regression estimate.
slope, intercept, valid = linRegWeighted(tempSpeedTime, tempVV, tempRegWeights)
if !valid {
log.Printf("GPS attitude: Error calculating vertical speed regression from UBX position messages")
return false
} else {
v_z = (slope*float64(myGPSPerfStats[index].nmeaTime) + intercept) // units are feet per sec; no conversion needed
}
} else { // If we need to parse standard NMEA messages, determine if it's RMC or GGA, then fill the temporary slices accordingly. Need to pull from multiple message types since GGA doesn't do course or speed; VTG / RMC don't do altitude, etc. Grrr.
//v_x = float64(myGPSPerfStats[index].gsf * 1.687810)
//v_z = 0
// first, parse groundspeed from RMC messages.
tempSpeedTime = make([]float64, 0)
tempSpeed = make([]float64, 0)
tempRegWeights = make([]float64, 0)
for i := 0; i < length; i++ {
if myGPSPerfStats[i].msgType == "GPRMC" || myGPSPerfStats[i].msgType == "GNRMC" {
tempSpeed = append(tempSpeed, float64(myGPSPerfStats[i].gsf))
tempSpeedTime = append(tempSpeedTime, float64(myGPSPerfStats[i].nmeaTime))
tempRegWeights = append(tempRegWeights, triCubeWeight(center, halfwidth, float64(myGPSPerfStats[i].nmeaTime)))
}
}
lengthSpeed = len(tempSpeed)
if lengthSpeed == 0 {
log.Printf("GPS Attitude: No groundspeed data could be parsed from NMEA RMC messages\n")
return false
} else if lengthSpeed == 1 {
v_x = tempSpeed[0] * 1.687810
} else {
slope, intercept, valid = linRegWeighted(tempSpeedTime, tempSpeed, tempRegWeights)
if !valid {
log.Printf("GPS attitude: Error calculating speed regression from NMEA RMC position messages")
return false
} else {
v_x = (slope*float64(myGPSPerfStats[index].nmeaTime) + intercept) * 1.687810 // units are knots, converted to feet/sec
//log.Printf("Avg speed %f calculated from %d RMC messages\n", v_x, lengthSpeed) // DEBUG
}
}
// next, calculate vertical velocity from GGA altitude data.
tempSpeedTime = make([]float64, 0)
tempVV = make([]float64, 0)
tempRegWeights = make([]float64, 0)
for i := 0; i < length; i++ {
if myGPSPerfStats[i].msgType == "GPGGA" || myGPSPerfStats[i].msgType == "GNGGA" {
tempVV = append(tempVV, float64(myGPSPerfStats[i].alt))
tempSpeedTime = append(tempSpeedTime, float64(myGPSPerfStats[i].nmeaTime))
tempRegWeights = append(tempRegWeights, triCubeWeight(center, halfwidth, float64(myGPSPerfStats[i].nmeaTime)))
}
}
lengthSpeed = len(tempVV)
if lengthSpeed < 2 {
log.Printf("GPS Attitude: Not enough points to calculate vertical speed from NMEA GGA messages\n")
return false
} else {
slope, _, valid = linRegWeighted(tempSpeedTime, tempVV, tempRegWeights)
if !valid {
log.Printf("GPS attitude: Error calculating vertical speed regression from NMEA GGA messages")
return false
} else {
v_z = slope // units are feet/sec
//log.Printf("Avg VV %f calculated from %d GGA messages\n", v_z, lengthSpeed) // DEBUG
}
}
}
// If we're going too slow for processNMEALine() to give us valid heading data, there's no sense in trying to parse it.
// However, we need to return a valid level attitude so we don't get the "red X of death" on our AHRS display.
// This will also eliminate most of the nuisance error message from the turn rate calculation.
if v_x < 6 { // ~3.55 knots
myGPSPerfStats[index].gpsPitch = 0
myGPSPerfStats[index].gpsRoll = 0
myGPSPerfStats[index].gpsTurnRate = 0
myGPSPerfStats[index].gpsLoadFactor = 1.0
mySituation.GPSTurnRate = 0
// Output format:GPSAtttiude,seconds,nmeaTime,msg_type,GS,Course,Alt,VV,filtered_GS,filtered_course,turn rate,filtered_vv,pitch, roll,load_factor
buf := fmt.Sprintf("GPSAttitude,%.1f,%.2f,%s,%0.3f,%0.3f,%0.3f,%0.3f,%0.3f,%0.3f,%0.3f,%0.3f,%0.3f,%0.3f,%0.3f\n", float64(stratuxClock.Milliseconds)/1000, myGPSPerfStats[index].nmeaTime, myGPSPerfStats[index].msgType, myGPSPerfStats[index].gsf, myGPSPerfStats[index].coursef, myGPSPerfStats[index].alt, myGPSPerfStats[index].vv, v_x/1.687810, headingAvg, myGPSPerfStats[index].gpsTurnRate, v_z, myGPSPerfStats[index].gpsPitch, myGPSPerfStats[index].gpsRoll, myGPSPerfStats[index].gpsLoadFactor)
if globalSettings.DEBUG {
log.Printf("%s", buf) // FIXME. Send to sqlite log or other file?
}
logGPSAttitude(myGPSPerfStats[index])
//replayLog(buf, MSGCLASS_AHRS)
return true
}
// Heading. Same method used for UBX and generic.
// First, walk through the PerfStats and parse only valid heading data.
//log.Printf("Raw heading data:")
for i := 0; i < length; i++ {
//log.Printf("%.1f,",myGPSPerfStats[i].coursef)
if myGPSPerfStats[i].coursef >= 0 { // negative values are used to flag invalid / unavailable course
tempHdg = append(tempHdg, float64(myGPSPerfStats[i].coursef))
tempHdgTime = append(tempHdgTime, float64(myGPSPerfStats[i].nmeaTime))
}
}
//log.Printf("\n")
//log.Printf("tempHdg: %v\n", tempHdg)
// Next, unwrap the heading so we don't mess up the regression by fitting a line across the 0/360 deg discontinuity.
lengthHeading = len(tempHdg)
tempHdgUnwrapped = make([]float64, lengthHeading, lengthHeading)
tempRegWeights = make([]float64, lengthHeading, lengthHeading)
if lengthHeading > 1 {
tempHdgUnwrapped[0] = tempHdg[0]
tempRegWeights[0] = triCubeWeight(center, halfwidth, tempHdgTime[0])
for i := 1; i < lengthHeading; i++ {
tempRegWeights[i] = triCubeWeight(center, halfwidth, tempHdgTime[i])
if math.Abs(tempHdg[i]-tempHdg[i-1]) < 180 { // case 1: if angle change is less than 180 degrees, use the same reference system
tempHdgUnwrapped[i] = tempHdgUnwrapped[i-1] + tempHdg[i] - tempHdg[i-1]
} else if tempHdg[i] > tempHdg[i-1] { // case 2: heading has wrapped around from NE to NW. Subtract 360 to keep consistent with previous data.
tempHdgUnwrapped[i] = tempHdgUnwrapped[i-1] + tempHdg[i] - tempHdg[i-1] - 360
} else { // case 3: heading has wrapped around from NW to NE. Add 360 to keep consistent with previous data.
tempHdgUnwrapped[i] = tempHdgUnwrapped[i-1] + tempHdg[i] - tempHdg[i-1] + 360
}
}
} else { //
if globalSettings.DEBUG {
log.Printf("GPS attitude: Can't calculate turn rate with less than two points.\n")
}
return false
}
// Finally, calculate turn rate as the slope of the weighted linear regression of unwrapped heading.
slope, intercept, valid = linRegWeighted(tempHdgTime, tempHdgUnwrapped, tempRegWeights)
if !valid {
log.Printf("GPS attitude: Regression error calculating turn rate")
return false
} else {
headingAvg = slope*float64(myGPSPerfStats[index].nmeaTime) + intercept
dh = slope // units are deg per sec; no conversion needed here
//log.Printf("Calculated heading and turn rate: %.3f degrees, %.3f deg/sec\n",headingAvg,dh)
}
myGPSPerfStats[index].gpsTurnRate = dh
mySituation.GPSTurnRate = dh
// pitch angle -- or to be more pedantic, glide / climb angle, since we're just looking a rise-over-run.
// roll angle, based on turn rate and ground speed. Only valid for coordinated flight. Differences between airspeed and groundspeed will trip this up.
if v_x > 20 { // reduce nuisance 'bounce' at low speeds. 20 ft/sec = 11.9 knots.
myGPSPerfStats[index].gpsPitch = math.Atan2(v_z, v_x) * 180.0 / math.Pi
/*
Governing equations for roll calculations
Physics tells us that
a_z = g (in steady-state flight -- climbing, descending, or level -- this is gravity. 9.81 m/s^2 or 32.2 ft/s^2)
a_c = v^2/r (centripetal acceleration)
We don't know r. However, we do know the tangential velocity (v) and angular velocity (omega). Express omega in radians per unit time, and
v = omega*r
By substituting and rearranging terms:
a_c = v^2 / (v / omega)
a_c = v*omega
Free body diagram time!
/|
a_r / | a_z
/__|
X a_c
\_________________ [For the purpose of this comment, " X" is an airplane in a 20 degree bank. Use your imagination, mkay?)
Resultant acceleration a_r is what the wings feel; a_r/a_z = load factor. Anyway, trig out the bank angle:
bank angle = atan(a_c/a_z)
= atan(v*omega/g)
wing loading = sqrt(a_c^2 + a_z^2) / g
*/
g := 32.174 // ft/(s^2)
omega = radians(myGPSPerfStats[index].gpsTurnRate) // need radians/sec
a_c = v_x * omega
myGPSPerfStats[index].gpsRoll = math.Atan2(a_c, g) * 180 / math.Pi // output is degrees
myGPSPerfStats[index].gpsLoadFactor = math.Sqrt(a_c*a_c+g*g) / g
} else {
myGPSPerfStats[index].gpsPitch = 0
myGPSPerfStats[index].gpsRoll = 0
myGPSPerfStats[index].gpsLoadFactor = 1
}
if globalSettings.DEBUG {
// Output format:GPSAtttiude,seconds,nmeaTime,msg_type,GS,Course,Alt,VV,filtered_GS,filtered_course,turn rate,filtered_vv,pitch, roll,load_factor
buf := fmt.Sprintf("GPSAttitude,%.1f,%.2f,%s,%0.3f,%0.3f,%0.3f,%0.3f,%0.3f,%0.3f,%0.3f,%0.3f,%0.3f,%0.3f,%0.3f\n", float64(stratuxClock.Milliseconds)/1000, myGPSPerfStats[index].nmeaTime, myGPSPerfStats[index].msgType, myGPSPerfStats[index].gsf, myGPSPerfStats[index].coursef, myGPSPerfStats[index].alt, myGPSPerfStats[index].vv, v_x/1.687810, headingAvg, myGPSPerfStats[index].gpsTurnRate, v_z, myGPSPerfStats[index].gpsPitch, myGPSPerfStats[index].gpsRoll, myGPSPerfStats[index].gpsLoadFactor)
log.Printf("%s", buf) // FIXME. Send to sqlite log or other file?
}
logGPSAttitude(myGPSPerfStats[index])
//replayLog(buf, MSGCLASS_AHRS)
return true
}
func calculateNACp(accuracy float32) uint8 {
ret := uint8(0)
if accuracy < 3 {
ret = 11
} else if accuracy < 10 {
ret = 10
} else if accuracy < 30 {
ret = 9
} else if accuracy < 92.6 {
ret = 8
} else if accuracy < 185.2 {
ret = 7
} else if accuracy < 555.6 {
ret = 6
}
return ret
}
/*
registerSituationUpdate().
Called whenever there is a change in mySituation.
*/
func registerSituationUpdate() {
logSituation()
situationUpdate.SendJSON(mySituation)
}
/*
processNMEALine parses NMEA-0183 formatted strings against several message types.
Standard messages supported: RMC GGA VTG GSA
U-blox proprietary messages: PUBX,00 PUBX,03 PUBX,04
return is false if errors occur during parse, or if GPS position is invalid
return is true if parse occurs correctly and position is valid.
*/
func processNMEALine(l string) (sentenceUsed bool) {
mySituation.muGPS.Lock()
defer func() {
if sentenceUsed || globalSettings.DEBUG {
registerSituationUpdate()
}
mySituation.muGPS.Unlock()
}()
// Local variables for GPS attitude estimation
thisGpsPerf := gpsPerf // write to myGPSPerfStats at end of function IFF
thisGpsPerf.coursef = -999.9 // default value of -999.9 indicates invalid heading to regression calculation
thisGpsPerf.stratuxTime = stratuxClock.Milliseconds // used for gross indexing
updateGPSPerf := false // change to true when position or vector info is read
l_valid, validNMEAcs := validateNMEAChecksum(l)
if !validNMEAcs {
log.Printf("GPS error. Invalid NMEA string: %s\n", l_valid) // remove log message once validation complete
return false
}
x := strings.Split(l_valid, ",")
mySituation.GPSLastValidNMEAMessageTime = stratuxClock.Time
mySituation.GPSLastValidNMEAMessage = l
if x[0] == "PUBX" { // UBX proprietary message
if x[1] == "00" { // Position fix.
if len(x) < 20 {
return false
}
// set the global GPS type to UBX as soon as we see our first (valid length)
// PUBX,01 position message, even if we don't have a fix
if (globalStatus.GPS_detected_type & 0xf0) != GPS_PROTOCOL_UBX {
globalStatus.GPS_detected_type |= GPS_PROTOCOL_UBX
log.Printf("GPS detected: u-blox NMEA position message seen.\n")
}
thisGpsPerf.msgType = x[0] + x[1]
tmpSituation := mySituation // If we decide to not use the data in this message, then don't make incomplete changes in mySituation.
// Do the accuracy / quality fields first to prevent invalid position etc. from being sent downstream
// field 8 = nav status
// DR = dead reckoning, G2= 2D GPS, G3 = 3D GPS, D2= 2D diff, D3 = 3D diff, RK = GPS+DR, TT = time only
if x[8] == "D2" || x[8] == "D3" {
tmpSituation.GPSFixQuality = 2
} else if x[8] == "G2" || x[8] == "G3" {
tmpSituation.GPSFixQuality = 1
} else if x[8] == "DR" || x[8] == "RK" {
tmpSituation.GPSFixQuality = 6
} else if x[8] == "NF" {
tmpSituation.GPSFixQuality = 0 // Just a note.
return false
} else {
tmpSituation.GPSFixQuality = 0 // Just a note.
return false
}
// field 9 = horizontal accuracy, m
hAcc, err := strconv.ParseFloat(x[9], 32)
if err != nil {
return false
}
tmpSituation.GPSHorizontalAccuracy = float32(hAcc * 2) // UBX reports 1-sigma variation; NACp is 95% confidence (2-sigma)
// NACp estimate.
tmpSituation.GPSNACp = calculateNACp(tmpSituation.GPSHorizontalAccuracy)
// field 10 = vertical accuracy, m
/*
vAcc, err := strconv.ParseFloat(x[10], 32)
if err != nil {
return false
}
tmpSituation.GPSVerticalAccuracy = float32(vAcc * 2) // UBX reports 1-sigma variation; we want 95% confidence
*/
tmpSituation.GPSVerticalAccuracy = float32(2.) * tmpSituation.GPSHorizontalAccuracy
// field 2 = time
if len(x[2]) < 8 {
return false
}
hr, err1 := strconv.Atoi(x[2][0:2])
min, err2 := strconv.Atoi(x[2][2:4])
sec, err3 := strconv.ParseFloat(x[2][4:], 32)
if err1 != nil || err2 != nil || err3 != nil {
return false
}
tmpSituation.GPSLastFixSinceMidnightUTC = float32(3600*hr+60*min) + float32(sec)
thisGpsPerf.nmeaTime = tmpSituation.GPSLastFixSinceMidnightUTC
// field 3-4 = lat
if len(x[3]) < 10 {
return false
}
hr, err1 = strconv.Atoi(x[3][0:2])
minf, err2 := strconv.ParseFloat(x[3][2:], 32)
if err1 != nil || err2 != nil {
return false
}
tmpSituation.GPSLatitude = float32(hr) + float32(minf/60.0)
if x[4] == "S" { // South = negative.
tmpSituation.GPSLatitude = -tmpSituation.GPSLatitude
}
// field 5-6 = lon
if len(x[5]) < 11 {
return false
}
hr, err1 = strconv.Atoi(x[5][0:3])
minf, err2 = strconv.ParseFloat(x[5][3:], 32)
if err1 != nil || err2 != nil {
return false
}
tmpSituation.GPSLongitude = float32(hr) + float32(minf/60.0)
if x[6] == "W" { // West = negative.
tmpSituation.GPSLongitude = -tmpSituation.GPSLongitude
}
// field 7 = height above ellipsoid, m
hae, err1 := strconv.ParseFloat(x[7], 32)
if err1 != nil {
return false
}
// the next 'if' statement is a workaround for a ubx7 firmware bug:
// PUBX,00 reports HAE with a floor of zero (i.e. negative altitudes are set to zero). This causes GPS altitude to never read lower than -GPSGeoidSep,