APM:Libraries
AP_GPS.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 #include "AP_GPS.h"
16 
17 #include <AP_Common/AP_Common.h>
18 #include <AP_HAL/AP_HAL.h>
19 #include <AP_Math/AP_Math.h>
20 #include <AP_Notify/AP_Notify.h>
21 #include <GCS_MAVLink/GCS.h>
23 #include <climits>
24 
25 #include "AP_GPS_NOVA.h"
26 #include "AP_GPS_ERB.h"
27 #include "AP_GPS_GSOF.h"
28 #include "AP_GPS_MTK.h"
29 #include "AP_GPS_MTK19.h"
30 #include "AP_GPS_NMEA.h"
31 #include "AP_GPS_SBF.h"
32 #include "AP_GPS_SBP.h"
33 #include "AP_GPS_SBP2.h"
34 #include "AP_GPS_SIRF.h"
35 #include "AP_GPS_UBLOX.h"
36 #include "AP_GPS_MAV.h"
37 #include "GPS_Backend.h"
38 
39 #if HAL_WITH_UAVCAN
41 #include <AP_UAVCAN/AP_UAVCAN.h>
42 #include "AP_GPS_UAVCAN.h"
43 #endif
44 
45 #define GPS_BAUD_TIME_MS 1200
46 #define GPS_TIMEOUT_MS 4000u
47 
48 // defines used to specify the mask position for use of different accuracy metrics in the blending algorithm
49 #define BLEND_MASK_USE_HPOS_ACC 1
50 #define BLEND_MASK_USE_VPOS_ACC 2
51 #define BLEND_MASK_USE_SPD_ACC 4
52 #define BLEND_COUNTER_FAILURE_INCREMENT 10
53 
54 extern const AP_HAL::HAL &hal;
55 
56 // baudrates to try to detect GPSes with
57 const uint32_t AP_GPS::_baudrates[] = {9600U, 115200U, 4800U, 19200U, 38400U, 57600U, 230400U};
58 
59 // initialisation blobs to send to the GPS to try to get it into the
60 // right mode
62 
64 
65 // table of user settable parameters
67  // @Param: TYPE
68  // @DisplayName: GPS type
69  // @Description: GPS type
70  // @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
71  // @RebootRequired: True
72  // @User: Advanced
73  AP_GROUPINFO("TYPE", 0, AP_GPS, _type[0], HAL_GPS_TYPE_DEFAULT),
74 
75  // @Param: TYPE2
76  // @DisplayName: 2nd GPS type
77  // @Description: GPS type of 2nd GPS
78  // @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
79  // @RebootRequired: True
80  // @User: Advanced
81  AP_GROUPINFO("TYPE2", 1, AP_GPS, _type[1], 0),
82 
83  // @Param: NAVFILTER
84  // @DisplayName: Navigation filter setting
85  // @Description: Navigation filter engine setting
86  // @Values: 0:Portable,2:Stationary,3:Pedestrian,4:Automotive,5:Sea,6:Airborne1G,7:Airborne2G,8:Airborne4G
87  // @User: Advanced
88  AP_GROUPINFO("NAVFILTER", 2, AP_GPS, _navfilter, GPS_ENGINE_AIRBORNE_4G),
89 
90  // @Param: AUTO_SWITCH
91  // @DisplayName: Automatic Switchover Setting
92  // @Description: Automatic switchover to GPS reporting best lock
93  // @Values: 0:Disabled,1:UseBest,2:Blend
94  // @User: Advanced
95  AP_GROUPINFO("AUTO_SWITCH", 3, AP_GPS, _auto_switch, 1),
96 
97  // @Param: MIN_DGPS
98  // @DisplayName: Minimum Lock Type Accepted for DGPS
99  // @Description: Sets the minimum type of differential GPS corrections required before allowing to switch into DGPS mode.
100  // @Values: 0:Any,50:FloatRTK,100:IntegerRTK
101  // @User: Advanced
102  // @RebootRequired: True
103  AP_GROUPINFO("MIN_DGPS", 4, AP_GPS, _min_dgps, 100),
104 
105  // @Param: SBAS_MODE
106  // @DisplayName: SBAS Mode
107  // @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.
108  // @Values: 0:Disabled,1:Enabled,2:NoChange
109  // @User: Advanced
110  AP_GROUPINFO("SBAS_MODE", 5, AP_GPS, _sbas_mode, 2),
111 
112  // @Param: MIN_ELEV
113  // @DisplayName: Minimum elevation
114  // @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.
115  // @Range: -100 90
116  // @Units: deg
117  // @User: Advanced
118  AP_GROUPINFO("MIN_ELEV", 6, AP_GPS, _min_elevation, -100),
119 
120  // @Param: INJECT_TO
121  // @DisplayName: Destination for GPS_INJECT_DATA MAVLink packets
122  // @Description: The GGS can send raw serial packets to inject data to multiple GPSes.
123  // @Values: 0:send to first GPS,1:send to 2nd GPS,127:send to all
124  // @User: Advanced
125  AP_GROUPINFO("INJECT_TO", 7, AP_GPS, _inject_to, GPS_RTK_INJECT_TO_ALL),
126 
127  // @Param: SBP_LOGMASK
128  // @DisplayName: Swift Binary Protocol Logging Mask
129  // @Description: Masked with the SBP msg_type field to determine whether SBR1/SBR2 data is logged
130  // @Values: 0:None (0x0000),-1:All (0xFFFF),-256:External only (0xFF00)
131  // @User: Advanced
132  AP_GROUPINFO("SBP_LOGMASK", 8, AP_GPS, _sbp_logmask, 0xFF00),
133 
134  // @Param: RAW_DATA
135  // @DisplayName: Raw data logging
136  // @Description: Handles logging raw data; on uBlox chips that support raw data this will log RXM messages into dataflash log; 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
137  // @Values: 0:Ignore,1:Always log,2:Stop logging when disarmed (SBF only),5:Only log every five samples (uBlox only)
138  // @RebootRequired: True
139  // @User: Advanced
140  AP_GROUPINFO("RAW_DATA", 9, AP_GPS, _raw_data, 0),
141 
142  // @Param: GNSS_MODE
143  // @DisplayName: GNSS system configuration
144  // @Description: Bitmask for what GNSS system to use on the first GPS (all unchecked or zero to leave GPS as configured)
145  // @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
146  // @Bitmask: 0:GPS,1:SBAS,2:Galileo,3:Beidou,4:IMES,5:QZSS,6:GLOSNASS
147  // @User: Advanced
148  AP_GROUPINFO("GNSS_MODE", 10, AP_GPS, _gnss_mode[0], 0),
149 
150  // @Param: SAVE_CFG
151  // @DisplayName: Save GPS configuration
152  // @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.
153  // @Values: 0:Do not save config,1:Save config,2:Save only when needed
154  // @User: Advanced
155  AP_GROUPINFO("SAVE_CFG", 11, AP_GPS, _save_config, 2),
156 
157  // @Param: GNSS_MODE2
158  // @DisplayName: GNSS system configuration
159  // @Description: Bitmask for what GNSS system to use on the second GPS (all unchecked or zero to leave GPS as configured)
160  // @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
161  // @Bitmask: 0:GPS,1:SBAS,2:Galileo,3:Beidou,4:IMES,5:QZSS,6:GLOSNASS
162  // @User: Advanced
163  AP_GROUPINFO("GNSS_MODE2", 12, AP_GPS, _gnss_mode[1], 0),
164 
165  // @Param: AUTO_CONFIG
166  // @DisplayName: Automatic GPS configuration
167  // @Description: Controls if the autopilot should automatically configure the GPS based on the parameters and default settings
168  // @Values: 0:Disables automatic configuration,1:Enable automatic configuration
169  // @User: Advanced
170  AP_GROUPINFO("AUTO_CONFIG", 13, AP_GPS, _auto_config, 1),
171 
172  // @Param: RATE_MS
173  // @DisplayName: GPS update rate in milliseconds
174  // @Description: Controls how often the GPS should provide a position update. Lowering below 5Hz is not allowed
175  // @Units: ms
176  // @Values: 100:10Hz,125:8Hz,200:5Hz
177  // @Range: 50 200
178  // @User: Advanced
179  AP_GROUPINFO("RATE_MS", 14, AP_GPS, _rate_ms[0], 200),
180 
181  // @Param: RATE_MS2
182  // @DisplayName: GPS 2 update rate in milliseconds
183  // @Description: Controls how often the GPS should provide a position update. Lowering below 5Hz is not allowed
184  // @Units: ms
185  // @Values: 100:10Hz,125:8Hz,200:5Hz
186  // @Range: 50 200
187  // @User: Advanced
188  AP_GROUPINFO("RATE_MS2", 15, AP_GPS, _rate_ms[1], 200),
189 
190  // @Param: POS1_X
191  // @DisplayName: Antenna X position offset
192  // @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.
193  // @Units: m
194  // @User: Advanced
195 
196  // @Param: POS1_Y
197  // @DisplayName: Antenna Y position offset
198  // @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.
199  // @Units: m
200  // @User: Advanced
201 
202  // @Param: POS1_Z
203  // @DisplayName: Antenna Z position offset
204  // @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.
205  // @Units: m
206  // @User: Advanced
207  AP_GROUPINFO("POS1", 16, AP_GPS, _antenna_offset[0], 0.0f),
208 
209  // @Param: POS2_X
210  // @DisplayName: Antenna X position offset
211  // @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.
212  // @Units: m
213  // @User: Advanced
214 
215  // @Param: POS2_Y
216  // @DisplayName: Antenna Y position offset
217  // @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.
218  // @Units: m
219  // @User: Advanced
220 
221  // @Param: POS2_Z
222  // @DisplayName: Antenna Z position offset
223  // @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.
224  // @Units: m
225  // @User: Advanced
226  AP_GROUPINFO("POS2", 17, AP_GPS, _antenna_offset[1], 0.0f),
227 
228  // @Param: DELAY_MS
229  // @DisplayName: GPS delay in milliseconds
230  // @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.
231  // @Units: ms
232  // @Range: 0 250
233  // @User: Advanced
234  // @RebootRequired: True
235  AP_GROUPINFO("DELAY_MS", 18, AP_GPS, _delay_ms[0], 0),
236 
237  // @Param: DELAY_MS2
238  // @DisplayName: GPS 2 delay in milliseconds
239  // @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.
240  // @Units: ms
241  // @Range: 0 250
242  // @User: Advanced
243  // @RebootRequired: True
244  AP_GROUPINFO("DELAY_MS2", 19, AP_GPS, _delay_ms[1], 0),
245 
246  // @Param: BLEND_MASK
247  // @DisplayName: Multi GPS Blending Mask
248  // @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
249  // @Bitmask: 0:Horiz Pos,1:Vert Pos,2:Speed
250  // @User: Advanced
251  AP_GROUPINFO("BLEND_MASK", 20, AP_GPS, _blend_mask, 5),
252 
253  // @Param: BLEND_TC
254  // @DisplayName: Blending time constant
255  // @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.
256  // @Units: s
257  // @Range: 5.0 30.0
258  // @User: Advanced
259  AP_GROUPINFO("BLEND_TC", 21, AP_GPS, _blend_tc, 10.0f),
260 
262 };
263 
264 // constructor
266 {
267  static_assert((sizeof(_initialisation_blob) * (CHAR_BIT + 2)) < (4800 * GPS_BAUD_TIME_MS * 1e-3),
268  "GPS initilisation blob is to large to be completely sent before the baud rate changes");
269 
271 
272  if (_singleton != nullptr) {
273  AP_HAL::panic("AP_GPS must be singleton");
274  }
275  _singleton = this;
276 }
277 
280 {
281  primary_instance = 0;
282 
283  // search for serial ports with gps protocol
287 
288  // Initialise class variables used to do GPS blending
289  _omega_lpf = 1.0f / constrain_float(_blend_tc, 5.0f, 30.0f);
290 
291  // prep the state instance fields
292  for (uint8_t i = 0; i < GPS_MAX_INSTANCES; i++) {
293  state[i].instance = i;
294  }
295 
296  // sanity check update rate
297  for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
298  if (_rate_ms[i] <= 0 || _rate_ms[i] > GPS_MAX_RATE_MS) {
300  }
301  }
302 }
303 
304 // return number of active GPS sensors. Note that if the first GPS
305 // is not present but the 2nd is then we return 2. Note that a blended
306 // GPS solution is treated as an additional sensor.
307 uint8_t AP_GPS::num_sensors(void) const
308 {
309  if (!_output_is_blended) {
310  return num_instances;
311  } else {
312  return num_instances+1;
313  }
314 }
315 
316 bool AP_GPS::speed_accuracy(uint8_t instance, float &sacc) const
317 {
318  if (state[instance].have_speed_accuracy) {
319  sacc = state[instance].speed_accuracy;
320  return true;
321  }
322  return false;
323 }
324 
325 bool AP_GPS::horizontal_accuracy(uint8_t instance, float &hacc) const
326 {
327  if (state[instance].have_horizontal_accuracy) {
328  hacc = state[instance].horizontal_accuracy;
329  return true;
330  }
331  return false;
332 }
333 
334 bool AP_GPS::vertical_accuracy(uint8_t instance, float &vacc) const
335 {
336  if (state[instance].have_vertical_accuracy) {
337  vacc = state[instance].vertical_accuracy;
338  return true;
339  }
340  return false;
341 }
342 
343 
347 uint64_t AP_GPS::time_epoch_convert(uint16_t gps_week, uint32_t gps_ms)
348 {
349  uint64_t fix_time_ms = UNIX_OFFSET_MSEC + gps_week * AP_MSEC_PER_WEEK + gps_ms;
350  return fix_time_ms;
351 }
352 
356 uint64_t AP_GPS::time_epoch_usec(uint8_t instance) const
357 {
358  const GPS_State &istate = state[instance];
359  if (istate.last_gps_time_ms == 0) {
360  return 0;
361  }
362  uint64_t fix_time_ms = time_epoch_convert(istate.time_week, istate.time_week_ms);
363  // add in the milliseconds since the last fix
364  return (fix_time_ms + (AP_HAL::millis() - istate.last_gps_time_ms)) * 1000ULL;
365 }
366 
367 /*
368  send some more initialisation string bytes if there is room in the
369  UART transmit buffer
370  */
371 void AP_GPS::send_blob_start(uint8_t instance, const char *_blob, uint16_t size)
372 {
373  initblob_state[instance].blob = _blob;
374  initblob_state[instance].remaining = size;
375 }
376 
377 /*
378  send some more initialisation string bytes if there is room in the
379  UART transmit buffer
380  */
381 void AP_GPS::send_blob_update(uint8_t instance)
382 {
383  // exit immediately if no uart for this instance
384  if (_port[instance] == nullptr) {
385  return;
386  }
387 
388  // see if we can write some more of the initialisation blob
389  if (initblob_state[instance].remaining > 0) {
390  int16_t space = _port[instance]->txspace();
391  if (space > (int16_t)initblob_state[instance].remaining) {
392  space = initblob_state[instance].remaining;
393  }
394  while (space > 0) {
395  _port[instance]->write(*initblob_state[instance].blob);
396  initblob_state[instance].blob++;
397  space--;
398  initblob_state[instance].remaining--;
399  }
400  }
401 }
402 
403 /*
404  run detection step for one GPS instance. If this finds a GPS then it
405  will fill in drivers[instance] and change state[instance].status
406  from NO_GPS to NO_FIX.
407  */
408 void AP_GPS::detect_instance(uint8_t instance)
409 {
410  AP_GPS_Backend *new_gps = nullptr;
411  struct detect_state *dstate = &detect_state[instance];
412  const uint32_t now = AP_HAL::millis();
413 
414  state[instance].status = NO_GPS;
415  state[instance].hdop = GPS_UNKNOWN_DOP;
416  state[instance].vdop = GPS_UNKNOWN_DOP;
417 
418  switch (_type[instance]) {
419  // user has to explicitly set the MAV type, do not use AUTO
420  // do not try to detect the MAV type, assume it's there
421  case GPS_TYPE_MAV:
422  dstate->auto_detected_baud = false; // specified, not detected
423  new_gps = new AP_GPS_MAV(*this, state[instance], nullptr);
424  goto found_gps;
425  break;
426 
427 #if HAL_WITH_UAVCAN
428  // user has to explicitly set the UAVCAN type, do not use AUTO
429  case GPS_TYPE_UAVCAN:
430  dstate->auto_detected_baud = false; // specified, not detected
431  if (AP_BoardConfig_CAN::get_can_num_ifaces() >= 1) {
432  for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_DRIVERS; i++) {
433  if (hal.can_mgr[i] != nullptr) {
434  AP_UAVCAN *uavcan = hal.can_mgr[i]->get_UAVCAN();
435 
436  if (uavcan != nullptr) {
437  uint8_t gps_node = uavcan->find_gps_without_listener();
438 
439  if (gps_node != UINT8_MAX) {
440  new_gps = new AP_GPS_UAVCAN(*this, state[instance], nullptr);
441  ((AP_GPS_UAVCAN*) new_gps)->set_uavcan_manager(i);
442  if (uavcan->register_gps_listener_to_node(new_gps, gps_node)) {
443  if (AP_BoardConfig_CAN::get_can_debug() >= 2) {
444  printf("AP_GPS_UAVCAN registered\n\r");
445  }
446  goto found_gps;
447  } else {
448  delete new_gps;
449  }
450  }
451  }
452  }
453  }
454  }
455  return;
456 #endif
457 
458  default:
459  break;
460  }
461 
462  if (_port[instance] == nullptr) {
463  // UART not available
464  return;
465  }
466 
467  // all remaining drivers automatically cycle through baud rates to detect
468  // the correct baud rate, and should have the selected baud broadcast
469  dstate->auto_detected_baud = true;
470 
471  switch (_type[instance]) {
472  // by default the sbf/trimble gps outputs no data on its port, until configured.
473  case GPS_TYPE_SBF:
474  new_gps = new AP_GPS_SBF(*this, state[instance], _port[instance]);
475  break;
476 
477  case GPS_TYPE_GSOF:
478  new_gps = new AP_GPS_GSOF(*this, state[instance], _port[instance]);
479  break;
480 
481  case GPS_TYPE_NOVA:
482  new_gps = new AP_GPS_NOVA(*this, state[instance], _port[instance]);
483  break;
484 
485  default:
486  break;
487  }
488 
489  if (now - dstate->last_baud_change_ms > GPS_BAUD_TIME_MS) {
490  // try the next baud rate
491  // incrementing like this will skip the first element in array of bauds
492  // this is okay, and relied upon
493  dstate->current_baud++;
494  if (dstate->current_baud == ARRAY_SIZE(_baudrates)) {
495  dstate->current_baud = 0;
496  }
497  uint32_t baudrate = _baudrates[dstate->current_baud];
498  _port[instance]->begin(baudrate);
500  dstate->last_baud_change_ms = now;
501 
502  if (_auto_config == GPS_AUTO_CONFIG_ENABLE && new_gps == nullptr) {
504  }
505  }
506 
507  if (_auto_config == GPS_AUTO_CONFIG_ENABLE && new_gps == nullptr) {
508  send_blob_update(instance);
509  }
510 
511  while (initblob_state[instance].remaining == 0 && _port[instance]->available() > 0
512  && new_gps == nullptr) {
513  uint8_t data = _port[instance]->read();
514  /*
515  running a uBlox at less than 38400 will lead to packet
516  corruption, as we can't receive the packets in the 200ms
517  window for 5Hz fixes. The NMEA startup message should force
518  the uBlox into 115200 no matter what rate it is configured
519  for.
520  */
521  if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_UBLOX) &&
522  ((!_auto_config && _baudrates[dstate->current_baud] >= 38400) ||
523  _baudrates[dstate->current_baud] == 115200) &&
524  AP_GPS_UBLOX::_detect(dstate->ublox_detect_state, data)) {
525  new_gps = new AP_GPS_UBLOX(*this, state[instance], _port[instance]);
526  }
527 #if !HAL_MINIMIZE_FEATURES
528  // we drop the MTK drivers when building a small build as they are so rarely used
529  // and are surprisingly large
530  else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_MTK19) &&
531  AP_GPS_MTK19::_detect(dstate->mtk19_detect_state, data)) {
532  new_gps = new AP_GPS_MTK19(*this, state[instance], _port[instance]);
533  } else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_MTK) &&
534  AP_GPS_MTK::_detect(dstate->mtk_detect_state, data)) {
535  new_gps = new AP_GPS_MTK(*this, state[instance], _port[instance]);
536  }
537 #endif
538  else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_SBP) &&
539  AP_GPS_SBP2::_detect(dstate->sbp2_detect_state, data)) {
540  new_gps = new AP_GPS_SBP2(*this, state[instance], _port[instance]);
541  }
542  else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_SBP) &&
543  AP_GPS_SBP::_detect(dstate->sbp_detect_state, data)) {
544  new_gps = new AP_GPS_SBP(*this, state[instance], _port[instance]);
545  }
546 #if !HAL_MINIMIZE_FEATURES
547  else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_SIRF) &&
548  AP_GPS_SIRF::_detect(dstate->sirf_detect_state, data)) {
549  new_gps = new AP_GPS_SIRF(*this, state[instance], _port[instance]);
550  }
551 #endif
552  else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_ERB) &&
553  AP_GPS_ERB::_detect(dstate->erb_detect_state, data)) {
554  new_gps = new AP_GPS_ERB(*this, state[instance], _port[instance]);
555  } else if (_type[instance] == GPS_TYPE_NMEA &&
556  AP_GPS_NMEA::_detect(dstate->nmea_detect_state, data)) {
557  new_gps = new AP_GPS_NMEA(*this, state[instance], _port[instance]);
558  }
559  }
560 
561 found_gps:
562  if (new_gps != nullptr) {
563  state[instance].status = NO_FIX;
564  drivers[instance] = new_gps;
565  timing[instance].last_message_time_ms = now;
566  timing[instance].delta_time_ms = GPS_TIMEOUT_MS;
567  new_gps->broadcast_gps_type();
568  }
569 }
570 
572 {
573  if (instance < GPS_MAX_RECEIVERS && drivers[instance] != nullptr) {
574  return drivers[instance]->highest_supported_status();
575  }
576  return AP_GPS::GPS_OK_FIX_3D;
577 }
578 
580 {
582  if (instance == nullptr) {
583  return false;
584  }
585  if (_log_gps_bit == (uint32_t)-1) {
586  return false;
587  }
588  if (!instance->should_log(_log_gps_bit)) {
589  return false;
590  }
591  return true;
592 }
593 
594 
595 /*
596  update one GPS instance. This should be called at 10Hz or greater
597  */
598 void AP_GPS::update_instance(uint8_t instance)
599 {
600  if (_type[instance] == GPS_TYPE_HIL) {
601  // in HIL, leave info alone
602  return;
603  }
604  if (_type[instance] == GPS_TYPE_NONE) {
605  // not enabled
606  state[instance].status = NO_GPS;
607  state[instance].hdop = GPS_UNKNOWN_DOP;
608  state[instance].vdop = GPS_UNKNOWN_DOP;
609  return;
610  }
611  if (locked_ports & (1U<<instance)) {
612  // the port is locked by another driver
613  return;
614  }
615 
616  if (drivers[instance] == nullptr || state[instance].status == NO_GPS) {
617  // we don't yet know the GPS type of this one, or it has timed
618  // out and needs to be re-initialised
619  detect_instance(instance);
620  return;
621  }
622 
624  send_blob_update(instance);
625  }
626 
627  // we have an active driver for this instance
628  bool result = drivers[instance]->read();
629  const uint32_t tnow = AP_HAL::millis();
630 
631  // if we did not get a message, and the idle timer of 2 seconds
632  // has expired, re-initialise the GPS. This will cause GPS
633  // detection to run again
634  bool data_should_be_logged = false;
635  if (!result) {
636  if (tnow - timing[instance].last_message_time_ms > GPS_TIMEOUT_MS) {
637  memset(&state[instance], 0, sizeof(state[instance]));
638  state[instance].instance = instance;
639  state[instance].hdop = GPS_UNKNOWN_DOP;
640  state[instance].vdop = GPS_UNKNOWN_DOP;
641  timing[instance].last_message_time_ms = tnow;
642  timing[instance].delta_time_ms = GPS_TIMEOUT_MS;
643  // do not try to detect again if type is MAV
644  if (_type[instance] == GPS_TYPE_MAV) {
645  state[instance].status = NO_FIX;
646  } else {
647  // free the driver before we run the next detection, so we
648  // don't end up with two allocated at any time
649  delete drivers[instance];
650  drivers[instance] = nullptr;
651  state[instance].status = NO_GPS;
652  }
653  // log this data as a "flag" that the GPS is no longer
654  // valid (see PR#8144)
655  data_should_be_logged = true;
656  }
657  } else {
658  // delta will only be correct after parsing two messages
659  timing[instance].delta_time_ms = tnow - timing[instance].last_message_time_ms;
660  timing[instance].last_message_time_ms = tnow;
661  if (state[instance].status >= GPS_OK_FIX_2D) {
662  timing[instance].last_fix_time_ms = tnow;
663  }
664 
665  data_should_be_logged = true;
666  }
667 
668  if (data_should_be_logged &&
669  should_df_log() &&
670  !AP::ahrs().have_ekf_logging()) {
672  }
673 }
674 
675 /*
676  update all GPS instances
677  */
678 void AP_GPS::update(void)
679 {
680  for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
681  update_instance(i);
682  }
683 
684  // calculate number of instances
685  for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
686  if (state[i].status != NO_GPS) {
687  num_instances = i+1;
688  }
689  }
690 
691  // if blending is requested, attempt to calculate weighting for each GPS
692  if (_auto_switch == 2) {
694  // adjust blend health counter
695  if (!_output_is_blended) {
697  } else if (_blend_health_counter > 0) {
699  }
700  // stop blending if unhealthy
701  if (_blend_health_counter >= 50) {
702  _output_is_blended = false;
703  }
704  } else {
705  _output_is_blended = false;
707  }
708 
709  if (_output_is_blended) {
710  // Use the weighting to calculate blended GPS states
712  // set primary to the virtual instance
714  } else {
715  // use switch logic to find best GPS
716  uint32_t now = AP_HAL::millis();
717  if (_auto_switch >= 1) {
718  // handling switching away from blended GPS
720  primary_instance = 0;
721  for (uint8_t i=1; i<GPS_MAX_RECEIVERS; i++) {
722  // choose GPS with highest state or higher number of satellites
723  if ((state[i].status > state[primary_instance].status) ||
724  ((state[i].status == state[primary_instance].status) && (state[i].num_sats > state[primary_instance].num_sats))) {
725  primary_instance = i;
727  }
728  }
729  } else {
730  // handle switch between real GPSs
731  for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
732  if (i == primary_instance) {
733  continue;
734  }
736  // we have a higher status lock, or primary is set to the blended GPS, change GPS
737  primary_instance = i;
739  continue;
740  }
741 
742  bool another_gps_has_1_or_more_sats = (state[i].num_sats >= state[primary_instance].num_sats + 1);
743 
744  if (state[i].status == state[primary_instance].status && another_gps_has_1_or_more_sats) {
745 
746  bool another_gps_has_2_or_more_sats = (state[i].num_sats >= state[primary_instance].num_sats + 2);
747 
748  if ((another_gps_has_1_or_more_sats && (now - _last_instance_swap_ms) >= 20000) ||
749  (another_gps_has_2_or_more_sats && (now - _last_instance_swap_ms) >= 5000)) {
750  // this GPS has more satellites than the
751  // current primary, switch primary. Once we switch we will
752  // then tend to stick to the new GPS as primary. We don't
753  // want to switch too often as it will look like a
754  // position shift to the controllers.
755  primary_instance = i;
757  }
758  }
759  }
760  }
761  } else {
762  // AUTO_SWITCH is 0 so no switching of GPSs
763  primary_instance = 0;
764  }
765 
766  // copy the primary instance to the blended instance in case it is enabled later
769  }
770 
771  // update notify with gps status. We always base this on the primary_instance
774 
775 }
776 
777 void AP_GPS::handle_gps_inject(const mavlink_message_t *msg)
778 {
779  mavlink_gps_inject_data_t packet;
780  mavlink_msg_gps_inject_data_decode(msg, &packet);
781  //TODO: check target
782 
783  inject_data(packet.data, packet.len);
784 }
785 
786 /*
787  pass along a mavlink message (for MAV type)
788  */
789 void AP_GPS::handle_msg(const mavlink_message_t *msg)
790 {
791  switch (msg->msgid) {
792  case MAVLINK_MSG_ID_GPS_RTCM_DATA:
793  // pass data to de-fragmenter
795  break;
796  case MAVLINK_MSG_ID_GPS_INJECT_DATA:
797  handle_gps_inject(msg);
798  break;
799  default: {
800  uint8_t i;
801  for (i=0; i<num_instances; i++) {
802  if ((drivers[i] != nullptr) && (_type[i] != GPS_TYPE_NONE)) {
803  drivers[i]->handle_msg(msg);
804  }
805  }
806  break;
807  }
808  }
809 }
810 
811 /*
812  set HIL (hardware in the loop) status for a GPS instance
813  */
814 void AP_GPS::setHIL(uint8_t instance, GPS_Status _status, uint64_t time_epoch_ms,
815  const Location &_location, const Vector3f &_velocity, uint8_t _num_sats,
816  uint16_t hdop)
817 {
818  if (instance >= GPS_MAX_RECEIVERS) {
819  return;
820  }
821  const uint32_t tnow = AP_HAL::millis();
822  GPS_State &istate = state[instance];
823  istate.status = _status;
824  istate.location = _location;
825  istate.location.options = 0;
826  istate.velocity = _velocity;
827  istate.ground_speed = norm(istate.velocity.x, istate.velocity.y);
828  istate.ground_course = wrap_360(degrees(atan2f(istate.velocity.y, istate.velocity.x)));
829  istate.hdop = hdop;
830  istate.num_sats = _num_sats;
831  istate.last_gps_time_ms = tnow;
832  uint64_t gps_time_ms = time_epoch_ms - UNIX_OFFSET_MSEC;
833  istate.time_week = gps_time_ms / AP_MSEC_PER_WEEK;
834  istate.time_week_ms = gps_time_ms - istate.time_week * AP_MSEC_PER_WEEK;
835  timing[instance].last_message_time_ms = tnow;
836  timing[instance].last_fix_time_ms = tnow;
837  _type[instance].set(GPS_TYPE_HIL);
838 }
839 
840 // set accuracy for HIL
841 void AP_GPS::setHIL_Accuracy(uint8_t instance, float vdop, float hacc, float vacc, float sacc, bool _have_vertical_velocity, uint32_t sample_ms)
842 {
843  if (instance >= GPS_MAX_RECEIVERS) {
844  return;
845  }
846  GPS_State &istate = state[instance];
847  istate.vdop = vdop * 100;
848  istate.horizontal_accuracy = hacc;
849  istate.vertical_accuracy = vacc;
850  istate.speed_accuracy = sacc;
851  istate.have_horizontal_accuracy = true;
852  istate.have_vertical_accuracy = true;
853  istate.have_speed_accuracy = true;
854  istate.have_vertical_velocity |= _have_vertical_velocity;
855  if (sample_ms != 0) {
856  timing[instance].last_message_time_ms = sample_ms;
857  timing[instance].last_fix_time_ms = sample_ms;
858  }
859 }
860 
866 void AP_GPS::lock_port(uint8_t instance, bool lock)
867 {
868 
869  if (instance >= GPS_MAX_RECEIVERS) {
870  return;
871  }
872  if (lock) {
873  locked_ports |= (1U<<instance);
874  } else {
875  locked_ports &= ~(1U<<instance);
876  }
877 }
878 
879 // Inject a packet of raw binary to a GPS
880 void AP_GPS::inject_data(uint8_t *data, uint16_t len)
881 {
882  //Support broadcasting to all GPSes.
884  for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
885  inject_data(i, data, len);
886  }
887  } else {
888  inject_data(_inject_to, data, len);
889  }
890 }
891 
892 void AP_GPS::inject_data(uint8_t instance, uint8_t *data, uint16_t len)
893 {
894  if (instance < GPS_MAX_RECEIVERS && drivers[instance] != nullptr) {
895  drivers[instance]->inject_data(data, len);
896  }
897 }
898 
899 void AP_GPS::send_mavlink_gps_raw(mavlink_channel_t chan)
900 {
901  static uint32_t last_send_time_ms[MAVLINK_COMM_NUM_BUFFERS];
902  if (status(0) > AP_GPS::NO_GPS) {
903  // when we have a GPS then only send new data
904  if (last_send_time_ms[chan] == last_message_time_ms(0)) {
905  return;
906  }
907  last_send_time_ms[chan] = last_message_time_ms(0);
908  } else {
909  // when we don't have a GPS then send at 1Hz
910  uint32_t now = AP_HAL::millis();
911  if (now - last_send_time_ms[chan] < 1000) {
912  return;
913  }
914  last_send_time_ms[chan] = now;
915  }
916  const Location &loc = location(0);
917  float hacc = 0.0f;
918  float vacc = 0.0f;
919  float sacc = 0.0f;
920  horizontal_accuracy(0, hacc);
921  vertical_accuracy(0, vacc);
922  speed_accuracy(0, sacc);
923  mavlink_msg_gps_raw_int_send(
924  chan,
925  last_fix_time_ms(0)*(uint64_t)1000,
926  status(0),
927  loc.lat, // in 1E7 degrees
928  loc.lng, // in 1E7 degrees
929  loc.alt * 10UL, // in mm
930  get_hdop(0),
931  get_vdop(0),
932  ground_speed(0)*100, // cm/s
933  ground_course(0)*100, // 1/100 degrees,
934  num_sats(0),
935  0, // TODO: Elipsoid height in mm
936  hacc * 1000, // one-sigma standard deviation in mm
937  vacc * 1000, // one-sigma standard deviation in mm
938  sacc * 1000, // one-sigma standard deviation in mm/s
939  0); // TODO one-sigma heading accuracy standard deviation
940 }
941 
942 void AP_GPS::send_mavlink_gps2_raw(mavlink_channel_t chan)
943 {
944  static uint32_t last_send_time_ms[MAVLINK_COMM_NUM_BUFFERS];
945  if (num_instances < 2 || status(1) <= AP_GPS::NO_GPS) {
946  return;
947  }
948  // when we have a GPS then only send new data
949  if (last_send_time_ms[chan] == last_message_time_ms(1)) {
950  return;
951  }
952  last_send_time_ms[chan] = last_message_time_ms(1);
953 
954  const Location &loc = location(1);
955  mavlink_msg_gps2_raw_send(
956  chan,
957  last_fix_time_ms(1)*(uint64_t)1000,
958  status(1),
959  loc.lat,
960  loc.lng,
961  loc.alt * 10UL,
962  get_hdop(1),
963  get_vdop(1),
964  ground_speed(1)*100, // cm/s
965  ground_course(1)*100, // 1/100 degrees,
966  num_sats(1),
967  rtk_num_sats(1),
968  rtk_age_ms(1));
969 }
970 
971 void AP_GPS::send_mavlink_gps_rtk(mavlink_channel_t chan, uint8_t inst)
972 {
973  if (inst >= GPS_MAX_RECEIVERS) {
974  return;
975  }
976  if (drivers[inst] != nullptr && drivers[inst]->supports_mavlink_gps_rtk_message()) {
977  drivers[inst]->send_mavlink_gps_rtk(chan);
978  }
979 }
980 
982 {
983  for (int i = 0; i < GPS_MAX_RECEIVERS; i++) {
984  if (_type[i] != GPS_TYPE_NONE && (drivers[i] == nullptr || !drivers[i]->is_configured())) {
985  return i;
986  }
987  }
988  return GPS_ALL_CONFIGURED;
989 }
990 
992 {
993  const uint8_t unconfigured = first_unconfigured_gps();
994  if (drivers[unconfigured] == nullptr) {
995  gcs().send_text(MAV_SEVERITY_INFO, "GPS %d: was not found", unconfigured + 1);
996  } else {
998  }
999 }
1000 
1001 // pre-arm check that all GPSs are close to each other. farthest distance between GPSs (in meters) is returned
1003 {
1004  // return true immediately if only one valid receiver
1005  if (num_instances <= 1 ||
1006  drivers[0] == nullptr || _type[0] == GPS_TYPE_NONE) {
1007  distance = 0;
1008  return true;
1009  }
1010 
1011  // calculate distance
1012  distance = location_3d_diff_NED(state[0].location, state[1].location).length();
1013  // success if distance is within 50m
1014  return (distance < 50);
1015 }
1016 
1017 // pre-arm check of GPS blending. True means healthy or that blending is not being used
1019 {
1020  return (_blend_health_counter < 50);
1021 }
1022 
1023 /*
1024  re-assemble GPS_RTCM_DATA message
1025  */
1026 void AP_GPS::handle_gps_rtcm_data(const mavlink_message_t *msg)
1027 {
1028  mavlink_gps_rtcm_data_t packet;
1029  mavlink_msg_gps_rtcm_data_decode(msg, &packet);
1030 
1031  if (packet.len > MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN) {
1032  // invalid packet
1033  return;
1034  }
1035 
1036  if ((packet.flags & 1) == 0) {
1037  // it is not fragmented, pass direct
1038  inject_data(packet.data, packet.len);
1039  return;
1040  }
1041 
1042  // see if we need to allocate re-assembly buffer
1043  if (rtcm_buffer == nullptr) {
1044  rtcm_buffer = (struct rtcm_buffer *)calloc(1, sizeof(*rtcm_buffer));
1045  if (rtcm_buffer == nullptr) {
1046  // nothing to do but discard the data
1047  return;
1048  }
1049  }
1050 
1051  uint8_t fragment = (packet.flags >> 1U) & 0x03;
1052  uint8_t sequence = (packet.flags >> 3U) & 0x1F;
1053 
1054  // see if this fragment is consistent with existing fragments
1056  (rtcm_buffer->sequence != sequence ||
1057  (rtcm_buffer->fragments_received & (1U<<fragment)))) {
1058  // we have one or more partial fragments already received
1059  // which conflict with the new fragment, discard previous fragments
1060  memset(rtcm_buffer, 0, sizeof(*rtcm_buffer));
1061  }
1062 
1063  // add this fragment
1064  rtcm_buffer->sequence = sequence;
1065  rtcm_buffer->fragments_received |= (1U << fragment);
1066 
1067  // copy the data
1068  memcpy(&rtcm_buffer->buffer[MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN*(uint16_t)fragment], packet.data, packet.len);
1069 
1070  // when we get a fragment of less than max size then we know the
1071  // number of fragments. Note that this means if you want to send a
1072  // block of RTCM data of an exact multiple of the buffer size you
1073  // need to send a final packet of zero length
1074  if (packet.len < MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN) {
1075  rtcm_buffer->fragment_count = fragment+1;
1076  rtcm_buffer->total_length = (MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN*fragment) + packet.len;
1077  } else if (rtcm_buffer->fragments_received == 0x0F) {
1078  // special case of 4 full fragments
1080  rtcm_buffer->total_length = MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN*4;
1081  }
1082 
1083 
1084  // see if we have all fragments
1085  if (rtcm_buffer->fragment_count != 0 &&
1087  // we have them all, inject
1089  memset(rtcm_buffer, 0, sizeof(*rtcm_buffer));
1090  }
1091 }
1092 
1094 {
1095  for (uint8_t instance=0; instance<num_instances; instance++) {
1096  if (drivers[instance] == nullptr || state[instance].status == NO_GPS) {
1097  continue;
1098  }
1100  }
1101 }
1102 
1103 /*
1104  return the expected lag (in seconds) in the position and velocity readings from the gps
1105  return true if the GPS hardware configuration is known or the delay parameter has been set
1106  */
1107 bool AP_GPS::get_lag(uint8_t instance, float &lag_sec) const
1108 {
1109  // return lag of blended GPS
1110  if (instance == GPS_BLENDED_INSTANCE) {
1111  lag_sec = _blended_lag_sec;
1112  // auto switching uses all GPS receivers, so all must be configured
1113  return all_configured();
1114  }
1115 
1116  if (_delay_ms[instance] > 0) {
1117  // if the user has specified a non zero time delay, always return that value
1118  lag_sec = 0.001f * (float)_delay_ms[instance];
1119  // the user is always right !!
1120  return true;
1121  } else if (drivers[instance] == nullptr || state[instance].status == NO_GPS) {
1122  // no GPS was detected in this instance so return the worst possible lag term
1123  if (_type[instance] == GPS_TYPE_NONE) {
1124  lag_sec = 0.0f;
1125  return true;
1126  } else {
1127  lag_sec = GPS_WORST_LAG_SEC;
1128  }
1129  return _type[instance] == GPS_TYPE_AUTO;
1130  } else {
1131  // the user has not specified a delay so we determine it from the GPS type
1132  return drivers[instance]->get_lag(lag_sec);
1133  }
1134 }
1135 
1136 // return a 3D vector defining the offset of the GPS antenna in meters relative to the body frame origin
1137 const Vector3f &AP_GPS::get_antenna_offset(uint8_t instance) const
1138 {
1139  if (instance == GPS_MAX_RECEIVERS) {
1140  // return an offset for the blended GPS solution
1141  return _blended_antenna_offset;
1142  } else {
1143  return _antenna_offset[instance];
1144  }
1145 }
1146 
1147 /*
1148  returns the desired gps update rate in milliseconds
1149  this does not provide any guarantee that the GPS is updating at the requested
1150  rate it is simply a helper for use in the backends for determining what rate
1151  they should be configuring the GPS to run at
1152 */
1153 uint16_t AP_GPS::get_rate_ms(uint8_t instance) const
1154 {
1155  // sanity check
1156  if (instance >= num_instances || _rate_ms[instance] <= 0) {
1157  return GPS_MAX_RATE_MS;
1158  }
1159  return MIN(_rate_ms[instance], GPS_MAX_RATE_MS);
1160 }
1161 
1162 /*
1163  calculate the weightings used to blend GPSs location and velocity data
1164 */
1166 {
1167  // zero the blend weights
1168  memset(&_blend_weights, 0, sizeof(_blend_weights));
1169 
1170  // exit immediately if not enough receivers to do blending
1171  if (num_instances < 2 || drivers[1] == nullptr || _type[1] == GPS_TYPE_NONE) {
1172  return false;
1173  }
1174 
1175  // Use the oldest non-zero time, but if time difference is excessive, use newest to prevent a disconnected receiver from blocking updates
1176  uint32_t max_ms = 0; // newest non-zero system time of arrival of a GPS message
1177  uint32_t min_ms = -1; // oldest non-zero system time of arrival of a GPS message
1178  int16_t max_rate_ms = 0; // largest update interval of a GPS receiver
1179  for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
1180  // Find largest and smallest times
1181  if (state[i].last_gps_time_ms > max_ms) {
1182  max_ms = state[i].last_gps_time_ms;
1183  }
1184  if ((state[i].last_gps_time_ms < min_ms) && (state[i].last_gps_time_ms > 0)) {
1185  min_ms = state[i].last_gps_time_ms;
1186  }
1187  if (get_rate_ms(i) > max_rate_ms) {
1188  max_rate_ms = get_rate_ms(i);
1189  }
1190  }
1191  if ((int32_t)(max_ms - min_ms) < (int32_t)(2 * max_rate_ms)) {
1192  // data is not too delayed so use the oldest time_stamp to give a chance for data from that receiver to be updated
1194  } else {
1195  // receiver data has timed out so fail out of blending
1196  return false;
1197  }
1198 
1199  // calculate the sum squared speed accuracy across all GPS sensors
1200  float speed_accuracy_sum_sq = 0.0f;
1202  for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
1203  if (state[i].status >= GPS_OK_FIX_3D) {
1204  if (state[i].have_speed_accuracy && state[i].speed_accuracy > 0.0f) {
1205  speed_accuracy_sum_sq += state[i].speed_accuracy * state[i].speed_accuracy;
1206  } else {
1207  // not all receivers support this metric so set it to zero and don't use it
1208  speed_accuracy_sum_sq = 0.0f;
1209  break;
1210  }
1211  }
1212  }
1213  }
1214 
1215  // calculate the sum squared horizontal position accuracy across all GPS sensors
1216  float horizontal_accuracy_sum_sq = 0.0f;
1218  for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
1219  if (state[i].status >= GPS_OK_FIX_2D) {
1220  if (state[i].have_horizontal_accuracy && state[i].horizontal_accuracy > 0.0f) {
1221  horizontal_accuracy_sum_sq += state[i].horizontal_accuracy * state[i].horizontal_accuracy;
1222  } else {
1223  // not all receivers support this metric so set it to zero and don't use it
1224  horizontal_accuracy_sum_sq = 0.0f;
1225  break;
1226  }
1227  }
1228  }
1229  }
1230 
1231  // calculate the sum squared vertical position accuracy across all GPS sensors
1232  float vertical_accuracy_sum_sq = 0.0f;
1234  for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
1235  if (state[i].status >= GPS_OK_FIX_3D) {
1236  if (state[i].have_vertical_accuracy && state[i].vertical_accuracy > 0.0f) {
1237  vertical_accuracy_sum_sq += state[i].vertical_accuracy * state[i].vertical_accuracy;
1238  } else {
1239  // not all receivers support this metric so set it to zero and don't use it
1240  vertical_accuracy_sum_sq = 0.0f;
1241  break;
1242  }
1243  }
1244  }
1245  }
1246  // Check if we can do blending using reported accuracy
1247  bool can_do_blending = (horizontal_accuracy_sum_sq > 0.0f || vertical_accuracy_sum_sq > 0.0f || speed_accuracy_sum_sq > 0.0f);
1248 
1249  // if we can't do blending using reported accuracy, return false and hard switch logic will be used instead
1250  if (!can_do_blending) {
1251  return false;
1252  }
1253 
1254  float sum_of_all_weights = 0.0f;
1255 
1256  // calculate a weighting using the reported horizontal position
1257  float hpos_blend_weights[GPS_MAX_RECEIVERS] = {};
1258  if (horizontal_accuracy_sum_sq > 0.0f && (_blend_mask & BLEND_MASK_USE_HPOS_ACC)) {
1259  // calculate the weights using the inverse of the variances
1260  float sum_of_hpos_weights = 0.0f;
1261  for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
1262  if (state[i].status >= GPS_OK_FIX_2D && state[i].horizontal_accuracy >= 0.001f) {
1263  hpos_blend_weights[i] = horizontal_accuracy_sum_sq / (state[i].horizontal_accuracy * state[i].horizontal_accuracy);
1264  sum_of_hpos_weights += hpos_blend_weights[i];
1265  }
1266  }
1267  // normalise the weights
1268  if (sum_of_hpos_weights > 0.0f) {
1269  for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
1270  hpos_blend_weights[i] = hpos_blend_weights[i] / sum_of_hpos_weights;
1271  }
1272  sum_of_all_weights += 1.0f;
1273  }
1274  }
1275 
1276  // calculate a weighting using the reported vertical position accuracy
1277  float vpos_blend_weights[GPS_MAX_RECEIVERS] = {};
1278  if (vertical_accuracy_sum_sq > 0.0f && (_blend_mask & BLEND_MASK_USE_VPOS_ACC)) {
1279  // calculate the weights using the inverse of the variances
1280  float sum_of_vpos_weights = 0.0f;
1281  for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
1282  if (state[i].status >= GPS_OK_FIX_3D && state[i].vertical_accuracy >= 0.001f) {
1283  vpos_blend_weights[i] = vertical_accuracy_sum_sq / (state[i].vertical_accuracy * state[i].vertical_accuracy);
1284  sum_of_vpos_weights += vpos_blend_weights[i];
1285  }
1286  }
1287  // normalise the weights
1288  if (sum_of_vpos_weights > 0.0f) {
1289  for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
1290  vpos_blend_weights[i] = vpos_blend_weights[i] / sum_of_vpos_weights;
1291  }
1292  sum_of_all_weights += 1.0f;
1293  };
1294  }
1295 
1296  // calculate a weighting using the reported speed accuracy
1297  float spd_blend_weights[GPS_MAX_RECEIVERS] = {};
1298  if (speed_accuracy_sum_sq > 0.0f && (_blend_mask & BLEND_MASK_USE_SPD_ACC)) {
1299  // calculate the weights using the inverse of the variances
1300  float sum_of_spd_weights = 0.0f;
1301  for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
1302  if (state[i].status >= GPS_OK_FIX_3D && state[i].speed_accuracy >= 0.001f) {
1303  spd_blend_weights[i] = speed_accuracy_sum_sq / (state[i].speed_accuracy * state[i].speed_accuracy);
1304  sum_of_spd_weights += spd_blend_weights[i];
1305  }
1306  }
1307  // normalise the weights
1308  if (sum_of_spd_weights > 0.0f) {
1309  for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
1310  spd_blend_weights[i] = spd_blend_weights[i] / sum_of_spd_weights;
1311  }
1312  sum_of_all_weights += 1.0f;
1313  }
1314  }
1315 
1316  // calculate an overall weight
1317  for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
1318  _blend_weights[i] = (hpos_blend_weights[i] + vpos_blend_weights[i] + spd_blend_weights[i]) / sum_of_all_weights;
1319  }
1320 
1321  return true;
1322 }
1323 
1324 /*
1325  calculate a blended GPS state
1326 */
1328 {
1329  // initialise the blended states so we can accumulate the results using the weightings for each GPS receiver
1347  memset(&state[GPS_BLENDED_INSTANCE].location, 0, sizeof(state[GPS_BLENDED_INSTANCE].location));
1348 
1350  _blended_lag_sec = 0;
1351 
1354 
1355  // combine the states into a blended solution
1356  for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
1357  // use the highest status
1360  }
1361 
1362  // calculate a blended average velocity
1364 
1365  // report the best valid accuracies and DOP metrics
1366 
1367  if (state[i].have_horizontal_accuracy && state[i].horizontal_accuracy > 0.0f && state[i].horizontal_accuracy < state[GPS_BLENDED_INSTANCE].horizontal_accuracy) {
1370  }
1371 
1372  if (state[i].have_vertical_accuracy && state[i].vertical_accuracy > 0.0f && state[i].vertical_accuracy < state[GPS_BLENDED_INSTANCE].vertical_accuracy) {
1375  }
1376 
1377  if (state[i].have_vertical_velocity) {
1379  }
1380 
1381  if (state[i].have_speed_accuracy && state[i].speed_accuracy > 0.0f && state[i].speed_accuracy < state[GPS_BLENDED_INSTANCE].speed_accuracy) {
1384  }
1385 
1386  if (state[i].hdop > 0 && state[i].hdop < state[GPS_BLENDED_INSTANCE].hdop) {
1388  }
1389 
1390  if (state[i].vdop > 0 && state[i].vdop < state[GPS_BLENDED_INSTANCE].vdop) {
1392  }
1393 
1396  }
1397 
1398  // report a blended average GPS antenna position
1399  Vector3f temp_antenna_offset = _antenna_offset[i];
1400  temp_antenna_offset *= _blend_weights[i];
1401  _blended_antenna_offset += temp_antenna_offset;
1402 
1403  // blend the timing data
1406  }
1409  }
1410 
1411  }
1412 
1413  /*
1414  * Calculate an instantaneous weighted/blended average location from the available GPS instances and store in the _output_state.
1415  * This will be statistically the most likely location, but will be not stable enough for direct use by the autopilot.
1416  */
1417 
1418  // Use the GPS with the highest weighting as the reference position
1419  float best_weight = 0.0f;
1420  uint8_t best_index = 0;
1421  for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
1422  if (_blend_weights[i] > best_weight) {
1423  best_weight = _blend_weights[i];
1424  best_index = i;
1426  }
1427  }
1428 
1429  // Calculate the weighted sum of horizontal and vertical position offsets relative to the reference position
1430  Vector2f blended_NE_offset_m;
1431  float blended_alt_offset_cm = 0.0f;
1432  blended_NE_offset_m.zero();
1433  for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
1434  if (_blend_weights[i] > 0.0f && i != best_index) {
1435  blended_NE_offset_m += location_diff(state[GPS_BLENDED_INSTANCE].location, state[i].location) * _blend_weights[i];
1436  blended_alt_offset_cm += (float)(state[i].location.alt - state[GPS_BLENDED_INSTANCE].location.alt) * _blend_weights[i];
1437  }
1438  }
1439 
1440  // Add the sum of weighted offsets to the reference location to obtain the blended location
1441  location_offset(state[GPS_BLENDED_INSTANCE].location, blended_NE_offset_m.x, blended_NE_offset_m.y);
1442  state[GPS_BLENDED_INSTANCE].location.alt += (int)blended_alt_offset_cm;
1443 
1444  // Calculate ground speed and course from blended velocity vector
1446  state[GPS_BLENDED_INSTANCE].ground_course = wrap_360(degrees(atan2f(state[GPS_BLENDED_INSTANCE].velocity.y, state[GPS_BLENDED_INSTANCE].velocity.x)));
1447 
1448  /*
1449  * The blended location in _output_state.location is not stable enough to be used by the autopilot
1450  * as it will move around as the relative accuracy changes. To mitigate this effect a low-pass filtered
1451  * offset from each GPS location to the blended location is calculated and the filtered offset is applied
1452  * to each receiver.
1453  */
1454 
1455  // Calculate filter coefficients to be applied to the offsets for each GPS position and height offset
1456  // A weighting of 1 will make the offset adjust the slowest, a weighting of 0 will make it adjust with zero filtering
1457  float alpha[GPS_MAX_RECEIVERS] = {};
1458  for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
1459  if (state[i].last_gps_time_ms - _last_time_updated[i] > 0) {
1460  float min_alpha = constrain_float(_omega_lpf * 0.001f * (float)(state[i].last_gps_time_ms - _last_time_updated[i]), 0.0f, 1.0f);
1461  if (_blend_weights[i] > min_alpha) {
1462  alpha[i] = min_alpha / _blend_weights[i];
1463  } else {
1464  alpha[i] = 1.0f;
1465  }
1467  }
1468  }
1469 
1470  // Calculate the offset from each GPS solution to the blended solution
1471  for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
1472  _NE_pos_offset_m[i] = location_diff(state[i].location, state[GPS_BLENDED_INSTANCE].location) * alpha[i] + _NE_pos_offset_m[i] * (1.0f - alpha[i]);
1473  _hgt_offset_cm[i] = (float)(state[GPS_BLENDED_INSTANCE].location.alt - state[i].location.alt) * alpha[i] + _hgt_offset_cm[i] * (1.0f - alpha[i]);
1474  }
1475 
1476  // Calculate a corrected location for each GPS
1477  Location corrected_location[GPS_MAX_RECEIVERS];
1478  for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
1479  corrected_location[i] = state[i].location;
1480  location_offset(corrected_location[i], _NE_pos_offset_m[i].x, _NE_pos_offset_m[i].y);
1481  corrected_location[i].alt += (int)(_hgt_offset_cm[i]);
1482  }
1483 
1484  // If the GPS week is the same then use a blended time_week_ms
1485  // If week is different, then use time stamp from GPS with largest weighting
1486  // detect inconsistent week data
1487  uint8_t last_week_instance = 0;
1488  bool weeks_consistent = true;
1489  for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
1490  if (last_week_instance == 0 && _blend_weights[i] > 0) {
1491  // this is our first valid sensor week data
1492  last_week_instance = state[i].time_week;
1493  } else if (last_week_instance != 0 && _blend_weights[i] > 0 && last_week_instance != state[i].time_week) {
1494  // there is valid sensor week data that is inconsistent
1495  weeks_consistent = false;
1496  }
1497  }
1498  // calculate output
1499  if (!weeks_consistent) {
1500  // use data from highest weighted sensor
1503  } else {
1504  // use week number from highest weighting GPS (they should all have the same week number)
1506  // calculate a blended value for the number of ms lapsed in the week
1507  double temp_time_0 = 0.0;
1508  for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
1509  if (_blend_weights[i] > 0.0f) {
1510  temp_time_0 += (double)state[i].time_week_ms * (double)_blend_weights[i];
1511  }
1512  }
1513  state[GPS_BLENDED_INSTANCE].time_week_ms = (uint32_t)temp_time_0;
1514  }
1515 
1516  // calculate a blended value for the timing data and lag
1517  double temp_time_1 = 0.0;
1518  double temp_time_2 = 0.0;
1519  for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
1520  if (_blend_weights[i] > 0.0f) {
1521  temp_time_1 += (double)timing[i].last_fix_time_ms * (double) _blend_weights[i];
1522  temp_time_2 += (double)timing[i].last_message_time_ms * (double)_blend_weights[i];
1523  float gps_lag_sec = 0;
1524  get_lag(i, gps_lag_sec);
1525  _blended_lag_sec += gps_lag_sec * _blend_weights[i];
1526  }
1527  }
1528  timing[GPS_BLENDED_INSTANCE].last_fix_time_ms = (uint32_t)temp_time_1;
1529  timing[GPS_BLENDED_INSTANCE].last_message_time_ms = (uint32_t)temp_time_2;
1530 }
1531 
1532 bool AP_GPS::is_healthy(uint8_t instance) const {
1533  return drivers[instance] != nullptr &&
1535  drivers[instance]->is_healthy();
1536 }
1537 
1539  bool all_passed = true;
1540  for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) {
1541  if (drivers[i] != nullptr) {
1542  all_passed &= drivers[i]->prepare_for_arming();
1543  }
1544  }
1545  return all_passed;
1546 }
1547 
1548 namespace AP {
1549 
1551 {
1552  return AP_GPS::gps();
1553 }
1554 
1555 };
float norm(const T first, const U second, const Params... parameters)
Definition: AP_Math.h:190
uint32_t last_message_time_ms
Definition: AP_GPS.h:457
uint32_t rtk_age_ms(void) const
Definition: AP_GPS.h:345
int printf(const char *fmt,...)
Definition: stdio.c:113
uint32_t _log_gps_bit
Definition: AP_GPS.h:441
Definition: AP_GPS.h:48
uint16_t remaining
Definition: AP_GPS.h:496
uint32_t time_week_ms
GPS time (milliseconds from start of GPS week)
Definition: AP_GPS.h:133
AP_HAL::UARTDriver * _port[GPS_MAX_RECEIVERS]
Definition: AP_GPS.h:466
void send_blob_start(uint8_t instance, const char *_blob, uint16_t size)
Definition: AP_GPS.cpp:371
static AP_SerialManager serial_manager
Definition: AHRS_Test.cpp:24
bool auto_detected_baud
Definition: AP_GPS.h:481
float _blend_weights[GPS_MAX_RECEIVERS]
Definition: AP_GPS.h:540
virtual AP_GPS::GPS_Status highest_supported_status(void)
Definition: GPS_Backend.h:40
uint8_t locked_ports
Definition: AP_GPS.h:475
struct NMEA_detect_state nmea_detect_state
Definition: AP_GPS.h:488
uint8_t fragment_count
Definition: AP_GPS.h:521
struct SBP_detect_state sbp_detect_state
Definition: AP_GPS.h:489
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_GPS.h:404
uint8_t current_baud
Definition: AP_GPS.h:480
friend class AP_GPS_UBLOX
Definition: AP_GPS.h:62
uint32_t last_gps_time_ms
the system time we got the last GPS timestamp, milliseconds
Definition: AP_GPS.h:149
AP_Int16 _delay_ms[GPS_MAX_RECEIVERS]
Definition: AP_GPS.h:437
virtual bool get_lag(float &lag) const
Definition: GPS_Backend.h:56
friend class AP_GPS_MTK19
Definition: AP_GPS.h:54
bool prepare_for_arming(void)
Definition: AP_GPS.cpp:1538
uint8_t instance
Definition: AP_GPS.h:129
uint32_t time_week_ms() const
Definition: AP_GPS.h:271
void detect_instance(uint8_t instance)
Definition: AP_GPS.cpp:408
virtual void begin(uint32_t baud)=0
uint8_t num_sensors(void) const
Definition: AP_GPS.cpp:307
void calc_blended_state(void)
Definition: AP_GPS.cpp:1327
uint8_t register_gps_listener_to_node(AP_GPS_Backend *new_listener, uint8_t node)
float ground_speed() const
Definition: AP_GPS.h:235
virtual void broadcast_configuration_failure_reason(void) const
Definition: GPS_Backend.h:50
GPS_Status status
driver fix status
Definition: AP_GPS.h:132
AP_Int8 _inject_to
Definition: AP_GPS.h:427
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
Interface definition for the various Ground Control System.
bool have_vertical_velocity
does GPS give vertical velocity? Set to true only once available.
Definition: AP_GPS.h:145
Vector3f velocity
3D velocity in m/s, in NED format
Definition: AP_GPS.h:141
bool should_log(uint32_t mask) const
Definition: DataFlash.cpp:416
GPS_State state[GPS_MAX_RECEIVERS+1]
Definition: AP_GPS.h:464
uint8_t primary_instance
primary GPS instance
Definition: AP_GPS.h:469
friend class AP_GPS_GSOF
Definition: AP_GPS.h:51
void send_mavlink_gps2_raw(mavlink_channel_t chan)
Definition: AP_GPS.cpp:942
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
void lock_port(uint8_t instance, bool locked)
Definition: AP_GPS.cpp:866
bool all_consistent(float &distance) const
Definition: AP_GPS.cpp:1002
virtual void inject_data(const uint8_t *data, uint16_t len)
#define UBLOX_SET_BINARY
Definition: AP_GPS_UBLOX.h:40
virtual uint32_t txspace()=0
uint32_t _last_time_updated[GPS_MAX_RECEIVERS]
Definition: AP_GPS.h:541
void broadcast_first_configuration_failure_reason(void) const
Definition: AP_GPS.cpp:991
void handle_gps_inject(const mavlink_message_t *msg)
Definition: AP_GPS.cpp:777
GCS & gcs()
#define AP_MSEC_PER_WEEK
Definition: definitions.h:96
#define MTK_SET_BINARY
bool should_df_log() const
Definition: AP_GPS.cpp:579
bool have_vertical_velocity(void) const
Definition: AP_GPS.h:329
#define GPS_RTK_INJECT_TO_ALL
Definition: AP_GPS.h:33
static bool _detect(struct NMEA_detect_state &state, uint8_t data)
AP_GPS_Backend * drivers[GPS_MAX_RECEIVERS]
Definition: AP_GPS.h:465
void location_offset(struct Location &loc, float ofs_north, float ofs_east)
Definition: location.cpp:125
#define GPS_MAX_RATE_MS
Definition: AP_GPS.h:34
GPS_timing timing[GPS_MAX_RECEIVERS+1]
Definition: AP_GPS.h:463
const char * result
Definition: Printf.cpp:16
GPS_Status highest_supported_status(uint8_t instance) const
Definition: AP_GPS.cpp:571
static bool _detect(struct ERB_detect_state &state, uint8_t data)
Definition: AP_GPS_ERB.cpp:241
AP_GPS()
Definition: AP_GPS.cpp:265
float distance
Definition: location.cpp:94
void * calloc(size_t nmemb, size_t size)
Definition: malloc.c:76
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
#define MIN(a, b)
Definition: usb_conf.h:215
void update_instance(uint8_t instance)
Definition: AP_GPS.cpp:598
virtual bool prepare_for_arming(void)
Definition: GPS_Backend.h:66
AP_HAL::CANManager ** can_mgr
Definition: HAL.h:120
friend class AP_GPS_MAV
Definition: AP_GPS.h:52
#define BLEND_MASK_USE_HPOS_ACC
Definition: AP_GPS.cpp:49
uint16_t get_vdop() const
Definition: AP_GPS.h:295
T y
Definition: vector2.h:37
void init(const AP_SerialManager &serial_manager)
Startup initialisation.
Definition: AP_GPS.cpp:279
void inject_data(uint8_t *data, uint16_t len)
Definition: AP_GPS.cpp:880
friend class AP_GPS_SBP2
Definition: AP_GPS.h:60
GPS_Status
GPS status codes.
Definition: AP_GPS.h:96
#define HAL_GPS_TYPE_DEFAULT
static AP_GPS * _singleton
Definition: AP_GPS.h:444
static bool _detect(struct MTK19_detect_state &state, uint8_t data)
bool is_healthy(void) const
Definition: AP_GPS.h:414
friend class AP_GPS_SIRF
Definition: AP_GPS.h:61
float _omega_lpf
Definition: AP_GPS.h:542
#define x(i)
#define BLEND_MASK_USE_SPD_ACC
Definition: AP_GPS.cpp:51
void send_mavlink_gps_raw(mavlink_channel_t chan)
Definition: AP_GPS.cpp:899
Vector3f _blended_antenna_offset
Definition: AP_GPS.h:538
uint64_t time_epoch_usec(void) const
Definition: AP_GPS.h:397
uint8_t num_instances
number of GPS instances present
Definition: AP_GPS.h:472
float wrap_360(const T angle, float unit_mod)
Definition: AP_Math.cpp:123
const Vector3f & velocity() const
Definition: AP_GPS.h:227
virtual bool is_healthy(void) const
Definition: GPS_Backend.h:59
const Vector3f & get_antenna_offset(uint8_t instance) const
Definition: AP_GPS.cpp:1137
uint8_t num_sats() const
Definition: AP_GPS.h:263
void setHIL_Accuracy(uint8_t instance, float vdop, float hacc, float vacc, float sacc, bool _have_vertical_velocity, uint32_t sample_ms)
Definition: AP_GPS.cpp:841
Vector2f location_diff(const struct Location &loc1, const struct Location &loc2)
Definition: location.cpp:139
Definition: AP_AHRS.cpp:486
#define GPS_MAX_INSTANCES
Definition: AP_GPS.h:31
#define GPS_WORST_LAG_SEC
Definition: AP_GPS.h:36
float _hgt_offset_cm[GPS_MAX_RECEIVERS]
Definition: AP_GPS.h:537
friend class AP_GPS_NOVA
Definition: AP_GPS.h:56
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
Definition: AP_Common.h:142
#define UNIX_OFFSET_MSEC
Definition: AP_GPS.h:42
uint8_t _blend_health_counter
Definition: AP_GPS.h:544
AP_Int8 _blend_mask
Definition: AP_GPS.h:438
uint16_t delta_time_ms
Definition: AP_GPS.h:460
bool speed_accuracy(uint8_t instance, float &sacc) const
Definition: AP_GPS.cpp:316
uint32_t _last_instance_swap_ms
Definition: AP_GPS.h:428
struct MTK19_detect_state mtk19_detect_state
Definition: AP_GPS.h:485
#define f(i)
bool blend_health_check() const
Definition: AP_GPS.cpp:1018
T y
Definition: vector3.h:67
void send_mavlink_gps_rtk(mavlink_channel_t chan, uint8_t inst)
Definition: AP_GPS.cpp:971
virtual size_t write(uint8_t)=0
uint32_t last_baud_change_ms
Definition: AP_GPS.h:479
uint32_t last_message_time_ms(void) const
Definition: AP_GPS.h:313
uint32_t millis()
Definition: system.cpp:157
const char * blob
Definition: AP_GPS.h:495
virtual void send_mavlink_gps_rtk(mavlink_channel_t chan)
static bool _detect(struct SBP2_detect_state &state, uint8_t data)
static DataFlash_Class * instance(void)
Definition: DataFlash.h:62
void broadcast_gps_type() const
uint16_t time_week() const
Definition: AP_GPS.h:279
uint16_t total_length
Definition: AP_GPS.h:522
struct ERB_detect_state erb_detect_state
Definition: AP_GPS.h:491
uint32_t last_fix_time_ms(void) const
Definition: AP_GPS.h:304
static bool _detect(struct UBLOX_detect_state &state, uint8_t data)
virtual void handle_msg(const mavlink_message_t *msg)
Definition: GPS_Backend.h:52
virtual void set_flow_control(enum flow_control flow_control_setting)
Definition: UARTDriver.h:50
AP_Int16 _rate_ms[GPS_MAX_RECEIVERS]
Definition: AP_GPS.h:433
uint16_t time_week
GPS week number.
Definition: AP_GPS.h:134
Receiving valid messages and 2D lock.
Definition: AP_GPS.h:99
bool all_configured(void) const
Definition: AP_GPS.h:381
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Definition: GCS.cpp:8
#define GPS_UNKNOWN_DOP
Definition: AP_GPS.h:35
AP_Float _blend_tc
Definition: AP_GPS.h:439
virtual int16_t read()=0
#define ARRAY_SIZE(_arr)
Definition: AP_Common.h:80
uint32_t last_fix_time_ms
Definition: AP_GPS.h:454
static const char _initialisation_blob[]
Definition: AP_GPS.h:500
uint8_t sequence
Definition: AP_GPS.h:520
uint8_t rtk_num_sats(void) const
Definition: AP_GPS.h:337
#define GPS_MAX_DELTA_MS
Definition: AP_GPS.h:37
struct SBP2_detect_state sbp2_detect_state
Definition: AP_GPS.h:490
void Log_Write_GPS(uint8_t instance, uint64_t time_us=0)
Definition: LogFile.cpp:136
float length(void) const
Definition: vector3.cpp:288
#define GPS_BLENDED_INSTANCE
Definition: AP_GPS.h:32
float ground_course() const
Definition: AP_GPS.h:248
Common definitions and utility routines for the ArduPilot libraries.
uint16_t vdop
vertical dilution of precision in cm
Definition: AP_GPS.h:139
Location location
last fix location
Definition: AP_GPS.h:135
struct UBLOX_detect_state ublox_detect_state
Definition: AP_GPS.h:482
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
T x
Definition: vector2.h:37
#define BLEND_COUNTER_FAILURE_INCREMENT
Definition: AP_GPS.cpp:52
AP_AHRS & ahrs()
Definition: AP_AHRS.cpp:488
void 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)
Definition: AP_GPS.cpp:814
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
uint8_t fragments_received
Definition: AP_GPS.h:519
static bool _detect(struct MTK_detect_state &state, uint8_t data)
Definition: AP_GPS_MTK.cpp:170
Vector3f location_3d_diff_NED(const struct Location &loc1, const struct Location &loc2)
Definition: location.cpp:149
static const uint32_t _baudrates[]
Definition: AP_GPS.h:499
Receiving valid GPS messages but no lock.
Definition: AP_GPS.h:98
#define BLEND_MASK_USE_VPOS_ACC
Definition: AP_GPS.cpp:50
uint16_t last_message_delta_time_ms(void) const
Definition: AP_GPS.h:321
static struct notify_flags_and_values_type flags
Definition: AP_Notify.h:117
void zero()
Definition: vector2.h:125
static uint64_t time_epoch_convert(uint16_t gps_week, uint32_t gps_ms)
Definition: AP_GPS.cpp:347
#define SIRF_SET_BINARY
Definition: AP_GPS_SIRF.h:28
void handle_msg(const mavlink_message_t *msg)
Definition: AP_GPS.cpp:789
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
friend class AP_GPS_SBP
Definition: AP_GPS.h:59
NMEA protocol parser.
const Location & location() const
Definition: AP_GPS.h:203
uint8_t buffer[MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN *4]
Definition: AP_GPS.h:523
GPS_Status status(void) const
Definition: AP_GPS.h:192
AP_Int8 _auto_config
Definition: AP_GPS.h:435
friend class AP_GPS_MTK
Definition: AP_GPS.h:53
struct SIRF_detect_state sirf_detect_state
Definition: AP_GPS.h:486
No GPS connected/detected.
Definition: AP_GPS.h:97
friend class AP_GPS_ERB
Definition: AP_GPS.h:50
#define GPS_TIMEOUT_MS
Definition: AP_GPS.cpp:46
void send_blob_update(uint8_t instance)
Definition: AP_GPS.cpp:381
struct MTK_detect_state mtk_detect_state
Definition: AP_GPS.h:484
friend class AP_GPS_SBF
Definition: AP_GPS.h:58
static bool _detect(struct SBP_detect_state &state, uint8_t data)
Definition: AP_GPS_SBP.cpp:311
bool have_vertical_accuracy
does GPS give vertical position accuracy? Set to true only once available.
Definition: AP_GPS.h:148
float speed_accuracy
3D velocity RMS accuracy estimate in m/s
Definition: AP_GPS.h:142
void handle_gps_rtcm_data(const mavlink_message_t *msg)
Definition: AP_GPS.cpp:1026
bool have_horizontal_accuracy
does GPS give horizontal position accuracy? Set to true only once available.
Definition: AP_GPS.h:147
float horizontal_accuracy
horizontal RMS accuracy estimate in m
Definition: AP_GPS.h:143
float ground_speed
ground speed in m/sec
Definition: AP_GPS.h:136
uint8_t find_gps_without_listener(void)
bool calc_blend_weights(void)
Definition: AP_GPS.cpp:1165
virtual void Write_DataFlash_Log_Startup_messages() const
AP_Int8 _type[GPS_MAX_RECEIVERS]
Definition: AP_GPS.h:422
#define GPS_BAUD_TIME_MS
Definition: AP_GPS.cpp:45
void update(void)
Definition: AP_GPS.cpp:678
Receiving valid messages and 3D lock.
Definition: AP_GPS.h:100
#define degrees(x)
Definition: moduletest.c:23
uint8_t first_unconfigured_gps(void) const
Definition: AP_GPS.cpp:981
virtual bool read()=0
float vertical_accuracy
vertical RMS accuracy estimate in m
Definition: AP_GPS.h:144
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
uint16_t get_rate_ms(uint8_t instance) const
Definition: AP_GPS.cpp:1153
friend class AP_GPS_NMEA
Definition: AP_GPS.h:55
bool vertical_accuracy(uint8_t instance, float &vacc) const
Definition: AP_GPS.cpp:334
static bool _detect(struct SIRF_detect_state &state, uint8_t data)
float _blended_lag_sec
Definition: AP_GPS.h:539
uint16_t hdop
horizontal dilution of precision in cm
Definition: AP_GPS.h:138
bool horizontal_accuracy(uint8_t instance, float &hacc) const
Definition: AP_GPS.cpp:325
Vector2f _NE_pos_offset_m[GPS_MAX_RECEIVERS]
Definition: AP_GPS.h:536
AP_Int8 _auto_switch
Definition: AP_GPS.h:424
bool _output_is_blended
Definition: AP_GPS.h:543
AP_Vector3f _antenna_offset[GPS_MAX_RECEIVERS]
Definition: AP_GPS.h:436
#define AP_GROUPEND
Definition: AP_Param.h:121
#define GPS_MAX_RECEIVERS
Definition: AP_GPS.h:30
void zero()
Definition: vector3.h:182
T x
Definition: vector3.h:67
uint8_t options
Definition: AP_Common.h:136
AP_HAL::UARTDriver * find_serial(enum SerialProtocol protocol, uint8_t instance) const
uint16_t get_hdop() const
Definition: AP_GPS.h:287
uint8_t num_sats
Number of visible satellites.
Definition: AP_GPS.h:140
bool get_lag(uint8_t instance, float &lag_sec) const
Definition: AP_GPS.cpp:1107
static AP_GPS & gps()
Definition: AP_GPS.h:72
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214
bool have_speed_accuracy
does GPS give speed accuracy? Set to true only once available.
Definition: AP_GPS.h:146
float ground_course
ground course in degrees
Definition: AP_GPS.h:137
void Write_DataFlash_Log_Startup_messages()
Definition: AP_GPS.cpp:1093
struct AP_GPS::@27 initblob_state[GPS_MAX_RECEIVERS]