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 40 #define GPS_LEAPSECONDS_MILLIS 18000ULL 42 #define UNIX_OFFSET_MSEC (17000ULL * 86400ULL + 52ULL * 10ULL * AP_MSEC_PER_WEEK - GPS_LEAPSECONDS_MILLIS) 173 void handle_msg(
const mavlink_message_t *msg);
351 bool get_lag(uint8_t instance,
float &lag_sec)
const;
365 void setHIL_Accuracy(uint8_t instance,
float vdop,
float hacc,
float vacc,
float sacc,
bool _have_vertical_velocity, uint32_t sample_ms);
368 void lock_port(uint8_t instance,
bool locked);
392 void send_blob_start(uint8_t instance,
const char *_blob, uint16_t size);
483 #if !HAL_MINIMIZE_FEATURES 487 #endif // !HAL_MINIMIZE_FEATURES 523 uint8_t
buffer[MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN*4];
532 void inject_data(uint8_t instance, uint8_t *data, uint16_t len);
uint32_t last_message_time_ms
uint32_t rtk_age_ms(void) const
uint32_t time_week_ms
GPS time (milliseconds from start of GPS week)
AP_HAL::UARTDriver * _port[GPS_MAX_RECEIVERS]
void send_blob_start(uint8_t instance, const char *_blob, uint16_t size)
static AP_SerialManager serial_manager
float _blend_weights[GPS_MAX_RECEIVERS]
bool get_lag(float &lag_sec) const
uint16_t rtk_week_number
GPS Week Number of last baseline.
static const struct AP_Param::GroupInfo var_info[]
uint32_t last_gps_time_ms
the system time we got the last GPS timestamp, milliseconds
AP_Int16 _delay_ms[GPS_MAX_RECEIVERS]
bool prepare_for_arming(void)
uint32_t time_week_ms() const
void detect_instance(uint8_t instance)
uint8_t num_sensors(void) const
void calc_blended_state(void)
float ground_speed() const
GPS_Status status
driver fix status
bool have_vertical_velocity
does GPS give vertical velocity? Set to true only once available.
static uint8_t buffer[SRXL_FRAMELEN_MAX]
int32_t rtk_baseline_z_mm
Current baseline in ECEF z or NED down component in mm.
Vector3f velocity
3D velocity in m/s, in NED format
GPS_State state[GPS_MAX_RECEIVERS+1]
uint8_t primary_instance
primary GPS instance
void send_mavlink_gps2_raw(mavlink_channel_t chan)
void lock_port(uint8_t instance, bool locked)
uint16_t time_week(uint8_t instance) const
bool all_consistent(float &distance) const
uint32_t last_fix_time_ms(uint8_t instance) const
uint32_t _last_time_updated[GPS_MAX_RECEIVERS]
void handle_gps_inject(const mavlink_message_t *msg)
void broadcast_first_configuration_failure_reason(void) const
uint32_t last_message_time_ms(uint8_t instance) const
bool should_df_log() const
bool have_vertical_velocity(void) const
AP_GPS_Backend * drivers[GPS_MAX_RECEIVERS]
float ground_course(uint8_t instance) const
GPS_timing timing[GPS_MAX_RECEIVERS+1]
GPS_Status highest_supported_status(uint8_t instance) const
const Location & location(uint8_t instance) const
uint16_t last_message_delta_time_ms(uint8_t instance) const
uint8_t rtk_num_sats(uint8_t instance) const
int32_t ground_course_cd(uint8_t instance) const
void update_instance(uint8_t instance)
int32_t rtk_baseline_y_mm
Current baseline in ECEF y or NED east component in mm.
Receiving valid messages and 3D RTK Fixed.
uint32_t ground_speed_cm(void)
A system for managing and storing variables that are of general interest to the system.
uint16_t get_vdop() const
void init(const AP_SerialManager &serial_manager)
Startup initialisation.
void inject_data(uint8_t *data, uint16_t len)
GPS_Status
GPS status codes.
static AP_GPS * _singleton
bool is_healthy(void) const
void send_mavlink_gps_raw(mavlink_channel_t chan)
Vector3f _blended_antenna_offset
uint64_t time_epoch_usec(void) const
uint8_t num_instances
number of GPS instances present
const Vector3f & velocity() const
const Vector3f & get_antenna_offset(uint8_t instance) const
const Vector3f & velocity(uint8_t instance) const
void setHIL_Accuracy(uint8_t instance, float vdop, float hacc, float vacc, float sacc, bool _have_vertical_velocity, uint32_t sample_ms)
float _hgt_offset_cm[GPS_MAX_RECEIVERS]
float ground_speed(uint8_t instance) const
Receiving valid messages and 3D lock with differential improvements.
uint8_t _blend_health_counter
uint32_t _last_instance_swap_ms
uint8_t rtk_num_sats
Current number of satellites used for RTK calculation.
Receiving valid messages and 3D RTK Float.
bool blend_health_check() const
void send_mavlink_gps_rtk(mavlink_channel_t chan, uint8_t inst)
bool vertical_accuracy(float &vacc) const
uint32_t last_baud_change_ms
uint32_t last_message_time_ms(void) const
uint32_t time_week_ms(uint8_t instance) const
uint8_t rtk_baseline_coords_type
Coordinate system of baseline. 0 == ECEF, 1 == NED.
int32_t rtk_iar_num_hypotheses
Current number of integer ambiguity hypotheses.
uint16_t time_week() const
uint32_t rtk_age_ms(uint8_t instance) const
uint32_t last_fix_time_ms(void) const
AP_Int16 _rate_ms[GPS_MAX_RECEIVERS]
bool horizontal_accuracy(float &hacc) const
uint16_t time_week
GPS week number.
Receiving valid messages and 2D lock.
uint32_t rtk_age_ms
GPS age of last baseline correction in milliseconds (0 when no corrections, 0xFFFFFFFF indicates over...
uint16_t get_hdop(uint8_t instance) const
bool all_configured(void) const
GPS_Status status(uint8_t instance) const
Query GPS status.
void set_log_gps_bit(uint32_t bit)
uint32_t last_fix_time_ms
static const char _initialisation_blob[]
uint8_t rtk_num_sats(void) const
uint16_t get_vdop(uint8_t instance) const
float ground_course() const
Common definitions and utility routines for the ArduPilot libraries.
uint16_t vdop
vertical dilution of precision in cm
uint32_t rtk_accuracy
Current estimate of 3D baseline accuracy (receiver dependent, typical 0 to 9999)
struct AP_GPS::rtcm_buffer * rtcm_buffer
Location location
last fix location
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)
bool speed_accuracy(float &sacc) const
uint8_t fragments_received
uint8_t num_sats(uint8_t instance) const
static const uint32_t _baudrates[]
AP_Int8 _gnss_mode[GPS_MAX_RECEIVERS]
Receiving valid GPS messages but no lock.
uint16_t last_message_delta_time_ms(void) const
static uint64_t time_epoch_convert(uint16_t gps_week, uint32_t gps_ms)
void handle_msg(const mavlink_message_t *msg)
AP_HAL::AnalogSource * chan
const Location & location() const
GPS_Status status(void) const
No GPS connected/detected.
uint8_t primary_sensor(void) const
void send_blob_update(uint8_t instance)
uint32_t rtk_time_week_ms
GPS Time of Week of last baseline in milliseconds.
bool have_vertical_accuracy
does GPS give vertical position accuracy? Set to true only once available.
float speed_accuracy
3D velocity RMS accuracy estimate in m/s
void handle_gps_rtcm_data(const mavlink_message_t *msg)
bool have_horizontal_accuracy
does GPS give horizontal position accuracy? Set to true only once available.
float horizontal_accuracy
horizontal RMS accuracy estimate in m
float ground_speed
ground speed in m/sec
bool calc_blend_weights(void)
AP_Int8 _type[GPS_MAX_RECEIVERS]
Receiving valid messages and 3D lock.
uint8_t first_unconfigured_gps(void) const
float vertical_accuracy
vertical RMS accuracy estimate in m
AP_GPS & operator=(const AP_GPS &)=delete
uint16_t get_rate_ms(uint8_t instance) const
static const char _initialisation_raw_blob[]
uint16_t hdop
horizontal dilution of precision in cm
Vector2f _NE_pos_offset_m[GPS_MAX_RECEIVERS]
AP_Vector3f _antenna_offset[GPS_MAX_RECEIVERS]
#define GPS_MAX_RECEIVERS
uint16_t get_hdop() const
int32_t ground_course_cd() const
uint8_t num_sats
Number of visible satellites.
bool get_lag(uint8_t instance, float &lag_sec) const
bool have_vertical_velocity(uint8_t instance) const
bool have_speed_accuracy
does GPS give speed accuracy? Set to true only once available.
float ground_course
ground course in degrees
void Write_DataFlash_Log_Startup_messages()
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.