Path: blob/master/libraries/AP_GPS/AP_GPS_Blended.cpp
9532 views
#include "AP_GPS_config.h"12#if AP_GPS_BLENDED_ENABLED34#include "AP_GPS_Blended.h"56// defines used to specify the mask position for use of different accuracy metrics in the blending algorithm7#define BLEND_MASK_USE_HPOS_ACC 18#define BLEND_MASK_USE_VPOS_ACC 29#define BLEND_MASK_USE_SPD_ACC 41011#define BLEND_COUNTER_FAILURE_INCREMENT 101213/*14calculate the weightings used to blend GPSs location and velocity data15*/16bool AP_GPS_Blended::_calc_weights(void)17{18static_assert(GPS_MAX_RECEIVERS == 2, "GPS blending only currently works with 2 receivers");19// Note that the early quit below relies upon exactly 2 instances20// The time delta calculations below also rely upon every instance being currently detected and being parsed2122// exit immediately if not enough receivers to do blending23if (gps.state[0].status <= AP_GPS::NO_FIX || gps.state[1].status <= AP_GPS::NO_FIX) {24return false;25}2627// Use the oldest non-zero time, but if time difference is excessive, use newest to prevent a disconnected receiver from blocking updates28uint32_t max_ms = 0; // newest non-zero system time of arrival of a GPS message29uint32_t min_ms = -1; // oldest non-zero system time of arrival of a GPS message30uint32_t max_rate_ms = 0; // largest update interval of a GPS receiver31for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {32// Find largest and smallest times33if (gps.state[i].last_gps_time_ms > max_ms) {34max_ms = gps.state[i].last_gps_time_ms;35}36if ((gps.state[i].last_gps_time_ms < min_ms) && (gps.state[i].last_gps_time_ms > 0)) {37min_ms = gps.state[i].last_gps_time_ms;38}39max_rate_ms = MAX(gps.get_rate_ms(i), max_rate_ms);40if (isinf(gps.state[i].speed_accuracy) ||41isinf(gps.state[i].horizontal_accuracy) ||42isinf(gps.state[i].vertical_accuracy)) {43return false;44}45}46if ((max_ms - min_ms) < (2 * max_rate_ms)) {47// data is not too delayed so use the oldest time_stamp to give a chance for data from that receiver to be updated48state.last_gps_time_ms = min_ms;49} else {50// receiver data has timed out so fail out of blending51return false;52}5354// calculate the sum squared speed accuracy across all GPS sensors55float speed_accuracy_sum_sq = 0.0f;56if (gps._blend_mask & BLEND_MASK_USE_SPD_ACC) {57for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {58if (gps.state[i].status >= AP_GPS::GPS_OK_FIX_3D) {59if (gps.state[i].have_speed_accuracy && gps.state[i].speed_accuracy > 0.0f) {60speed_accuracy_sum_sq += sq(gps.state[i].speed_accuracy);61} else {62// not all receivers support this metric so set it to zero and don't use it63speed_accuracy_sum_sq = 0.0f;64break;65}66}67}68}6970// calculate the sum squared horizontal position accuracy across all GPS sensors71float horizontal_accuracy_sum_sq = 0.0f;72if (gps._blend_mask & BLEND_MASK_USE_HPOS_ACC) {73for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {74if (gps.state[i].status >= AP_GPS::GPS_OK_FIX_2D) {75if (gps.state[i].have_horizontal_accuracy && gps.state[i].horizontal_accuracy > 0.0f) {76horizontal_accuracy_sum_sq += sq(gps.state[i].horizontal_accuracy);77} else {78// not all receivers support this metric so set it to zero and don't use it79horizontal_accuracy_sum_sq = 0.0f;80break;81}82}83}84}8586// calculate the sum squared vertical position accuracy across all GPS sensors87float vertical_accuracy_sum_sq = 0.0f;88if (gps._blend_mask & BLEND_MASK_USE_VPOS_ACC) {89for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {90if (gps.state[i].status >= AP_GPS::GPS_OK_FIX_3D) {91if (gps.state[i].have_vertical_accuracy && gps.state[i].vertical_accuracy > 0.0f) {92vertical_accuracy_sum_sq += sq(gps.state[i].vertical_accuracy);93} else {94// not all receivers support this metric so set it to zero and don't use it95vertical_accuracy_sum_sq = 0.0f;96break;97}98}99}100}101// Check if we can do blending using reported accuracy102bool can_do_blending = (horizontal_accuracy_sum_sq > 0.0f || vertical_accuracy_sum_sq > 0.0f || speed_accuracy_sum_sq > 0.0f);103104// if we can't do blending using reported accuracy, return false and hard switch logic will be used instead105if (!can_do_blending) {106return false;107}108109float sum_of_all_weights = 0.0f;110111// calculate a weighting using the reported horizontal position112float hpos_blend_weights[GPS_MAX_RECEIVERS] = {};113if (horizontal_accuracy_sum_sq > 0.0f) {114// calculate the weights using the inverse of the variances115float sum_of_hpos_weights = 0.0f;116for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {117if (gps.state[i].status >= AP_GPS::GPS_OK_FIX_2D && gps.state[i].horizontal_accuracy >= 0.001f) {118hpos_blend_weights[i] = horizontal_accuracy_sum_sq / sq(gps.state[i].horizontal_accuracy);119sum_of_hpos_weights += hpos_blend_weights[i];120}121}122// normalise the weights123if (sum_of_hpos_weights > 0.0f) {124for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {125hpos_blend_weights[i] = hpos_blend_weights[i] / sum_of_hpos_weights;126}127sum_of_all_weights += 1.0f;128}129}130131// calculate a weighting using the reported vertical position accuracy132float vpos_blend_weights[GPS_MAX_RECEIVERS] = {};133if (vertical_accuracy_sum_sq > 0.0f) {134// calculate the weights using the inverse of the variances135float sum_of_vpos_weights = 0.0f;136for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {137if (gps.state[i].status >= AP_GPS::GPS_OK_FIX_3D && gps.state[i].vertical_accuracy >= 0.001f) {138vpos_blend_weights[i] = vertical_accuracy_sum_sq / sq(gps.state[i].vertical_accuracy);139sum_of_vpos_weights += vpos_blend_weights[i];140}141}142// normalise the weights143if (sum_of_vpos_weights > 0.0f) {144for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {145vpos_blend_weights[i] = vpos_blend_weights[i] / sum_of_vpos_weights;146}147sum_of_all_weights += 1.0f;148};149}150151// calculate a weighting using the reported speed accuracy152float spd_blend_weights[GPS_MAX_RECEIVERS] = {};153if (speed_accuracy_sum_sq > 0.0f) {154// calculate the weights using the inverse of the variances155float sum_of_spd_weights = 0.0f;156for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {157if (gps.state[i].status >= AP_GPS::GPS_OK_FIX_3D && gps.state[i].speed_accuracy >= 0.001f) {158spd_blend_weights[i] = speed_accuracy_sum_sq / sq(gps.state[i].speed_accuracy);159sum_of_spd_weights += spd_blend_weights[i];160}161}162// normalise the weights163if (sum_of_spd_weights > 0.0f) {164for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {165spd_blend_weights[i] = spd_blend_weights[i] / sum_of_spd_weights;166}167sum_of_all_weights += 1.0f;168}169}170171if (!is_positive(sum_of_all_weights)) {172return false;173}174175// calculate an overall weight176for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {177_blend_weights[i] = (hpos_blend_weights[i] + vpos_blend_weights[i] + spd_blend_weights[i]) / sum_of_all_weights;178}179180return true;181}182183bool AP_GPS_Blended::calc_weights()184{185// adjust blend health counter186if (!_calc_weights()) {187_blend_health_counter = MIN(_blend_health_counter+BLEND_COUNTER_FAILURE_INCREMENT, 100);188} else if (_blend_health_counter > 0) {189_blend_health_counter--;190}191192// we are never healthy if we do not have any weights:193bool non_zero_weight_found = false;194for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {195if (_blend_weights[i] > 0) {196non_zero_weight_found = true;197break;198}199}200if (!non_zero_weight_found) {201return false;202}203204// stop blending if unhealthy205return _blend_health_counter < 50;206}207208/*209calculate a blended GPS state210*/211void AP_GPS_Blended::calc_state(void)212{213// initialise the blended states so we can accumulate the results using the weightings for each GPS receiver214state.instance = GPS_BLENDED_INSTANCE;215state.status = AP_GPS::NO_FIX;216state.time_week_ms = 0;217state.time_week = 0;218state.ground_speed = 0.0f;219state.ground_course = 0.0f;220state.hdop = GPS_UNKNOWN_DOP;221state.vdop = GPS_UNKNOWN_DOP;222state.num_sats = 0;223state.velocity.zero();224state.speed_accuracy = 1e6f;225state.horizontal_accuracy = 1e6f;226state.vertical_accuracy = 1e6f;227state.have_vertical_velocity = false;228state.have_speed_accuracy = false;229state.have_horizontal_accuracy = false;230state.have_vertical_accuracy = false;231state.location = {};232233_blended_antenna_offset.zero();234_blended_lag_sec = 0;235236#if HAL_LOGGING_ENABLED237const uint32_t last_blended_message_time_ms = timing.last_message_time_ms;238#endif239timing.last_fix_time_ms = 0;240timing.last_message_time_ms = 0;241242if (gps.state[0].have_undulation) {243state.have_undulation = true;244state.undulation = gps.state[0].undulation;245} else if (gps.state[1].have_undulation) {246state.have_undulation = true;247state.undulation = gps.state[1].undulation;248} else {249state.have_undulation = false;250}251252// combine the states into a blended solution253for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {254// use the highest status255if (gps.state[i].status > state.status) {256state.status = gps.state[i].status;257}258259// calculate a blended average velocity260state.velocity += gps.state[i].velocity * _blend_weights[i];261262// report the best valid accuracies and DOP metrics263264if (gps.state[i].have_horizontal_accuracy && gps.state[i].horizontal_accuracy > 0.0f && gps.state[i].horizontal_accuracy < state.horizontal_accuracy) {265state.have_horizontal_accuracy = true;266state.horizontal_accuracy = gps.state[i].horizontal_accuracy;267}268269if (gps.state[i].have_vertical_accuracy && gps.state[i].vertical_accuracy > 0.0f && gps.state[i].vertical_accuracy < state.vertical_accuracy) {270state.have_vertical_accuracy = true;271state.vertical_accuracy = gps.state[i].vertical_accuracy;272}273274if (gps.state[i].have_vertical_velocity) {275state.have_vertical_velocity = true;276}277278if (gps.state[i].have_speed_accuracy && gps.state[i].speed_accuracy > 0.0f && gps.state[i].speed_accuracy < state.speed_accuracy) {279state.have_speed_accuracy = true;280state.speed_accuracy = gps.state[i].speed_accuracy;281}282283if (gps.state[i].hdop > 0 && gps.state[i].hdop < state.hdop) {284state.hdop = gps.state[i].hdop;285}286287if (gps.state[i].vdop > 0 && gps.state[i].vdop < state.vdop) {288state.vdop = gps.state[i].vdop;289}290291if (gps.state[i].num_sats > 0 && gps.state[i].num_sats > state.num_sats) {292state.num_sats = gps.state[i].num_sats;293}294295// report a blended average GPS antenna position296Vector3f temp_antenna_offset = gps.params[i].antenna_offset;297temp_antenna_offset *= _blend_weights[i];298_blended_antenna_offset += temp_antenna_offset;299300// blend the timing data301if (gps.timing[i].last_fix_time_ms > timing.last_fix_time_ms) {302timing.last_fix_time_ms = gps.timing[i].last_fix_time_ms;303}304if (gps.timing[i].last_message_time_ms > timing.last_message_time_ms) {305timing.last_message_time_ms = gps.timing[i].last_message_time_ms;306}307}308309/*310* Calculate an instantaneous weighted/blended average location from the available GPS instances and store in the _output_state.311* This will be statistically the most likely location, but will be not stable enough for direct use by the autopilot.312*/313314// Use the GPS with the highest weighting as the reference position315float best_weight = 0.0f;316uint8_t best_index = 0;317for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {318if (_blend_weights[i] > best_weight) {319best_weight = _blend_weights[i];320best_index = i;321state.location = gps.state[i].location;322}323}324325// Calculate the weighted sum of horizontal and vertical position offsets relative to the reference position326Vector2f blended_NE_offset_m;327float blended_alt_offset_cm = 0.0f;328blended_NE_offset_m.zero();329for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {330if (_blend_weights[i] > 0.0f && i != best_index) {331blended_NE_offset_m += state.location.get_distance_NE(gps.state[i].location) * _blend_weights[i];332blended_alt_offset_cm += (float)(gps.state[i].location.alt - state.location.alt) * _blend_weights[i];333}334}335336// Add the sum of weighted offsets to the reference location to obtain the blended location337state.location.offset(blended_NE_offset_m.x, blended_NE_offset_m.y);338state.location.offset_up_cm(blended_alt_offset_cm);339340// Calculate ground speed and course from blended velocity vector341state.ground_speed = state.velocity.xy().length();342state.ground_course = wrap_360(degrees(atan2f(state.velocity.y, state.velocity.x)));343344// If the GPS week is the same then use a blended time_week_ms345// If week is different, then use time stamp from GPS with largest weighting346// detect inconsistent week data347uint8_t last_week_instance = 0;348bool weeks_consistent = true;349for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {350if (last_week_instance == 0 && _blend_weights[i] > 0) {351// this is our first valid sensor week data352last_week_instance = gps.state[i].time_week;353} else if (last_week_instance != 0 && _blend_weights[i] > 0 && last_week_instance != gps.state[i].time_week) {354// there is valid sensor week data that is inconsistent355weeks_consistent = false;356}357}358// calculate output359if (!weeks_consistent) {360// use data from highest weighted sensor361state.time_week = gps.state[best_index].time_week;362state.time_week_ms = gps.state[best_index].time_week_ms;363} else {364// use week number from highest weighting GPS (they should all have the same week number)365state.time_week = gps.state[best_index].time_week;366// calculate a blended value for the number of ms lapsed in the week367double temp_time_0 = 0.0;368for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {369if (_blend_weights[i] > 0.0f) {370temp_time_0 += (double)gps.state[i].time_week_ms * (double)_blend_weights[i];371}372}373state.time_week_ms = (uint32_t)temp_time_0;374}375376// calculate a blended value for the timing data and lag377double temp_time_1 = 0.0;378double temp_time_2 = 0.0;379for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {380if (_blend_weights[i] > 0.0f) {381temp_time_1 += (double)gps.timing[i].last_fix_time_ms * (double) _blend_weights[i];382temp_time_2 += (double)gps.timing[i].last_message_time_ms * (double)_blend_weights[i];383float gps_lag_sec = 0;384gps.get_lag(i, gps_lag_sec);385_blended_lag_sec += gps_lag_sec * _blend_weights[i];386}387}388timing.last_fix_time_ms = (uint32_t)temp_time_1;389timing.last_message_time_ms = (uint32_t)temp_time_2;390391#if HAL_LOGGING_ENABLED392if (timing.last_message_time_ms > last_blended_message_time_ms &&393should_log()) {394gps.Write_GPS(GPS_BLENDED_INSTANCE);395}396#endif397398#if CONFIG_HAL_BOARD == HAL_BOARD_SITL399// sanity checks400if (state.status > AP_GPS::NO_FIX && !state.location.initialised()) {401AP_HAL::panic("status is >NO_FIX but location is zero");402}403#endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL404}405406bool AP_GPS_Blended::get_lag(float &lag_sec) const407{408lag_sec = _blended_lag_sec;409// auto switching uses all GPS receivers, so all must be configured410uint8_t inst; // we don't actually care what the number is, but must pass it411return gps.first_unconfigured_gps(inst);412}413414#endif // AP_GPS_BLENDED_ENABLED415416417