APM:Libraries
AP_GPS.h
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 #pragma once
16 
17 #include <AP_HAL/AP_HAL.h>
18 #include <inttypes.h>
19 #include <AP_Common/AP_Common.h>
20 #include <AP_Param/AP_Param.h>
21 #include <AP_Math/AP_Math.h>
22 #include <AP_Vehicle/AP_Vehicle.h>
23 #include "GPS_detect_state.h"
25 
30 #define GPS_MAX_RECEIVERS 2 // maximum number of physical GPS sensors allowed - does not include virtual GPS created by blending receiver data
31 #define GPS_MAX_INSTANCES (GPS_MAX_RECEIVERS + 1) // maximum number of GPs instances including the 'virtual' GPS created by blending receiver data
32 #define GPS_BLENDED_INSTANCE GPS_MAX_RECEIVERS // the virtual blended GPS is always the highest instance (2)
33 #define GPS_RTK_INJECT_TO_ALL 127
34 #define GPS_MAX_RATE_MS 200 // maximum value of rate_ms (i.e. slowest update rate) is 5hz or 200ms
35 #define GPS_UNKNOWN_DOP UINT16_MAX // set unknown DOP's to maximum value, which is also correct for MAVLink
36 #define GPS_WORST_LAG_SEC 0.22f // worst lag value any GPS driver is expected to return, expressed in seconds
37 #define GPS_MAX_DELTA_MS 245 // 200 ms (5Hz) + 45 ms buffer
38 
39 // the number of GPS leap seconds
40 #define GPS_LEAPSECONDS_MILLIS 18000ULL
41 
42 #define UNIX_OFFSET_MSEC (17000ULL * 86400ULL + 52ULL * 10ULL * AP_MSEC_PER_WEEK - GPS_LEAPSECONDS_MILLIS)
43 
44 class AP_GPS_Backend;
45 
48 class AP_GPS
49 {
50  friend class AP_GPS_ERB;
51  friend class AP_GPS_GSOF;
52  friend class AP_GPS_MAV;
53  friend class AP_GPS_MTK;
54  friend class AP_GPS_MTK19;
55  friend class AP_GPS_NMEA;
56  friend class AP_GPS_NOVA;
57  friend class AP_GPS_PX4;
58  friend class AP_GPS_SBF;
59  friend class AP_GPS_SBP;
60  friend class AP_GPS_SBP2;
61  friend class AP_GPS_SIRF;
62  friend class AP_GPS_UBLOX;
63  friend class AP_GPS_Backend;
64 
65 public:
66  AP_GPS();
67 
68  /* Do not allow copies */
69  AP_GPS(const AP_GPS &other) = delete;
70  AP_GPS &operator=(const AP_GPS&) = delete;
71 
72  static AP_GPS &gps() {
73  return *_singleton;
74  }
75 
76  // GPS driver types
77  enum GPS_Type {
93  };
94 
96  enum GPS_Status {
97  NO_GPS = GPS_FIX_TYPE_NO_GPS,
98  NO_FIX = GPS_FIX_TYPE_NO_FIX,
99  GPS_OK_FIX_2D = GPS_FIX_TYPE_2D_FIX,
100  GPS_OK_FIX_3D = GPS_FIX_TYPE_3D_FIX,
101  GPS_OK_FIX_3D_DGPS = GPS_FIX_TYPE_DGPS,
102  GPS_OK_FIX_3D_RTK_FLOAT = GPS_FIX_TYPE_RTK_FLOAT,
103  GPS_OK_FIX_3D_RTK_FIXED = GPS_FIX_TYPE_RTK_FIXED,
104  };
105 
106  // GPS navigation engine settings. Not all GPS receivers support
107  // this
118  };
119 
120  enum GPS_Config {
122  };
123 
124  /*
125  The GPS_State structure is filled in by the backend driver as it
126  parses each message from the GPS.
127  */
128  struct GPS_State {
129  uint8_t instance; // the instance number of this GPS
130 
131  // all the following fields must all be filled by the backend driver
133  uint32_t time_week_ms;
134  uint16_t time_week;
136  float ground_speed;
138  uint16_t hdop;
139  uint16_t vdop;
140  uint8_t num_sats;
149  uint32_t last_gps_time_ms;
150 
151  // all the following fields must only all be filled by RTK capable backend drivers
152  uint32_t rtk_time_week_ms;
153  uint16_t rtk_week_number;
154  uint32_t rtk_age_ms;
155  uint8_t rtk_num_sats;
160  uint32_t rtk_accuracy;
162  };
163 
165  void init(const AP_SerialManager& serial_manager);
166 
170  void update(void);
171 
172  // Pass mavlink data to message handlers (for MAV type)
173  void handle_msg(const mavlink_message_t *msg);
174 
175  // Accessor functions
176 
177  // return number of active GPS sensors. Note that if the first GPS
178  // is not present but the 2nd is then we return 2. Note that a blended
179  // GPS solution is treated as an additional sensor.
180  uint8_t num_sensors(void) const;
181 
182  // Return the index of the primary sensor which is the index of the sensor contributing to
183  // the output. A blended solution is available as an additional instance
184  uint8_t primary_sensor(void) const {
185  return primary_instance;
186  }
187 
189  GPS_Status status(uint8_t instance) const {
190  return state[instance].status;
191  }
192  GPS_Status status(void) const {
193  return status(primary_instance);
194  }
195 
196  // Query the highest status this GPS supports (always reports GPS_OK_FIX_3D for the blended GPS)
198 
199  // location of last fix
200  const Location &location(uint8_t instance) const {
201  return state[instance].location;
202  }
203  const Location &location() const {
204  return location(primary_instance);
205  }
206 
207  // report speed accuracy
208  bool speed_accuracy(uint8_t instance, float &sacc) const;
209  bool speed_accuracy(float &sacc) const {
210  return speed_accuracy(primary_instance, sacc);
211  }
212 
213  bool horizontal_accuracy(uint8_t instance, float &hacc) const;
214  bool horizontal_accuracy(float &hacc) const {
216  }
217 
218  bool vertical_accuracy(uint8_t instance, float &vacc) const;
219  bool vertical_accuracy(float &vacc) const {
220  return vertical_accuracy(primary_instance, vacc);
221  }
222 
223  // 3D velocity in NED format
224  const Vector3f &velocity(uint8_t instance) const {
225  return state[instance].velocity;
226  }
227  const Vector3f &velocity() const {
228  return velocity(primary_instance);
229  }
230 
231  // ground speed in m/s
232  float ground_speed(uint8_t instance) const {
233  return state[instance].ground_speed;
234  }
235  float ground_speed() const {
237  }
238 
239  // ground speed in cm/s
240  uint32_t ground_speed_cm(void) {
241  return ground_speed() * 100;
242  }
243 
244  // ground course in degrees
245  float ground_course(uint8_t instance) const {
246  return state[instance].ground_course;
247  }
248  float ground_course() const {
250  }
251  // ground course in centi-degrees
252  int32_t ground_course_cd(uint8_t instance) const {
253  return ground_course(instance) * 100;
254  }
255  int32_t ground_course_cd() const {
257  }
258 
259  // number of locked satellites
260  uint8_t num_sats(uint8_t instance) const {
261  return state[instance].num_sats;
262  }
263  uint8_t num_sats() const {
264  return num_sats(primary_instance);
265  }
266 
267  // GPS time of week in milliseconds
268  uint32_t time_week_ms(uint8_t instance) const {
269  return state[instance].time_week_ms;
270  }
271  uint32_t time_week_ms() const {
273  }
274 
275  // GPS week
276  uint16_t time_week(uint8_t instance) const {
277  return state[instance].time_week;
278  }
279  uint16_t time_week() const {
280  return time_week(primary_instance);
281  }
282 
283  // horizontal dilution of precision
284  uint16_t get_hdop(uint8_t instance) const {
285  return state[instance].hdop;
286  }
287  uint16_t get_hdop() const {
288  return get_hdop(primary_instance);
289  }
290 
291  // vertical dilution of precision
292  uint16_t get_vdop(uint8_t instance) const {
293  return state[instance].vdop;
294  }
295  uint16_t get_vdop() const {
296  return get_vdop(primary_instance);
297  }
298 
299  // the time we got our last fix in system milliseconds. This is
300  // used when calculating how far we might have moved since that fix
301  uint32_t last_fix_time_ms(uint8_t instance) const {
303  }
304  uint32_t last_fix_time_ms(void) const {
306  }
307 
308  // the time we last processed a message in milliseconds. This is
309  // used to indicate that we have new GPS data to process
310  uint32_t last_message_time_ms(uint8_t instance) const {
312  }
313  uint32_t last_message_time_ms(void) const {
315  }
316 
317  // system time delta between the last two reported positions
318  uint16_t last_message_delta_time_ms(uint8_t instance) const {
319  return timing[instance].delta_time_ms;
320  }
321  uint16_t last_message_delta_time_ms(void) const {
323  }
324 
325  // return true if the GPS supports vertical velocity values
326  bool have_vertical_velocity(uint8_t instance) const {
328  }
329  bool have_vertical_velocity(void) const {
331  }
332 
333  // return number of satellites used for RTK calculation
334  uint8_t rtk_num_sats(uint8_t instance) const {
335  return state[instance].rtk_num_sats;
336  }
337  uint8_t rtk_num_sats(void) const {
339  }
340 
341  // return age of last baseline correction in milliseconds
342  uint32_t rtk_age_ms(uint8_t instance) const {
343  return state[instance].rtk_age_ms;
344  }
345  uint32_t rtk_age_ms(void) const {
347  }
348 
349  // the expected lag (in seconds) in the position and velocity readings from the gps
350  // return true if the GPS hardware configuration is known or the lag parameter has been set manually
351  bool get_lag(uint8_t instance, float &lag_sec) const;
352  bool get_lag(float &lag_sec) const {
353  return get_lag(primary_instance, lag_sec);
354  }
355 
356  // return a 3D vector defining the offset of the GPS antenna in meters relative to the body frame origin
357  const Vector3f &get_antenna_offset(uint8_t instance) const;
358 
359  // set position for HIL
360  void setHIL(uint8_t instance, GPS_Status status, uint64_t time_epoch_ms,
361  const Location &location, const Vector3f &velocity, uint8_t num_sats,
362  uint16_t hdop);
363 
364  // set accuracy for HIL
365  void setHIL_Accuracy(uint8_t instance, float vdop, float hacc, float vacc, float sacc, bool _have_vertical_velocity, uint32_t sample_ms);
366 
367  // lock out a GPS port, allowing another application to use the port
368  void lock_port(uint8_t instance, bool locked);
369 
370  //MAVLink Status Sending
371  void send_mavlink_gps_raw(mavlink_channel_t chan);
372  void send_mavlink_gps2_raw(mavlink_channel_t chan);
373 
374  void send_mavlink_gps_rtk(mavlink_channel_t chan, uint8_t inst);
375 
376  // Returns the index of the first unconfigured GPS (returns GPS_ALL_CONFIGURED if all instances report as being configured)
377  uint8_t first_unconfigured_gps(void) const;
379 
380  // return true if all GPS instances have finished configuration
381  bool all_configured(void) const {
383  }
384 
385  // pre-arm check that all GPSs are close to each other. farthest distance between GPSs (in meters) is returned
386  bool all_consistent(float &distance) const;
387 
388  // pre-arm check of GPS blending. False if blending is unhealthy, True if healthy or blending is not being used
389  bool blend_health_check() const;
390 
391  // handle sending of initialisation strings to the GPS - only used by backends
392  void send_blob_start(uint8_t instance, const char *_blob, uint16_t size);
393  void send_blob_update(uint8_t instance);
394 
395  // return last fix time since the 1/1/1970 in microseconds
396  uint64_t time_epoch_usec(uint8_t instance) const;
397  uint64_t time_epoch_usec(void) const {
399  }
400 
401  // convert GPS week and millis to unix epoch in ms
402  static uint64_t time_epoch_convert(uint16_t gps_week, uint32_t gps_ms);
403 
404  static const struct AP_Param::GroupInfo var_info[];
405 
407 
408  // indicate which bit in LOG_BITMASK indicates gps logging enabled
409  void set_log_gps_bit(uint32_t bit) { _log_gps_bit = bit; }
410 
411  // report if the gps is healthy (this is defined as existing, an update at a rate greater than 4Hz,
412  // as well as any driver specific behaviour)
413  bool is_healthy(uint8_t instance) const;
414  bool is_healthy(void) const { return is_healthy(primary_instance); }
415 
416  // returns true if all GPS instances have passed all final arming checks/state changes
417  bool prepare_for_arming(void);
418 
419 protected:
420 
421  // configuration parameters
423  AP_Int8 _navfilter;
424  AP_Int8 _auto_switch;
425  AP_Int8 _min_dgps;
426  AP_Int16 _sbp_logmask;
427  AP_Int8 _inject_to;
429  AP_Int8 _sbas_mode;
430  AP_Int8 _min_elevation;
431  AP_Int8 _raw_data;
433  AP_Int16 _rate_ms[GPS_MAX_RECEIVERS]; // this parameter should always be accessed using get_rate_ms()
434  AP_Int8 _save_config;
435  AP_Int8 _auto_config;
438  AP_Int8 _blend_mask;
439  AP_Float _blend_tc;
440 
441  uint32_t _log_gps_bit = -1;
442 
443 private:
445 
446  // returns the desired gps update rate in milliseconds
447  // this does not provide any guarantee that the GPS is updating at the requested
448  // rate it is simply a helper for use in the backends for determining what rate
449  // they should be configuring the GPS to run at
450  uint16_t get_rate_ms(uint8_t instance) const;
451 
452  struct GPS_timing {
453  // the time we got our last fix in system milliseconds
455 
456  // the time we got our last message in system milliseconds
458 
459  // delta time between the last pair of GPS updates in system milliseconds
460  uint16_t delta_time_ms;
461  };
462  // Note allowance for an additional instance to contain blended data
467 
469  uint8_t primary_instance:2;
470 
472  uint8_t num_instances:2;
473 
474  // which ports are locked
475  uint8_t locked_ports:2;
476 
477  // state of auto-detection process, per instance
478  struct detect_state {
480  uint8_t current_baud;
482  struct UBLOX_detect_state ublox_detect_state;
483 #if !HAL_MINIMIZE_FEATURES
484  struct MTK_detect_state mtk_detect_state;
485  struct MTK19_detect_state mtk19_detect_state;
486  struct SIRF_detect_state sirf_detect_state;
487 #endif // !HAL_MINIMIZE_FEATURES
488  struct NMEA_detect_state nmea_detect_state;
489  struct SBP_detect_state sbp_detect_state;
490  struct SBP2_detect_state sbp2_detect_state;
491  struct ERB_detect_state erb_detect_state;
493 
494  struct {
495  const char *blob;
496  uint16_t remaining;
498 
499  static const uint32_t _baudrates[];
500  static const char _initialisation_blob[];
501  static const char _initialisation_raw_blob[];
502 
503  void detect_instance(uint8_t instance);
504  void update_instance(uint8_t instance);
505 
506  /*
507  buffer for re-assembling RTCM data for GPS injection.
508  The 8 bit flags field in GPS_RTCM_DATA is interpreted as:
509  1 bit for "is fragmented"
510  2 bits for fragment number
511  5 bits for sequence number
512 
513  The rtcm_buffer is allocated on first use. Once a block of data
514  is successfully reassembled it is injected into all active GPS
515  backends. This assumes we don't want more than 4*180=720 bytes
516  in a RTCM data block
517  */
518  struct rtcm_buffer {
520  uint8_t sequence:5;
521  uint8_t fragment_count;
522  uint16_t total_length;
523  uint8_t buffer[MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN*4];
524  } *rtcm_buffer;
525 
526  // re-assemble GPS_RTCM_DATA message
527  void handle_gps_rtcm_data(const mavlink_message_t *msg);
528  void handle_gps_inject(const mavlink_message_t *msg);
529 
530  //Inject a packet of raw binary to a GPS
531  void inject_data(uint8_t *data, uint16_t len);
532  void inject_data(uint8_t instance, uint8_t *data, uint16_t len);
533 
534 
535  // GPS blending and switching
536  Vector2f _NE_pos_offset_m[GPS_MAX_RECEIVERS]; // Filtered North,East position offset from GPS instance to blended solution in _output_state.location (m)
537  float _hgt_offset_cm[GPS_MAX_RECEIVERS]; // Filtered height offset from GPS instance relative to blended solution in _output_state.location (cm)
538  Vector3f _blended_antenna_offset; // blended antenna offset
539  float _blended_lag_sec = 0.001f * GPS_MAX_RATE_MS; // blended receiver lag in seconds
540  float _blend_weights[GPS_MAX_RECEIVERS]; // blend weight for each GPS. The blend weights must sum to 1.0 across all instances.
541  uint32_t _last_time_updated[GPS_MAX_RECEIVERS]; // the last value of state.last_gps_time_ms read for that GPS instance - used to detect new data.
542  float _omega_lpf; // cutoff frequency in rad/sec of LPF applied to position offsets
543  bool _output_is_blended; // true when a blended GPS solution being output
544  uint8_t _blend_health_counter; // 0 = perfectly health, 100 = very unhealthy
545 
546  // calculate the blend weight. Returns true if blend could be calculated, false if not
547  bool calc_blend_weights(void);
548 
549  // calculate the blended state
550  void calc_blended_state(void);
551 
552  bool should_df_log() const;
553 
554  // Auto configure types
558  };
559 
560 };
561 
562 namespace AP {
563  AP_GPS &gps();
564 };
uint32_t last_message_time_ms
Definition: AP_GPS.h:457
uint32_t rtk_age_ms(void) const
Definition: AP_GPS.h:345
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
uint8_t locked_ports
Definition: AP_GPS.h:475
bool get_lag(float &lag_sec) const
Definition: AP_GPS.h:352
uint16_t rtk_week_number
GPS Week Number of last baseline.
Definition: AP_GPS.h:153
uint8_t fragment_count
Definition: AP_GPS.h:521
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_GPS.h:404
uint8_t current_baud
Definition: AP_GPS.h:480
GPS_Engine_Setting
Definition: AP_GPS.h:108
uint32_t last_gps_time_ms
the system time we got the last GPS timestamp, milliseconds
Definition: AP_GPS.h:149
friend class AP_GPS_PX4
Definition: AP_GPS.h:57
AP_Int16 _delay_ms[GPS_MAX_RECEIVERS]
Definition: AP_GPS.h:437
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
uint8_t num_sensors(void) const
Definition: AP_GPS.cpp:307
void calc_blended_state(void)
Definition: AP_GPS.cpp:1327
float ground_speed() const
Definition: AP_GPS.h:235
GPS_Status status
driver fix status
Definition: AP_GPS.h:132
AP_Int8 _inject_to
Definition: AP_GPS.h:427
AP_Int8 _min_elevation
Definition: AP_GPS.h:430
bool have_vertical_velocity
does GPS give vertical velocity? Set to true only once available.
Definition: AP_GPS.h:145
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
int32_t rtk_baseline_z_mm
Current baseline in ECEF z or NED down component in mm.
Definition: AP_GPS.h:159
Vector3f velocity
3D velocity in m/s, in NED format
Definition: AP_GPS.h:141
GPS_State state[GPS_MAX_RECEIVERS+1]
Definition: AP_GPS.h:464
uint8_t primary_instance
primary GPS instance
Definition: AP_GPS.h:469
void send_mavlink_gps2_raw(mavlink_channel_t chan)
Definition: AP_GPS.cpp:942
void lock_port(uint8_t instance, bool locked)
Definition: AP_GPS.cpp:866
uint16_t time_week(uint8_t instance) const
Definition: AP_GPS.h:276
bool all_consistent(float &distance) const
Definition: AP_GPS.cpp:1002
uint32_t last_fix_time_ms(uint8_t instance) const
Definition: AP_GPS.h:301
uint32_t _last_time_updated[GPS_MAX_RECEIVERS]
Definition: AP_GPS.h:541
void handle_gps_inject(const mavlink_message_t *msg)
Definition: AP_GPS.cpp:777
void broadcast_first_configuration_failure_reason(void) const
Definition: AP_GPS.cpp:991
uint32_t last_message_time_ms(uint8_t instance) const
Definition: AP_GPS.h:310
AP_Int8 _navfilter
Definition: AP_GPS.h:423
bool should_df_log() const
Definition: AP_GPS.cpp:579
bool have_vertical_velocity(void) const
Definition: AP_GPS.h:329
AP_GPS_Backend * drivers[GPS_MAX_RECEIVERS]
Definition: AP_GPS.h:465
#define GPS_MAX_RATE_MS
Definition: AP_GPS.h:34
float ground_course(uint8_t instance) const
Definition: AP_GPS.h:245
GPS_timing timing[GPS_MAX_RECEIVERS+1]
Definition: AP_GPS.h:463
GPS_Status highest_supported_status(uint8_t instance) const
Definition: AP_GPS.cpp:571
const Location & location(uint8_t instance) const
Definition: AP_GPS.h:200
AP_GPS()
Definition: AP_GPS.cpp:265
float distance
Definition: location.cpp:94
uint16_t last_message_delta_time_ms(uint8_t instance) const
Definition: AP_GPS.h:318
GPS_Type
Definition: AP_GPS.h:77
uint8_t rtk_num_sats(uint8_t instance) const
Definition: AP_GPS.h:334
int32_t ground_course_cd(uint8_t instance) const
Definition: AP_GPS.h:252
void update_instance(uint8_t instance)
Definition: AP_GPS.cpp:598
int32_t rtk_baseline_y_mm
Current baseline in ECEF y or NED east component in mm.
Definition: AP_GPS.h:158
Receiving valid messages and 3D RTK Fixed.
Definition: AP_GPS.h:103
uint32_t ground_speed_cm(void)
Definition: AP_GPS.h:240
A system for managing and storing variables that are of general interest to the system.
uint16_t get_vdop() const
Definition: AP_GPS.h:295
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
GPS_Status
GPS status codes.
Definition: AP_GPS.h:96
static AP_GPS * _singleton
Definition: AP_GPS.h:444
bool is_healthy(void) const
Definition: AP_GPS.h:414
float _omega_lpf
Definition: AP_GPS.h:542
void send_mavlink_gps_raw(mavlink_channel_t chan)
Definition: AP_GPS.cpp:899
Vector3f _blended_antenna_offset
Definition: AP_GPS.h:538
GPS_AUTO_CONFIG
Definition: AP_GPS.h:555
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
const Vector3f & velocity() const
Definition: AP_GPS.h:227
AP_Int8 _sbas_mode
Definition: AP_GPS.h:429
const Vector3f & get_antenna_offset(uint8_t instance) const
Definition: AP_GPS.cpp:1137
uint8_t num_sats() const
Definition: AP_GPS.h:263
const Vector3f & velocity(uint8_t instance) const
Definition: AP_GPS.h:224
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
Definition: AP_AHRS.cpp:486
float _hgt_offset_cm[GPS_MAX_RECEIVERS]
Definition: AP_GPS.h:537
float ground_speed(uint8_t instance) const
Definition: AP_GPS.h:232
Receiving valid messages and 3D lock with differential improvements.
Definition: AP_GPS.h:101
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
uint32_t _last_instance_swap_ms
Definition: AP_GPS.h:428
uint8_t rtk_num_sats
Current number of satellites used for RTK calculation.
Definition: AP_GPS.h:155
Receiving valid messages and 3D RTK Float.
Definition: AP_GPS.h:102
bool blend_health_check() const
Definition: AP_GPS.cpp:1018
void send_mavlink_gps_rtk(mavlink_channel_t chan, uint8_t inst)
Definition: AP_GPS.cpp:971
bool vertical_accuracy(float &vacc) const
Definition: AP_GPS.h:219
uint32_t last_baud_change_ms
Definition: AP_GPS.h:479
uint32_t last_message_time_ms(void) const
Definition: AP_GPS.h:313
const char * blob
Definition: AP_GPS.h:495
uint32_t time_week_ms(uint8_t instance) const
Definition: AP_GPS.h:268
uint8_t rtk_baseline_coords_type
Coordinate system of baseline. 0 == ECEF, 1 == NED.
Definition: AP_GPS.h:156
int32_t rtk_iar_num_hypotheses
Current number of integer ambiguity hypotheses.
Definition: AP_GPS.h:161
uint16_t time_week() const
Definition: AP_GPS.h:279
uint16_t total_length
Definition: AP_GPS.h:522
uint32_t rtk_age_ms(uint8_t instance) const
Definition: AP_GPS.h:342
uint32_t last_fix_time_ms(void) const
Definition: AP_GPS.h:304
AP_Int16 _rate_ms[GPS_MAX_RECEIVERS]
Definition: AP_GPS.h:433
bool horizontal_accuracy(float &hacc) const
Definition: AP_GPS.h:214
uint16_t time_week
GPS week number.
Definition: AP_GPS.h:134
Receiving valid messages and 2D lock.
Definition: AP_GPS.h:99
uint32_t rtk_age_ms
GPS age of last baseline correction in milliseconds (0 when no corrections, 0xFFFFFFFF indicates over...
Definition: AP_GPS.h:154
uint16_t get_hdop(uint8_t instance) const
Definition: AP_GPS.h:284
bool all_configured(void) const
Definition: AP_GPS.h:381
AP_Float _blend_tc
Definition: AP_GPS.h:439
GPS_Status status(uint8_t instance) const
Query GPS status.
Definition: AP_GPS.h:189
void set_log_gps_bit(uint32_t bit)
Definition: AP_GPS.h:409
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
AP_Int8 _save_config
Definition: AP_GPS.h:434
uint16_t get_vdop(uint8_t instance) const
Definition: AP_GPS.h:292
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
uint32_t rtk_accuracy
Current estimate of 3D baseline accuracy (receiver dependent, typical 0 to 9999)
Definition: AP_GPS.h:160
struct AP_GPS::rtcm_buffer * rtcm_buffer
Location location
last fix location
Definition: AP_GPS.h:135
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
bool speed_accuracy(float &sacc) const
Definition: AP_GPS.h:209
uint8_t fragments_received
Definition: AP_GPS.h:519
uint8_t num_sats(uint8_t instance) const
Definition: AP_GPS.h:260
static const uint32_t _baudrates[]
Definition: AP_GPS.h:499
GPS_Config
Definition: AP_GPS.h:120
AP_Int8 _gnss_mode[GPS_MAX_RECEIVERS]
Definition: AP_GPS.h:432
Receiving valid GPS messages but no lock.
Definition: AP_GPS.h:98
uint16_t last_message_delta_time_ms(void) const
Definition: AP_GPS.h:321
AP_Int8 _raw_data
Definition: AP_GPS.h:431
static uint64_t time_epoch_convert(uint16_t gps_week, uint32_t gps_ms)
Definition: AP_GPS.cpp:347
void handle_msg(const mavlink_message_t *msg)
Definition: AP_GPS.cpp:789
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
const Location & location() const
Definition: AP_GPS.h:203
GPS_Status status(void) const
Definition: AP_GPS.h:192
AP_Int8 _auto_config
Definition: AP_GPS.h:435
No GPS connected/detected.
Definition: AP_GPS.h:97
uint8_t primary_sensor(void) const
Definition: AP_GPS.h:184
void send_blob_update(uint8_t instance)
Definition: AP_GPS.cpp:381
uint32_t rtk_time_week_ms
GPS Time of Week of last baseline in milliseconds.
Definition: AP_GPS.h:152
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
bool calc_blend_weights(void)
Definition: AP_GPS.cpp:1165
AP_Int8 _type[GPS_MAX_RECEIVERS]
Definition: AP_GPS.h:422
void update(void)
Definition: AP_GPS.cpp:678
Receiving valid messages and 3D lock.
Definition: AP_GPS.h:100
uint8_t first_unconfigured_gps(void) const
Definition: AP_GPS.cpp:981
float vertical_accuracy
vertical RMS accuracy estimate in m
Definition: AP_GPS.h:144
AP_GPS & operator=(const AP_GPS &)=delete
uint16_t get_rate_ms(uint8_t instance) const
Definition: AP_GPS.cpp:1153
static const char _initialisation_raw_blob[]
Definition: AP_GPS.h:501
float _blended_lag_sec
Definition: AP_GPS.h:539
uint16_t hdop
horizontal dilution of precision in cm
Definition: AP_GPS.h:138
Vector2f _NE_pos_offset_m[GPS_MAX_RECEIVERS]
Definition: AP_GPS.h:536
AP_Int8 _min_dgps
Definition: AP_GPS.h:425
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 GPS_MAX_RECEIVERS
Definition: AP_GPS.h:30
AP_Int16 _sbp_logmask
Definition: AP_GPS.h:426
uint16_t get_hdop() const
Definition: AP_GPS.h:287
int32_t ground_course_cd() const
Definition: AP_GPS.h:255
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
bool have_vertical_velocity(uint8_t instance) const
Definition: AP_GPS.h:326
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]
int32_t rtk_baseline_x_mm
Current baseline in ECEF x or NED north component in mm.
Definition: AP_GPS.h:157