Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_GPS/AP_GPS_Blended.cpp
Views: 1798
#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{18// zero the blend weights19memset(&_blend_weights, 0, sizeof(_blend_weights));202122static_assert(GPS_MAX_RECEIVERS == 2, "GPS blending only currently works with 2 receivers");23// Note that the early quit below relies upon exactly 2 instances24// The time delta calculations below also rely upon every instance being currently detected and being parsed2526// exit immediately if not enough receivers to do blending27if (gps.state[0].status <= AP_GPS::NO_FIX || gps.state[1].status <= AP_GPS::NO_FIX) {28return false;29}3031// Use the oldest non-zero time, but if time difference is excessive, use newest to prevent a disconnected receiver from blocking updates32uint32_t max_ms = 0; // newest non-zero system time of arrival of a GPS message33uint32_t min_ms = -1; // oldest non-zero system time of arrival of a GPS message34uint32_t max_rate_ms = 0; // largest update interval of a GPS receiver35for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {36// Find largest and smallest times37if (gps.state[i].last_gps_time_ms > max_ms) {38max_ms = gps.state[i].last_gps_time_ms;39}40if ((gps.state[i].last_gps_time_ms < min_ms) && (gps.state[i].last_gps_time_ms > 0)) {41min_ms = gps.state[i].last_gps_time_ms;42}43max_rate_ms = MAX(gps.get_rate_ms(i), max_rate_ms);44if (isinf(gps.state[i].speed_accuracy) ||45isinf(gps.state[i].horizontal_accuracy) ||46isinf(gps.state[i].vertical_accuracy)) {47return false;48}49}50if ((max_ms - min_ms) < (2 * max_rate_ms)) {51// data is not too delayed so use the oldest time_stamp to give a chance for data from that receiver to be updated52state.last_gps_time_ms = min_ms;53} else {54// receiver data has timed out so fail out of blending55return false;56}5758// calculate the sum squared speed accuracy across all GPS sensors59float speed_accuracy_sum_sq = 0.0f;60if (gps._blend_mask & BLEND_MASK_USE_SPD_ACC) {61for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {62if (gps.state[i].status >= AP_GPS::GPS_OK_FIX_3D) {63if (gps.state[i].have_speed_accuracy && gps.state[i].speed_accuracy > 0.0f) {64speed_accuracy_sum_sq += sq(gps.state[i].speed_accuracy);65} else {66// not all receivers support this metric so set it to zero and don't use it67speed_accuracy_sum_sq = 0.0f;68break;69}70}71}72}7374// calculate the sum squared horizontal position accuracy across all GPS sensors75float horizontal_accuracy_sum_sq = 0.0f;76if (gps._blend_mask & BLEND_MASK_USE_HPOS_ACC) {77for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {78if (gps.state[i].status >= AP_GPS::GPS_OK_FIX_2D) {79if (gps.state[i].have_horizontal_accuracy && gps.state[i].horizontal_accuracy > 0.0f) {80horizontal_accuracy_sum_sq += sq(gps.state[i].horizontal_accuracy);81} else {82// not all receivers support this metric so set it to zero and don't use it83horizontal_accuracy_sum_sq = 0.0f;84break;85}86}87}88}8990// calculate the sum squared vertical position accuracy across all GPS sensors91float vertical_accuracy_sum_sq = 0.0f;92if (gps._blend_mask & BLEND_MASK_USE_VPOS_ACC) {93for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {94if (gps.state[i].status >= AP_GPS::GPS_OK_FIX_3D) {95if (gps.state[i].have_vertical_accuracy && gps.state[i].vertical_accuracy > 0.0f) {96vertical_accuracy_sum_sq += sq(gps.state[i].vertical_accuracy);97} else {98// not all receivers support this metric so set it to zero and don't use it99vertical_accuracy_sum_sq = 0.0f;100break;101}102}103}104}105// Check if we can do blending using reported accuracy106bool can_do_blending = (horizontal_accuracy_sum_sq > 0.0f || vertical_accuracy_sum_sq > 0.0f || speed_accuracy_sum_sq > 0.0f);107108// if we can't do blending using reported accuracy, return false and hard switch logic will be used instead109if (!can_do_blending) {110return false;111}112113float sum_of_all_weights = 0.0f;114115// calculate a weighting using the reported horizontal position116float hpos_blend_weights[GPS_MAX_RECEIVERS] = {};117if (horizontal_accuracy_sum_sq > 0.0f) {118// calculate the weights using the inverse of the variances119float sum_of_hpos_weights = 0.0f;120for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {121if (gps.state[i].status >= AP_GPS::GPS_OK_FIX_2D && gps.state[i].horizontal_accuracy >= 0.001f) {122hpos_blend_weights[i] = horizontal_accuracy_sum_sq / sq(gps.state[i].horizontal_accuracy);123sum_of_hpos_weights += hpos_blend_weights[i];124}125}126// normalise the weights127if (sum_of_hpos_weights > 0.0f) {128for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {129hpos_blend_weights[i] = hpos_blend_weights[i] / sum_of_hpos_weights;130}131sum_of_all_weights += 1.0f;132}133}134135// calculate a weighting using the reported vertical position accuracy136float vpos_blend_weights[GPS_MAX_RECEIVERS] = {};137if (vertical_accuracy_sum_sq > 0.0f) {138// calculate the weights using the inverse of the variances139float sum_of_vpos_weights = 0.0f;140for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {141if (gps.state[i].status >= AP_GPS::GPS_OK_FIX_3D && gps.state[i].vertical_accuracy >= 0.001f) {142vpos_blend_weights[i] = vertical_accuracy_sum_sq / sq(gps.state[i].vertical_accuracy);143sum_of_vpos_weights += vpos_blend_weights[i];144}145}146// normalise the weights147if (sum_of_vpos_weights > 0.0f) {148for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {149vpos_blend_weights[i] = vpos_blend_weights[i] / sum_of_vpos_weights;150}151sum_of_all_weights += 1.0f;152};153}154155// calculate a weighting using the reported speed accuracy156float spd_blend_weights[GPS_MAX_RECEIVERS] = {};157if (speed_accuracy_sum_sq > 0.0f) {158// calculate the weights using the inverse of the variances159float sum_of_spd_weights = 0.0f;160for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {161if (gps.state[i].status >= AP_GPS::GPS_OK_FIX_3D && gps.state[i].speed_accuracy >= 0.001f) {162spd_blend_weights[i] = speed_accuracy_sum_sq / sq(gps.state[i].speed_accuracy);163sum_of_spd_weights += spd_blend_weights[i];164}165}166// normalise the weights167if (sum_of_spd_weights > 0.0f) {168for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {169spd_blend_weights[i] = spd_blend_weights[i] / sum_of_spd_weights;170}171sum_of_all_weights += 1.0f;172}173}174175if (!is_positive(sum_of_all_weights)) {176return false;177}178179// calculate an overall weight180for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {181_blend_weights[i] = (hpos_blend_weights[i] + vpos_blend_weights[i] + spd_blend_weights[i]) / sum_of_all_weights;182}183184return true;185}186187bool AP_GPS_Blended::calc_weights()188{189// adjust blend health counter190if (!_calc_weights()) {191_blend_health_counter = MIN(_blend_health_counter+BLEND_COUNTER_FAILURE_INCREMENT, 100);192} else if (_blend_health_counter > 0) {193_blend_health_counter--;194}195// stop blending if unhealthy196return _blend_health_counter < 50;197}198199/*200calculate a blended GPS state201*/202void AP_GPS_Blended::calc_state(void)203{204// initialise the blended states so we can accumulate the results using the weightings for each GPS receiver205state.instance = GPS_BLENDED_INSTANCE;206state.status = AP_GPS::NO_FIX;207state.time_week_ms = 0;208state.time_week = 0;209state.ground_speed = 0.0f;210state.ground_course = 0.0f;211state.hdop = GPS_UNKNOWN_DOP;212state.vdop = GPS_UNKNOWN_DOP;213state.num_sats = 0;214state.velocity.zero();215state.speed_accuracy = 1e6f;216state.horizontal_accuracy = 1e6f;217state.vertical_accuracy = 1e6f;218state.have_vertical_velocity = false;219state.have_speed_accuracy = false;220state.have_horizontal_accuracy = false;221state.have_vertical_accuracy = false;222state.location = {};223224_blended_antenna_offset.zero();225_blended_lag_sec = 0;226227#if HAL_LOGGING_ENABLED228const uint32_t last_blended_message_time_ms = timing.last_message_time_ms;229#endif230timing.last_fix_time_ms = 0;231timing.last_message_time_ms = 0;232233if (gps.state[0].have_undulation) {234state.have_undulation = true;235state.undulation = gps.state[0].undulation;236} else if (gps.state[1].have_undulation) {237state.have_undulation = true;238state.undulation = gps.state[1].undulation;239} else {240state.have_undulation = false;241}242243// combine the states into a blended solution244for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {245// use the highest status246if (gps.state[i].status > state.status) {247state.status = gps.state[i].status;248}249250// calculate a blended average velocity251state.velocity += gps.state[i].velocity * _blend_weights[i];252253// report the best valid accuracies and DOP metrics254255if (gps.state[i].have_horizontal_accuracy && gps.state[i].horizontal_accuracy > 0.0f && gps.state[i].horizontal_accuracy < state.horizontal_accuracy) {256state.have_horizontal_accuracy = true;257state.horizontal_accuracy = gps.state[i].horizontal_accuracy;258}259260if (gps.state[i].have_vertical_accuracy && gps.state[i].vertical_accuracy > 0.0f && gps.state[i].vertical_accuracy < state.vertical_accuracy) {261state.have_vertical_accuracy = true;262state.vertical_accuracy = gps.state[i].vertical_accuracy;263}264265if (gps.state[i].have_vertical_velocity) {266state.have_vertical_velocity = true;267}268269if (gps.state[i].have_speed_accuracy && gps.state[i].speed_accuracy > 0.0f && gps.state[i].speed_accuracy < state.speed_accuracy) {270state.have_speed_accuracy = true;271state.speed_accuracy = gps.state[i].speed_accuracy;272}273274if (gps.state[i].hdop > 0 && gps.state[i].hdop < state.hdop) {275state.hdop = gps.state[i].hdop;276}277278if (gps.state[i].vdop > 0 && gps.state[i].vdop < state.vdop) {279state.vdop = gps.state[i].vdop;280}281282if (gps.state[i].num_sats > 0 && gps.state[i].num_sats > state.num_sats) {283state.num_sats = gps.state[i].num_sats;284}285286// report a blended average GPS antenna position287Vector3f temp_antenna_offset = gps.params[i].antenna_offset;288temp_antenna_offset *= _blend_weights[i];289_blended_antenna_offset += temp_antenna_offset;290291// blend the timing data292if (gps.timing[i].last_fix_time_ms > timing.last_fix_time_ms) {293timing.last_fix_time_ms = gps.timing[i].last_fix_time_ms;294}295if (gps.timing[i].last_message_time_ms > timing.last_message_time_ms) {296timing.last_message_time_ms = gps.timing[i].last_message_time_ms;297}298}299300/*301* Calculate an instantaneous weighted/blended average location from the available GPS instances and store in the _output_state.302* This will be statistically the most likely location, but will be not stable enough for direct use by the autopilot.303*/304305// Use the GPS with the highest weighting as the reference position306float best_weight = 0.0f;307uint8_t best_index = 0;308for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {309if (_blend_weights[i] > best_weight) {310best_weight = _blend_weights[i];311best_index = i;312state.location = gps.state[i].location;313}314}315316// Calculate the weighted sum of horizontal and vertical position offsets relative to the reference position317Vector2f blended_NE_offset_m;318float blended_alt_offset_cm = 0.0f;319blended_NE_offset_m.zero();320for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {321if (_blend_weights[i] > 0.0f && i != best_index) {322blended_NE_offset_m += state.location.get_distance_NE(gps.state[i].location) * _blend_weights[i];323blended_alt_offset_cm += (float)(gps.state[i].location.alt - state.location.alt) * _blend_weights[i];324}325}326327// Add the sum of weighted offsets to the reference location to obtain the blended location328state.location.offset(blended_NE_offset_m.x, blended_NE_offset_m.y);329state.location.alt += (int)blended_alt_offset_cm;330331// Calculate ground speed and course from blended velocity vector332state.ground_speed = state.velocity.xy().length();333state.ground_course = wrap_360(degrees(atan2f(state.velocity.y, state.velocity.x)));334335// If the GPS week is the same then use a blended time_week_ms336// If week is different, then use time stamp from GPS with largest weighting337// detect inconsistent week data338uint8_t last_week_instance = 0;339bool weeks_consistent = true;340for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {341if (last_week_instance == 0 && _blend_weights[i] > 0) {342// this is our first valid sensor week data343last_week_instance = gps.state[i].time_week;344} else if (last_week_instance != 0 && _blend_weights[i] > 0 && last_week_instance != gps.state[i].time_week) {345// there is valid sensor week data that is inconsistent346weeks_consistent = false;347}348}349// calculate output350if (!weeks_consistent) {351// use data from highest weighted sensor352state.time_week = gps.state[best_index].time_week;353state.time_week_ms = gps.state[best_index].time_week_ms;354} else {355// use week number from highest weighting GPS (they should all have the same week number)356state.time_week = gps.state[best_index].time_week;357// calculate a blended value for the number of ms lapsed in the week358double temp_time_0 = 0.0;359for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {360if (_blend_weights[i] > 0.0f) {361temp_time_0 += (double)gps.state[i].time_week_ms * (double)_blend_weights[i];362}363}364state.time_week_ms = (uint32_t)temp_time_0;365}366367// calculate a blended value for the timing data and lag368double temp_time_1 = 0.0;369double temp_time_2 = 0.0;370for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {371if (_blend_weights[i] > 0.0f) {372temp_time_1 += (double)gps.timing[i].last_fix_time_ms * (double) _blend_weights[i];373temp_time_2 += (double)gps.timing[i].last_message_time_ms * (double)_blend_weights[i];374float gps_lag_sec = 0;375gps.get_lag(i, gps_lag_sec);376_blended_lag_sec += gps_lag_sec * _blend_weights[i];377}378}379timing.last_fix_time_ms = (uint32_t)temp_time_1;380timing.last_message_time_ms = (uint32_t)temp_time_2;381382#if HAL_LOGGING_ENABLED383if (timing.last_message_time_ms > last_blended_message_time_ms &&384should_log()) {385gps.Write_GPS(GPS_BLENDED_INSTANCE);386}387#endif388}389390bool AP_GPS_Blended::get_lag(float &lag_sec) const391{392lag_sec = _blended_lag_sec;393// auto switching uses all GPS receivers, so all must be configured394uint8_t inst; // we don't actually care what the number is, but must pass it395return gps.first_unconfigured_gps(inst);396}397398#endif // AP_GPS_BLENDED_ENABLED399400401