45 #define GPS_BAUD_TIME_MS 1200 46 #define GPS_TIMEOUT_MS 4000u 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 57 const uint32_t
AP_GPS::_baudrates[] = {9600U, 115200U, 4800U, 19200U, 38400U, 57600U, 230400U};
268 "GPS initilisation blob is to large to be completely sent before the baud rate changes");
318 if (
state[instance].have_speed_accuracy) {
327 if (
state[instance].have_horizontal_accuracy) {
336 if (
state[instance].have_vertical_accuracy) {
384 if (
_port[instance] ==
nullptr) {
418 switch (
_type[instance]) {
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) {
436 if (uavcan !=
nullptr) {
439 if (gps_node != UINT8_MAX) {
443 if (AP_BoardConfig_CAN::get_can_debug() >= 2) {
444 printf(
"AP_GPS_UAVCAN registered\n\r");
462 if (
_port[instance] ==
nullptr) {
471 switch (
_type[instance]) {
512 && new_gps ==
nullptr) {
527 #if !HAL_MINIMIZE_FEATURES 546 #if !HAL_MINIMIZE_FEATURES 562 if (new_gps !=
nullptr) {
582 if (instance ==
nullptr) {
634 bool data_should_be_logged =
false;
637 memset(&
state[instance], 0,
sizeof(
state[instance]));
655 data_should_be_logged =
true;
665 data_should_be_logged =
true;
668 if (data_should_be_logged &&
779 mavlink_gps_inject_data_t packet;
780 mavlink_msg_gps_inject_data_decode(msg, &packet);
791 switch (msg->msgid) {
792 case MAVLINK_MSG_ID_GPS_RTCM_DATA:
796 case MAVLINK_MSG_ID_GPS_INJECT_DATA:
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)
847 istate.
vdop = vdop * 100;
855 if (sample_ms != 0) {
911 if (now - last_send_time_ms[chan] < 1000) {
914 last_send_time_ms[
chan] = now;
923 mavlink_msg_gps_raw_int_send(
955 mavlink_msg_gps2_raw_send(
976 if (
drivers[inst] !=
nullptr &&
drivers[inst]->supports_mavlink_gps_rtk_message()) {
994 if (
drivers[unconfigured] ==
nullptr) {
995 gcs().
send_text(MAV_SEVERITY_INFO,
"GPS %d: was not found", unconfigured + 1);
1014 return (distance < 50);
1028 mavlink_gps_rtcm_data_t packet;
1029 mavlink_msg_gps_rtcm_data_decode(msg, &packet);
1031 if (packet.len > MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN) {
1036 if ((packet.flags & 1) == 0) {
1051 uint8_t fragment = (packet.flags >> 1U) & 0x03;
1052 uint8_t sequence = (packet.flags >> 3U) & 0x1F;
1068 memcpy(&
rtcm_buffer->
buffer[MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN*(uint16_t)fragment], packet.data, packet.len);
1074 if (packet.len < MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN) {
1095 for (uint8_t instance=0; instance<
num_instances; instance++) {
1118 lag_sec = 0.001f * (float)
_delay_ms[instance];
1176 uint32_t max_ms = 0;
1177 uint32_t min_ms = -1;
1178 int16_t max_rate_ms = 0;
1181 if (
state[i].last_gps_time_ms > max_ms) {
1184 if ((
state[i].last_gps_time_ms < min_ms) && (
state[i].last_gps_time_ms > 0)) {
1191 if ((int32_t)(max_ms - min_ms) < (int32_t)(2 * max_rate_ms)) {
1200 float speed_accuracy_sum_sq = 0.0f;
1208 speed_accuracy_sum_sq = 0.0f;
1216 float horizontal_accuracy_sum_sq = 0.0f;
1224 horizontal_accuracy_sum_sq = 0.0f;
1232 float vertical_accuracy_sum_sq = 0.0f;
1240 vertical_accuracy_sum_sq = 0.0f;
1247 bool can_do_blending = (horizontal_accuracy_sum_sq > 0.0f || vertical_accuracy_sum_sq > 0.0f || speed_accuracy_sum_sq > 0.0f);
1250 if (!can_do_blending) {
1254 float sum_of_all_weights = 0.0f;
1258 if (horizontal_accuracy_sum_sq > 0.0
f && (
_blend_mask & BLEND_MASK_USE_HPOS_ACC)) {
1260 float sum_of_hpos_weights = 0.0f;
1264 sum_of_hpos_weights += hpos_blend_weights[i];
1268 if (sum_of_hpos_weights > 0.0
f) {
1270 hpos_blend_weights[i] = hpos_blend_weights[i] / sum_of_hpos_weights;
1272 sum_of_all_weights += 1.0f;
1278 if (vertical_accuracy_sum_sq > 0.0
f && (
_blend_mask & BLEND_MASK_USE_VPOS_ACC)) {
1280 float sum_of_vpos_weights = 0.0f;
1284 sum_of_vpos_weights += vpos_blend_weights[i];
1288 if (sum_of_vpos_weights > 0.0
f) {
1290 vpos_blend_weights[i] = vpos_blend_weights[i] / sum_of_vpos_weights;
1292 sum_of_all_weights += 1.0f;
1298 if (speed_accuracy_sum_sq > 0.0
f && (
_blend_mask & BLEND_MASK_USE_SPD_ACC)) {
1300 float sum_of_spd_weights = 0.0f;
1304 sum_of_spd_weights += spd_blend_weights[i];
1308 if (sum_of_spd_weights > 0.0
f) {
1310 spd_blend_weights[i] = spd_blend_weights[i] / sum_of_spd_weights;
1312 sum_of_all_weights += 1.0f;
1318 _blend_weights[i] = (hpos_blend_weights[i] + vpos_blend_weights[i] + spd_blend_weights[i]) / sum_of_all_weights;
1419 float best_weight = 0.0f;
1420 uint8_t best_index = 0;
1431 float blended_alt_offset_cm = 0.0f;
1432 blended_NE_offset_m.
zero();
1487 uint8_t last_week_instance = 0;
1488 bool weeks_consistent =
true;
1495 weeks_consistent =
false;
1499 if (!weeks_consistent) {
1507 double temp_time_0 = 0.0;
1517 double temp_time_1 = 0.0;
1518 double temp_time_2 = 0.0;
1523 float gps_lag_sec = 0;
1533 return drivers[instance] !=
nullptr &&
1539 bool all_passed =
true;
float norm(const T first, const U second, const Params... parameters)
uint32_t last_message_time_ms
uint32_t rtk_age_ms(void) const
int printf(const char *fmt,...)
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]
virtual AP_GPS::GPS_Status highest_supported_status(void)
struct NMEA_detect_state nmea_detect_state
struct SBP_detect_state sbp_detect_state
static const struct AP_Param::GroupInfo var_info[]
friend class AP_GPS_UBLOX
uint32_t last_gps_time_ms
the system time we got the last GPS timestamp, milliseconds
AP_Int16 _delay_ms[GPS_MAX_RECEIVERS]
virtual bool get_lag(float &lag) const
friend class AP_GPS_MTK19
bool prepare_for_arming(void)
uint32_t time_week_ms() const
void detect_instance(uint8_t instance)
virtual void begin(uint32_t baud)=0
uint8_t num_sensors(void) const
void calc_blended_state(void)
uint8_t register_gps_listener_to_node(AP_GPS_Backend *new_listener, uint8_t node)
float ground_speed() const
virtual void broadcast_configuration_failure_reason(void) const
GPS_Status status
driver fix status
Interface definition for the various Ground Control System.
bool have_vertical_velocity
does GPS give vertical velocity? Set to true only once available.
Vector3f velocity
3D velocity in m/s, in NED format
bool should_log(uint32_t mask) const
GPS_State state[GPS_MAX_RECEIVERS+1]
uint8_t primary_instance
primary GPS instance
void send_mavlink_gps2_raw(mavlink_channel_t chan)
#define AP_GROUPINFO(name, idx, clazz, element, def)
void lock_port(uint8_t instance, bool locked)
bool all_consistent(float &distance) const
virtual void inject_data(const uint8_t *data, uint16_t len)
virtual uint32_t txspace()=0
uint32_t _last_time_updated[GPS_MAX_RECEIVERS]
void broadcast_first_configuration_failure_reason(void) const
void handle_gps_inject(const mavlink_message_t *msg)
bool should_df_log() const
bool have_vertical_velocity(void) const
#define GPS_RTK_INJECT_TO_ALL
static bool _detect(struct NMEA_detect_state &state, uint8_t data)
AP_GPS_Backend * drivers[GPS_MAX_RECEIVERS]
void location_offset(struct Location &loc, float ofs_north, float ofs_east)
GPS_timing timing[GPS_MAX_RECEIVERS+1]
GPS_Status highest_supported_status(uint8_t instance) const
static bool _detect(struct ERB_detect_state &state, uint8_t data)
void * calloc(size_t nmemb, size_t size)
int32_t lat
param 3 - Latitude * 10**7
void update_instance(uint8_t instance)
virtual bool prepare_for_arming(void)
AP_HAL::CANManager ** can_mgr
#define BLEND_MASK_USE_HPOS_ACC
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.
#define HAL_GPS_TYPE_DEFAULT
static AP_GPS * _singleton
static bool _detect(struct MTK19_detect_state &state, uint8_t data)
bool is_healthy(void) const
#define BLEND_MASK_USE_SPD_ACC
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
float wrap_360(const T angle, float unit_mod)
const Vector3f & velocity() const
virtual bool is_healthy(void) const
const Vector3f & get_antenna_offset(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)
Vector2f location_diff(const struct Location &loc1, const struct Location &loc2)
#define GPS_MAX_INSTANCES
#define GPS_WORST_LAG_SEC
float _hgt_offset_cm[GPS_MAX_RECEIVERS]
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
uint8_t _blend_health_counter
bool speed_accuracy(uint8_t instance, float &sacc) const
uint32_t _last_instance_swap_ms
struct MTK19_detect_state mtk19_detect_state
bool blend_health_check() const
void send_mavlink_gps_rtk(mavlink_channel_t chan, uint8_t inst)
virtual size_t write(uint8_t)=0
uint32_t last_baud_change_ms
uint32_t last_message_time_ms(void) const
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)
void broadcast_gps_type() const
uint16_t time_week() const
struct ERB_detect_state erb_detect_state
uint32_t last_fix_time_ms(void) const
static bool _detect(struct UBLOX_detect_state &state, uint8_t data)
virtual void handle_msg(const mavlink_message_t *msg)
virtual void set_flow_control(enum flow_control flow_control_setting)
AP_Int16 _rate_ms[GPS_MAX_RECEIVERS]
uint16_t time_week
GPS week number.
Receiving valid messages and 2D lock.
bool all_configured(void) const
void send_text(MAV_SEVERITY severity, const char *fmt,...)
uint32_t last_fix_time_ms
static const char _initialisation_blob[]
uint8_t rtk_num_sats(void) const
struct SBP2_detect_state sbp2_detect_state
void Log_Write_GPS(uint8_t instance, uint64_t time_us=0)
#define GPS_BLENDED_INSTANCE
float ground_course() const
Common definitions and utility routines for the ArduPilot libraries.
uint16_t vdop
vertical dilution of precision in cm
Location location
last fix location
struct UBLOX_detect_state ublox_detect_state
float constrain_float(const float amt, const float low, const float high)
#define BLEND_COUNTER_FAILURE_INCREMENT
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)
int32_t lng
param 4 - Longitude * 10**7
uint8_t fragments_received
static bool _detect(struct MTK_detect_state &state, uint8_t data)
Vector3f location_3d_diff_NED(const struct Location &loc1, const struct Location &loc2)
static const uint32_t _baudrates[]
Receiving valid GPS messages but no lock.
#define BLEND_MASK_USE_VPOS_ACC
uint16_t last_message_delta_time_ms(void) const
static struct notify_flags_and_values_type flags
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
uint8_t buffer[MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN *4]
GPS_Status status(void) const
struct SIRF_detect_state sirf_detect_state
No GPS connected/detected.
void send_blob_update(uint8_t instance)
struct MTK_detect_state mtk_detect_state
static bool _detect(struct SBP_detect_state &state, uint8_t data)
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
uint8_t find_gps_without_listener(void)
bool calc_blend_weights(void)
virtual void Write_DataFlash_Log_Startup_messages() const
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
void panic(const char *errormsg,...) FMT_PRINTF(1
uint16_t get_rate_ms(uint8_t instance) const
bool vertical_accuracy(uint8_t instance, float &vacc) const
static bool _detect(struct SIRF_detect_state &state, uint8_t data)
uint16_t hdop
horizontal dilution of precision in cm
bool horizontal_accuracy(uint8_t instance, float &hacc) const
Vector2f _NE_pos_offset_m[GPS_MAX_RECEIVERS]
AP_Vector3f _antenna_offset[GPS_MAX_RECEIVERS]
#define GPS_MAX_RECEIVERS
#define MAVLINK_COMM_NUM_BUFFERS
AP_HAL::UARTDriver * find_serial(enum SerialProtocol protocol, uint8_t instance) const
uint16_t get_hdop() const
uint8_t num_sats
Number of visible satellites.
bool get_lag(uint8_t instance, float &lag_sec) const
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
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]