/
AP_GPS.cpp
1635 lines (1455 loc) · 61.8 KB
/
AP_GPS.cpp
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 program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include "AP_GPS.h"
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h>
#include <AP_Notify/AP_Notify.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_BoardConfig/AP_BoardConfig.h>
#include <AP_RTC/AP_RTC.h>
#include <climits>
#include "AP_GPS_NOVA.h"
#include "AP_GPS_ERB.h"
#include "AP_GPS_GSOF.h"
#include "AP_GPS_MTK.h"
#include "AP_GPS_MTK19.h"
#include "AP_GPS_NMEA.h"
#include "AP_GPS_SBF.h"
#include "AP_GPS_SBP.h"
#include "AP_GPS_SBP2.h"
#include "AP_GPS_SIRF.h"
#include "AP_GPS_UBLOX.h"
#include "AP_GPS_MAV.h"
#include "GPS_Backend.h"
#if HAL_WITH_UAVCAN
#include <AP_BoardConfig/AP_BoardConfig_CAN.h>
#include <AP_UAVCAN/AP_UAVCAN.h>
#include "AP_GPS_UAVCAN.h"
#endif
#include <AP_AHRS/AP_AHRS.h>
#include <AP_Logger/AP_Logger.h>
#define GPS_RTK_INJECT_TO_ALL 127
#define GPS_MAX_RATE_MS 200 // maximum value of rate_ms (i.e. slowest update rate) is 5hz or 200ms
#define GPS_BAUD_TIME_MS 1200
#define GPS_TIMEOUT_MS 4000u
// defines used to specify the mask position for use of different accuracy metrics in the blending algorithm
#define BLEND_MASK_USE_HPOS_ACC 1
#define BLEND_MASK_USE_VPOS_ACC 2
#define BLEND_MASK_USE_SPD_ACC 4
#define BLEND_COUNTER_FAILURE_INCREMENT 10
extern const AP_HAL::HAL &hal;
// baudrates to try to detect GPSes with
const uint32_t AP_GPS::_baudrates[] = {9600U, 115200U, 4800U, 19200U, 38400U, 57600U, 230400U};
// initialisation blobs to send to the GPS to try to get it into the
// right mode
const char AP_GPS::_initialisation_blob[] = UBLOX_SET_BINARY MTK_SET_BINARY SIRF_SET_BINARY;
AP_GPS *AP_GPS::_singleton;
// table of user settable parameters
const AP_Param::GroupInfo AP_GPS::var_info[] = {
// @Param: TYPE
// @DisplayName: GPS type
// @Description: GPS type
// @Values: 0:None,1:AUTO,2:uBlox,3:MTK,4:MTK19,5:NMEA,6:SiRF,7:HIL,8:SwiftNav,9:UAVCAN,10:SBF,11:GSOF,13:ERB,14:MAV,15:NOVA,16:HemisphereNMEA
// @RebootRequired: True
// @User: Advanced
AP_GROUPINFO("TYPE", 0, AP_GPS, _type[0], HAL_GPS_TYPE_DEFAULT),
#if GPS_MAX_RECEIVERS > 1
// @Param: TYPE2
// @DisplayName: 2nd GPS type
// @Description: GPS type of 2nd GPS
// @Values: 0:None,1:AUTO,2:uBlox,3:MTK,4:MTK19,5:NMEA,6:SiRF,7:HIL,8:SwiftNav,9:UAVCAN,10:SBF,11:GSOF,13:ERB,14:MAV,15:NOVA,16:HemisphereNMEA
// @RebootRequired: True
// @User: Advanced
AP_GROUPINFO("TYPE2", 1, AP_GPS, _type[1], 0),
#endif
// @Param: NAVFILTER
// @DisplayName: Navigation filter setting
// @Description: Navigation filter engine setting
// @Values: 0:Portable,2:Stationary,3:Pedestrian,4:Automotive,5:Sea,6:Airborne1G,7:Airborne2G,8:Airborne4G
// @User: Advanced
AP_GROUPINFO("NAVFILTER", 2, AP_GPS, _navfilter, GPS_ENGINE_AIRBORNE_4G),
#if GPS_MAX_RECEIVERS > 1
// @Param: AUTO_SWITCH
// @DisplayName: Automatic Switchover Setting
// @Description: Automatic switchover to GPS reporting best lock
// @Values: 0:Disabled,1:UseBest,2:Blend,3:UseSecond
// @User: Advanced
AP_GROUPINFO("AUTO_SWITCH", 3, AP_GPS, _auto_switch, 1),
#endif
// @Param: MIN_DGPS
// @DisplayName: Minimum Lock Type Accepted for DGPS
// @Description: Sets the minimum type of differential GPS corrections required before allowing to switch into DGPS mode.
// @Values: 0:Any,50:FloatRTK,100:IntegerRTK
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("MIN_DGPS", 4, AP_GPS, _min_dgps, 100),
// @Param: SBAS_MODE
// @DisplayName: SBAS Mode
// @Description: This sets the SBAS (satellite based augmentation system) mode if available on this GPS. If set to 2 then the SBAS mode is not changed in the GPS. Otherwise the GPS will be reconfigured to enable/disable SBAS. Disabling SBAS may be worthwhile in some parts of the world where an SBAS signal is available but the baseline is too long to be useful.
// @Values: 0:Disabled,1:Enabled,2:NoChange
// @User: Advanced
AP_GROUPINFO("SBAS_MODE", 5, AP_GPS, _sbas_mode, 2),
// @Param: MIN_ELEV
// @DisplayName: Minimum elevation
// @Description: This sets the minimum elevation of satellites above the horizon for them to be used for navigation. Setting this to -100 leaves the minimum elevation set to the GPS modules default.
// @Range: -100 90
// @Units: deg
// @User: Advanced
AP_GROUPINFO("MIN_ELEV", 6, AP_GPS, _min_elevation, -100),
// @Param: INJECT_TO
// @DisplayName: Destination for GPS_INJECT_DATA MAVLink packets
// @Description: The GGS can send raw serial packets to inject data to multiple GPSes.
// @Values: 0:send to first GPS,1:send to 2nd GPS,127:send to all
// @User: Advanced
AP_GROUPINFO("INJECT_TO", 7, AP_GPS, _inject_to, GPS_RTK_INJECT_TO_ALL),
// @Param: SBP_LOGMASK
// @DisplayName: Swift Binary Protocol Logging Mask
// @Description: Masked with the SBP msg_type field to determine whether SBR1/SBR2 data is logged
// @Values: 0:None (0x0000),-1:All (0xFFFF),-256:External only (0xFF00)
// @User: Advanced
AP_GROUPINFO("SBP_LOGMASK", 8, AP_GPS, _sbp_logmask, -256),
// @Param: RAW_DATA
// @DisplayName: Raw data logging
// @Description: Handles logging raw data; on uBlox chips that support raw data this will log RXM messages into logger; on Septentrio this will log on the equipment's SD card and when set to 2, the autopilot will try to stop logging after disarming and restart after arming
// @Values: 0:Ignore,1:Always log,2:Stop logging when disarmed (SBF only),5:Only log every five samples (uBlox only)
// @RebootRequired: True
// @User: Advanced
AP_GROUPINFO("RAW_DATA", 9, AP_GPS, _raw_data, 0),
// @Param: GNSS_MODE
// @DisplayName: GNSS system configuration
// @Description: Bitmask for what GNSS system to use on the first GPS (all unchecked or zero to leave GPS as configured)
// @Values: 0:Leave as currently configured, 1:GPS-NoSBAS, 3:GPS+SBAS, 4:Galileo-NoSBAS, 6:Galileo+SBAS, 8:Beidou, 51:GPS+IMES+QZSS+SBAS (Japan Only), 64:GLONASS, 66:GLONASS+SBAS, 67:GPS+GLONASS+SBAS
// @Bitmask: 0:GPS,1:SBAS,2:Galileo,3:Beidou,4:IMES,5:QZSS,6:GLOSNASS
// @User: Advanced
AP_GROUPINFO("GNSS_MODE", 10, AP_GPS, _gnss_mode[0], 0),
// @Param: SAVE_CFG
// @DisplayName: Save GPS configuration
// @Description: Determines whether the configuration for this GPS should be written to non-volatile memory on the GPS. Currently working for UBlox 6 series and above.
// @Values: 0:Do not save config,1:Save config,2:Save only when needed
// @User: Advanced
AP_GROUPINFO("SAVE_CFG", 11, AP_GPS, _save_config, 2),
#if GPS_MAX_RECEIVERS > 1
// @Param: GNSS_MODE2
// @DisplayName: GNSS system configuration
// @Description: Bitmask for what GNSS system to use on the second GPS (all unchecked or zero to leave GPS as configured)
// @Values: 0:Leave as currently configured, 1:GPS-NoSBAS, 3:GPS+SBAS, 4:Galileo-NoSBAS, 6:Galileo+SBAS, 8:Beidou, 51:GPS+IMES+QZSS+SBAS (Japan Only), 64:GLONASS, 66:GLONASS+SBAS, 67:GPS+GLONASS+SBAS
// @Bitmask: 0:GPS,1:SBAS,2:Galileo,3:Beidou,4:IMES,5:QZSS,6:GLOSNASS
// @User: Advanced
AP_GROUPINFO("GNSS_MODE2", 12, AP_GPS, _gnss_mode[1], 0),
#endif
// @Param: AUTO_CONFIG
// @DisplayName: Automatic GPS configuration
// @Description: Controls if the autopilot should automatically configure the GPS based on the parameters and default settings
// @Values: 0:Disables automatic configuration,1:Enable automatic configuration
// @User: Advanced
AP_GROUPINFO("AUTO_CONFIG", 13, AP_GPS, _auto_config, 1),
// @Param: RATE_MS
// @DisplayName: GPS update rate in milliseconds
// @Description: Controls how often the GPS should provide a position update. Lowering below 5Hz is not allowed
// @Units: ms
// @Values: 100:10Hz,125:8Hz,200:5Hz
// @Range: 50 200
// @User: Advanced
AP_GROUPINFO("RATE_MS", 14, AP_GPS, _rate_ms[0], 200),
#if GPS_MAX_RECEIVERS > 1
// @Param: RATE_MS2
// @DisplayName: GPS 2 update rate in milliseconds
// @Description: Controls how often the GPS should provide a position update. Lowering below 5Hz is not allowed
// @Units: ms
// @Values: 100:10Hz,125:8Hz,200:5Hz
// @Range: 50 200
// @User: Advanced
AP_GROUPINFO("RATE_MS2", 15, AP_GPS, _rate_ms[1], 200),
#endif
// @Param: POS1_X
// @DisplayName: Antenna X position offset
// @Description: X position of the first GPS antenna in body frame. Positive X is forward of the origin. Use antenna phase centroid location if provided by the manufacturer.
// @Units: m
// @Range: -10 10
// @User: Advanced
// @Param: POS1_Y
// @DisplayName: Antenna Y position offset
// @Description: Y position of the first GPS antenna in body frame. Positive Y is to the right of the origin. Use antenna phase centroid location if provided by the manufacturer.
// @Units: m
// @Range: -10 10
// @User: Advanced
// @Param: POS1_Z
// @DisplayName: Antenna Z position offset
// @Description: Z position of the first GPS antenna in body frame. Positive Z is down from the origin. Use antenna phase centroid location if provided by the manufacturer.
// @Units: m
// @Range: -10 10
// @User: Advanced
AP_GROUPINFO("POS1", 16, AP_GPS, _antenna_offset[0], 0.0f),
// @Param: POS2_X
// @DisplayName: Antenna X position offset
// @Description: X position of the second GPS antenna in body frame. Positive X is forward of the origin. Use antenna phase centroid location if provided by the manufacturer.
// @Units: m
// @Range: -10 10
// @User: Advanced
// @Param: POS2_Y
// @DisplayName: Antenna Y position offset
// @Description: Y position of the second GPS antenna in body frame. Positive Y is to the right of the origin. Use antenna phase centroid location if provided by the manufacturer.
// @Units: m
// @Range: -10 10
// @User: Advanced
#if GPS_MAX_RECEIVERS > 1
// @Param: POS2_Z
// @DisplayName: Antenna Z position offset
// @Description: Z position of the second GPS antenna in body frame. Positive Z is down from the origin. Use antenna phase centroid location if provided by the manufacturer.
// @Units: m
// @Range: -10 10
// @User: Advanced
AP_GROUPINFO("POS2", 17, AP_GPS, _antenna_offset[1], 0.0f),
#endif
// @Param: DELAY_MS
// @DisplayName: GPS delay in milliseconds
// @Description: Controls the amount of GPS measurement delay that the autopilot compensates for. Set to zero to use the default delay for the detected GPS type.
// @Units: ms
// @Range: 0 250
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("DELAY_MS", 18, AP_GPS, _delay_ms[0], 0),
#if GPS_MAX_RECEIVERS > 1
// @Param: DELAY_MS2
// @DisplayName: GPS 2 delay in milliseconds
// @Description: Controls the amount of GPS measurement delay that the autopilot compensates for. Set to zero to use the default delay for the detected GPS type.
// @Units: ms
// @Range: 0 250
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("DELAY_MS2", 19, AP_GPS, _delay_ms[1], 0),
#endif
#if defined(GPS_BLENDED_INSTANCE)
// @Param: BLEND_MASK
// @DisplayName: Multi GPS Blending Mask
// @Description: Determines which of the accuracy measures Horizontal position, Vertical Position and Speed are used to calculate the weighting on each GPS receiver when soft switching has been selected by setting GPS_AUTO_SWITCH to 2
// @Bitmask: 0:Horiz Pos,1:Vert Pos,2:Speed
// @User: Advanced
AP_GROUPINFO("BLEND_MASK", 20, AP_GPS, _blend_mask, 5),
// @Param: BLEND_TC
// @DisplayName: Blending time constant
// @Description: Controls the slowest time constant applied to the calculation of GPS position and height offsets used to adjust different GPS receivers for steady state position differences.
// @Units: s
// @Range: 5.0 30.0
// @User: Advanced
AP_GROUPINFO("BLEND_TC", 21, AP_GPS, _blend_tc, 10.0f),
#endif
AP_GROUPEND
};
// constructor
AP_GPS::AP_GPS()
{
static_assert((sizeof(_initialisation_blob) * (CHAR_BIT + 2)) < (4800 * GPS_BAUD_TIME_MS * 1e-3),
"GPS initilisation blob is too large to be completely sent before the baud rate changes");
AP_Param::setup_object_defaults(this, var_info);
if (_singleton != nullptr) {
AP_HAL::panic("AP_GPS must be singleton");
}
_singleton = this;
}
/// Startup initialisation.
void AP_GPS::init(const AP_SerialManager& serial_manager)
{
primary_instance = 0;
// search for serial ports with gps protocol
for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
_port[i] = serial_manager.find_serial(AP_SerialManager::SerialProtocol_GPS, i);
}
_last_instance_swap_ms = 0;
// Initialise class variables used to do GPS blending
_omega_lpf = 1.0f / constrain_float(_blend_tc, 5.0f, 30.0f);
// prep the state instance fields
for (uint8_t i = 0; i < GPS_MAX_INSTANCES; i++) {
state[i].instance = i;
}
// sanity check update rate
for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
if (_rate_ms[i] <= 0 || _rate_ms[i] > GPS_MAX_RATE_MS) {
_rate_ms[i] = GPS_MAX_RATE_MS;
}
}
}
// return number of active GPS sensors. Note that if the first GPS
// is not present but the 2nd is then we return 2. Note that a blended
// GPS solution is treated as an additional sensor.
uint8_t AP_GPS::num_sensors(void) const
{
if (!_output_is_blended) {
return num_instances;
} else {
return num_instances+1;
}
}
bool AP_GPS::speed_accuracy(uint8_t instance, float &sacc) const
{
if (state[instance].have_speed_accuracy) {
sacc = state[instance].speed_accuracy;
return true;
}
return false;
}
bool AP_GPS::horizontal_accuracy(uint8_t instance, float &hacc) const
{
if (state[instance].have_horizontal_accuracy) {
hacc = state[instance].horizontal_accuracy;
return true;
}
return false;
}
bool AP_GPS::vertical_accuracy(uint8_t instance, float &vacc) const
{
if (state[instance].have_vertical_accuracy) {
vacc = state[instance].vertical_accuracy;
return true;
}
return false;
}
/**
convert GPS week and milliseconds to unix epoch in milliseconds
*/
uint64_t AP_GPS::time_epoch_convert(uint16_t gps_week, uint32_t gps_ms)
{
uint64_t fix_time_ms = UNIX_OFFSET_MSEC + gps_week * AP_MSEC_PER_WEEK + gps_ms;
return fix_time_ms;
}
/**
calculate current time since the unix epoch in microseconds
*/
uint64_t AP_GPS::time_epoch_usec(uint8_t instance) const
{
const GPS_State &istate = state[instance];
if (istate.last_gps_time_ms == 0 || istate.time_week == 0) {
return 0;
}
uint64_t fix_time_ms = time_epoch_convert(istate.time_week, istate.time_week_ms);
// add in the milliseconds since the last fix
return (fix_time_ms + (AP_HAL::millis() - istate.last_gps_time_ms)) * 1000ULL;
}
/*
send some more initialisation string bytes if there is room in the
UART transmit buffer
*/
void AP_GPS::send_blob_start(uint8_t instance, const char *_blob, uint16_t size)
{
initblob_state[instance].blob = _blob;
initblob_state[instance].remaining = size;
}
/*
send some more initialisation string bytes if there is room in the
UART transmit buffer
*/
void AP_GPS::send_blob_update(uint8_t instance)
{
// exit immediately if no uart for this instance
if (_port[instance] == nullptr) {
return;
}
// see if we can write some more of the initialisation blob
if (initblob_state[instance].remaining > 0) {
int16_t space = _port[instance]->txspace();
if (space > (int16_t)initblob_state[instance].remaining) {
space = initblob_state[instance].remaining;
}
while (space > 0) {
_port[instance]->write(*initblob_state[instance].blob);
initblob_state[instance].blob++;
space--;
initblob_state[instance].remaining--;
}
}
}
/*
run detection step for one GPS instance. If this finds a GPS then it
will fill in drivers[instance] and change state[instance].status
from NO_GPS to NO_FIX.
*/
void AP_GPS::detect_instance(uint8_t instance)
{
AP_GPS_Backend *new_gps = nullptr;
struct detect_state *dstate = &detect_state[instance];
const uint32_t now = AP_HAL::millis();
state[instance].status = NO_GPS;
state[instance].hdop = GPS_UNKNOWN_DOP;
state[instance].vdop = GPS_UNKNOWN_DOP;
switch (_type[instance]) {
// user has to explicitly set the MAV type, do not use AUTO
// do not try to detect the MAV type, assume it's there
case GPS_TYPE_MAV:
#ifndef HAL_BUILD_AP_PERIPH
dstate->auto_detected_baud = false; // specified, not detected
new_gps = new AP_GPS_MAV(*this, state[instance], nullptr);
goto found_gps;
#endif
break;
// user has to explicitly set the UAVCAN type, do not use AUTO
case GPS_TYPE_UAVCAN:
#if HAL_WITH_UAVCAN
dstate->auto_detected_baud = false; // specified, not detected
new_gps = AP_GPS_UAVCAN::probe(*this, state[instance]);
goto found_gps;
#endif
return; // We don't do anything here if UAVCAN is not supported
default:
break;
}
if (_port[instance] == nullptr) {
// UART not available
return;
}
// all remaining drivers automatically cycle through baud rates to detect
// the correct baud rate, and should have the selected baud broadcast
dstate->auto_detected_baud = true;
#ifndef HAL_BUILD_AP_PERIPH
switch (_type[instance]) {
// by default the sbf/trimble gps outputs no data on its port, until configured.
case GPS_TYPE_SBF:
new_gps = new AP_GPS_SBF(*this, state[instance], _port[instance]);
break;
case GPS_TYPE_GSOF:
new_gps = new AP_GPS_GSOF(*this, state[instance], _port[instance]);
break;
case GPS_TYPE_NOVA:
new_gps = new AP_GPS_NOVA(*this, state[instance], _port[instance]);
break;
default:
break;
}
#endif // HAL_BUILD_AP_PERIPH
if (now - dstate->last_baud_change_ms > GPS_BAUD_TIME_MS) {
// try the next baud rate
// incrementing like this will skip the first element in array of bauds
// this is okay, and relied upon
dstate->current_baud++;
if (dstate->current_baud == ARRAY_SIZE(_baudrates)) {
dstate->current_baud = 0;
}
uint32_t baudrate = _baudrates[dstate->current_baud];
_port[instance]->begin(baudrate);
_port[instance]->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
dstate->last_baud_change_ms = now;
if (_auto_config == GPS_AUTO_CONFIG_ENABLE && new_gps == nullptr) {
if (_type[instance] == GPS_TYPE_HEMI) {
send_blob_start(instance, AP_GPS_NMEA_HEMISPHERE_INIT_STRING, strlen(AP_GPS_NMEA_HEMISPHERE_INIT_STRING));
} else {
send_blob_start(instance, _initialisation_blob, sizeof(_initialisation_blob));
}
}
}
if (_auto_config == GPS_AUTO_CONFIG_ENABLE && new_gps == nullptr) {
send_blob_update(instance);
}
while (initblob_state[instance].remaining == 0 && _port[instance]->available() > 0
&& new_gps == nullptr) {
uint8_t data = _port[instance]->read();
/*
running a uBlox at less than 38400 will lead to packet
corruption, as we can't receive the packets in the 200ms
window for 5Hz fixes. The NMEA startup message should force
the uBlox into 115200 no matter what rate it is configured
for.
*/
if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_UBLOX) &&
((!_auto_config && _baudrates[dstate->current_baud] >= 38400) ||
_baudrates[dstate->current_baud] == 115200) &&
AP_GPS_UBLOX::_detect(dstate->ublox_detect_state, data)) {
new_gps = new AP_GPS_UBLOX(*this, state[instance], _port[instance]);
}
#ifndef HAL_BUILD_AP_PERIPH
#if !HAL_MINIMIZE_FEATURES
// we drop the MTK drivers when building a small build as they are so rarely used
// and are surprisingly large
else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_MTK19) &&
AP_GPS_MTK19::_detect(dstate->mtk19_detect_state, data)) {
new_gps = new AP_GPS_MTK19(*this, state[instance], _port[instance]);
} else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_MTK) &&
AP_GPS_MTK::_detect(dstate->mtk_detect_state, data)) {
new_gps = new AP_GPS_MTK(*this, state[instance], _port[instance]);
}
#endif
else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_SBP) &&
AP_GPS_SBP2::_detect(dstate->sbp2_detect_state, data)) {
new_gps = new AP_GPS_SBP2(*this, state[instance], _port[instance]);
}
else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_SBP) &&
AP_GPS_SBP::_detect(dstate->sbp_detect_state, data)) {
new_gps = new AP_GPS_SBP(*this, state[instance], _port[instance]);
}
#if !HAL_MINIMIZE_FEATURES
else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_SIRF) &&
AP_GPS_SIRF::_detect(dstate->sirf_detect_state, data)) {
new_gps = new AP_GPS_SIRF(*this, state[instance], _port[instance]);
}
#endif
else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_ERB) &&
AP_GPS_ERB::_detect(dstate->erb_detect_state, data)) {
new_gps = new AP_GPS_ERB(*this, state[instance], _port[instance]);
} else if ((_type[instance] == GPS_TYPE_NMEA ||
_type[instance] == GPS_TYPE_HEMI) &&
AP_GPS_NMEA::_detect(dstate->nmea_detect_state, data)) {
new_gps = new AP_GPS_NMEA(*this, state[instance], _port[instance]);
}
#endif // HAL_BUILD_AP_PERIPH
if (new_gps) {
goto found_gps;
}
}
found_gps:
if (new_gps != nullptr) {
state[instance].status = NO_FIX;
drivers[instance] = new_gps;
timing[instance].last_message_time_ms = now;
timing[instance].delta_time_ms = GPS_TIMEOUT_MS;
new_gps->broadcast_gps_type();
}
}
AP_GPS::GPS_Status AP_GPS::highest_supported_status(uint8_t instance) const
{
if (instance < GPS_MAX_RECEIVERS && drivers[instance] != nullptr) {
return drivers[instance]->highest_supported_status();
}
return AP_GPS::GPS_OK_FIX_3D;
}
bool AP_GPS::should_log() const
{
#ifndef HAL_BUILD_AP_PERIPH
AP_Logger *logger = AP_Logger::get_singleton();
if (logger == nullptr) {
return false;
}
if (_log_gps_bit == (uint32_t)-1) {
return false;
}
if (!logger->should_log(_log_gps_bit)) {
return false;
}
return true;
#else
return false;
#endif
}
/*
update one GPS instance. This should be called at 10Hz or greater
*/
void AP_GPS::update_instance(uint8_t instance)
{
if (_type[instance] == GPS_TYPE_HIL) {
// in HIL, leave info alone
return;
}
if (_type[instance] == GPS_TYPE_NONE) {
// not enabled
state[instance].status = NO_GPS;
state[instance].hdop = GPS_UNKNOWN_DOP;
state[instance].vdop = GPS_UNKNOWN_DOP;
return;
}
if (locked_ports & (1U<<instance)) {
// the port is locked by another driver
return;
}
if (drivers[instance] == nullptr || state[instance].status == NO_GPS) {
// we don't yet know the GPS type of this one, or it has timed
// out and needs to be re-initialised
detect_instance(instance);
return;
}
if (_auto_config == GPS_AUTO_CONFIG_ENABLE) {
send_blob_update(instance);
}
// we have an active driver for this instance
bool result = drivers[instance]->read();
uint32_t tnow = AP_HAL::millis();
// if we did not get a message, and the idle timer of 2 seconds
// has expired, re-initialise the GPS. This will cause GPS
// detection to run again
bool data_should_be_logged = false;
if (!result) {
if (tnow - timing[instance].last_message_time_ms > GPS_TIMEOUT_MS) {
memset((void *)&state[instance], 0, sizeof(state[instance]));
state[instance].instance = instance;
state[instance].hdop = GPS_UNKNOWN_DOP;
state[instance].vdop = GPS_UNKNOWN_DOP;
timing[instance].last_message_time_ms = tnow;
timing[instance].delta_time_ms = GPS_TIMEOUT_MS;
// do not try to detect again if type is MAV
if (_type[instance] == GPS_TYPE_MAV) {
state[instance].status = NO_FIX;
} else {
// free the driver before we run the next detection, so we
// don't end up with two allocated at any time
delete drivers[instance];
drivers[instance] = nullptr;
state[instance].status = NO_GPS;
}
// log this data as a "flag" that the GPS is no longer
// valid (see PR#8144)
data_should_be_logged = true;
}
} else {
if (state[instance].uart_timestamp_ms != 0) {
// set the timestamp for this messages based on
// set_uart_timestamp() in backend, if available
tnow = state[instance].uart_timestamp_ms;
state[instance].uart_timestamp_ms = 0;
}
// delta will only be correct after parsing two messages
timing[instance].delta_time_ms = tnow - timing[instance].last_message_time_ms;
timing[instance].last_message_time_ms = tnow;
if (state[instance].status >= GPS_OK_FIX_2D) {
timing[instance].last_fix_time_ms = tnow;
}
data_should_be_logged = true;
}
#ifndef HAL_BUILD_AP_PERIPH
if (data_should_be_logged &&
(should_log() || AP::ahrs().have_ekf_logging())) {
AP::logger().Write_GPS(instance);
}
if (state[instance].status >= GPS_OK_FIX_3D) {
const uint64_t now = time_epoch_usec(instance);
if (now != 0) {
AP::rtc().set_utc_usec(now, AP_RTC::SOURCE_GPS);
}
}
#else
(void)data_should_be_logged;
#endif
}
/*
update all GPS instances
*/
void AP_GPS::update(void)
{
for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
update_instance(i);
}
// calculate number of instances
for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
if (state[i].status != NO_GPS) {
num_instances = i+1;
}
}
#if defined(GPS_BLENDED_INSTANCE)
// if blending is requested, attempt to calculate weighting for each GPS
if (_auto_switch == 2) {
_output_is_blended = calc_blend_weights();
// adjust blend health counter
if (!_output_is_blended) {
_blend_health_counter = MIN(_blend_health_counter+BLEND_COUNTER_FAILURE_INCREMENT, 100);
} else if (_blend_health_counter > 0) {
_blend_health_counter--;
}
// stop blending if unhealthy
if (_blend_health_counter >= 50) {
_output_is_blended = false;
}
} else {
_output_is_blended = false;
_blend_health_counter = 0;
}
if (_output_is_blended) {
// Use the weighting to calculate blended GPS states
calc_blended_state();
// set primary to the virtual instance
primary_instance = GPS_BLENDED_INSTANCE;
} else {
// use switch logic to find best GPS
uint32_t now = AP_HAL::millis();
if (_auto_switch == 3) {
// select the second GPS instance
primary_instance = 1;
} else if (_auto_switch >= 1) {
// handling switching away from blended GPS
if (primary_instance == GPS_BLENDED_INSTANCE) {
primary_instance = 0;
for (uint8_t i=1; i<GPS_MAX_RECEIVERS; i++) {
// choose GPS with highest state or higher number of satellites
if ((state[i].status > state[primary_instance].status) ||
((state[i].status == state[primary_instance].status) && (state[i].num_sats > state[primary_instance].num_sats))) {
primary_instance = i;
_last_instance_swap_ms = now;
}
}
} else {
// handle switch between real GPSs
for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
if (i == primary_instance) {
continue;
}
if (state[i].status > state[primary_instance].status) {
// we have a higher status lock, or primary is set to the blended GPS, change GPS
primary_instance = i;
_last_instance_swap_ms = now;
continue;
}
bool another_gps_has_1_or_more_sats = (state[i].num_sats >= state[primary_instance].num_sats + 1);
if (state[i].status == state[primary_instance].status && another_gps_has_1_or_more_sats) {
bool another_gps_has_2_or_more_sats = (state[i].num_sats >= state[primary_instance].num_sats + 2);
if ((another_gps_has_1_or_more_sats && (now - _last_instance_swap_ms) >= 20000) ||
(another_gps_has_2_or_more_sats && (now - _last_instance_swap_ms) >= 5000)) {
// this GPS has more satellites than the
// current primary, switch primary. Once we switch we will
// then tend to stick to the new GPS as primary. We don't
// want to switch too often as it will look like a
// position shift to the controllers.
primary_instance = i;
_last_instance_swap_ms = now;
}
}
}
}
} else {
// AUTO_SWITCH is 0 so no switching of GPSs
primary_instance = 0;
}
// copy the primary instance to the blended instance in case it is enabled later
state[GPS_BLENDED_INSTANCE] = state[primary_instance];
_blended_antenna_offset = _antenna_offset[primary_instance];
}
#endif // GPS_BLENDED_INSTANCE
#ifndef HAL_BUILD_AP_PERIPH
// update notify with gps status. We always base this on the primary_instance
AP_Notify::flags.gps_status = state[primary_instance].status;
AP_Notify::flags.gps_num_sats = state[primary_instance].num_sats;
#endif
}
void AP_GPS::handle_gps_inject(const mavlink_message_t &msg)
{
mavlink_gps_inject_data_t packet;
mavlink_msg_gps_inject_data_decode(&msg, &packet);
//TODO: check target
inject_data(packet.data, packet.len);
}
/*
pass along a mavlink message (for MAV type)
*/
void AP_GPS::handle_msg(const mavlink_message_t &msg)
{
switch (msg.msgid) {
case MAVLINK_MSG_ID_GPS_RTCM_DATA:
// pass data to de-fragmenter
handle_gps_rtcm_data(msg);
break;
case MAVLINK_MSG_ID_GPS_INJECT_DATA:
handle_gps_inject(msg);
break;
default: {
uint8_t i;
for (i=0; i<num_instances; i++) {
if ((drivers[i] != nullptr) && (_type[i] != GPS_TYPE_NONE)) {
drivers[i]->handle_msg(msg);
}
}
break;
}
}
}
/*
set HIL (hardware in the loop) status for a GPS instance
*/
void AP_GPS::setHIL(uint8_t instance, GPS_Status _status, uint64_t time_epoch_ms,
const Location &_location, const Vector3f &_velocity, uint8_t _num_sats,
uint16_t hdop)
{
if (instance >= GPS_MAX_RECEIVERS) {
return;
}
const uint32_t tnow = AP_HAL::millis();
GPS_State &istate = state[instance];
istate.status = _status;
istate.location = _location;
istate.velocity = _velocity;
istate.ground_speed = norm(istate.velocity.x, istate.velocity.y);
istate.ground_course = wrap_360(degrees(atan2f(istate.velocity.y, istate.velocity.x)));
istate.hdop = hdop;
istate.num_sats = _num_sats;
istate.last_gps_time_ms = tnow;
uint64_t gps_time_ms = time_epoch_ms - UNIX_OFFSET_MSEC;
istate.time_week = gps_time_ms / AP_MSEC_PER_WEEK;
istate.time_week_ms = gps_time_ms - istate.time_week * AP_MSEC_PER_WEEK;
timing[instance].last_message_time_ms = tnow;
timing[instance].last_fix_time_ms = tnow;
_type[instance].set(GPS_TYPE_HIL);
}
// set accuracy for HIL
void AP_GPS::setHIL_Accuracy(uint8_t instance, float vdop, float hacc, float vacc, float sacc, bool _have_vertical_velocity, uint32_t sample_ms)
{
if (instance >= GPS_MAX_RECEIVERS) {
return;
}
GPS_State &istate = state[instance];
istate.vdop = vdop * 100;
istate.horizontal_accuracy = hacc;
istate.vertical_accuracy = vacc;
istate.speed_accuracy = sacc;
istate.have_horizontal_accuracy = true;
istate.have_vertical_accuracy = true;
istate.have_speed_accuracy = true;
istate.have_vertical_velocity |= _have_vertical_velocity;
if (sample_ms != 0) {
timing[instance].last_message_time_ms = sample_ms;
timing[instance].last_fix_time_ms = sample_ms;
}
}
/**
Lock a GPS port, preventing the GPS driver from using it. This can
be used to allow a user to control a GPS port via the
SERIAL_CONTROL protocol
*/
void AP_GPS::lock_port(uint8_t instance, bool lock)
{
if (instance >= GPS_MAX_RECEIVERS) {
return;
}
if (lock) {
locked_ports |= (1U<<instance);
} else {
locked_ports &= ~(1U<<instance);
}
}
// Inject a packet of raw binary to a GPS
void AP_GPS::inject_data(uint8_t *data, uint16_t len)
{
//Support broadcasting to all GPSes.
if (_inject_to == GPS_RTK_INJECT_TO_ALL) {
for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
inject_data(i, data, len);
}
} else {
inject_data(_inject_to, data, len);
}
}
void AP_GPS::inject_data(uint8_t instance, uint8_t *data, uint16_t len)
{
if (instance < GPS_MAX_RECEIVERS && drivers[instance] != nullptr) {
drivers[instance]->inject_data(data, len);
}
}
void AP_GPS::send_mavlink_gps_raw(mavlink_channel_t chan)
{
static uint32_t last_send_time_ms[MAVLINK_COMM_NUM_BUFFERS];
if (status(0) > AP_GPS::NO_GPS) {
// when we have a GPS then only send new data
if (last_send_time_ms[chan] == last_message_time_ms(0)) {
return;
}
last_send_time_ms[chan] = last_message_time_ms(0);
} else {
// when we don't have a GPS then send at 1Hz
uint32_t now = AP_HAL::millis();
if (now - last_send_time_ms[chan] < 1000) {
return;
}
last_send_time_ms[chan] = now;
}
const Location &loc = location(0);
float hacc = 0.0f;
float vacc = 0.0f;
float sacc = 0.0f;
horizontal_accuracy(0, hacc);
vertical_accuracy(0, vacc);
speed_accuracy(0, sacc);
mavlink_msg_gps_raw_int_send(
chan,
last_fix_time_ms(0)*(uint64_t)1000,
status(0),
loc.lat, // in 1E7 degrees
loc.lng, // in 1E7 degrees
loc.alt * 10UL, // in mm
get_hdop(0),
get_vdop(0),
ground_speed(0)*100, // cm/s
ground_course(0)*100, // 1/100 degrees,
num_sats(0),
0, // TODO: Elipsoid height in mm
hacc * 1000, // one-sigma standard deviation in mm
vacc * 1000, // one-sigma standard deviation in mm
sacc * 1000, // one-sigma standard deviation in mm/s
0); // TODO one-sigma heading accuracy standard deviation
}
#if GPS_MAX_RECEIVERS > 1
void AP_GPS::send_mavlink_gps2_raw(mavlink_channel_t chan)
{
static uint32_t last_send_time_ms[MAVLINK_COMM_NUM_BUFFERS];
if (num_instances < 2 || status(1) <= AP_GPS::NO_GPS) {
return;
}
// when we have a GPS then only send new data
if (last_send_time_ms[chan] == last_message_time_ms(1)) {
return;
}
last_send_time_ms[chan] = last_message_time_ms(1);
const Location &loc = location(1);
mavlink_msg_gps2_raw_send(
chan,