From 8e7d587d5a0be270f2de1371abd7e70e7a0b2b57 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 19 Sep 2023 16:18:00 +1000 Subject: [PATCH] AP_GPS: prevent use of blended GPS with moving baseline when moving baseline is enabled the rover is slaved to the base for position and velocity, adding no additional useful data. Only the yaw comes from the rover --- libraries/AP_GPS/AP_GPS.cpp | 14 ++++++++++++-- 1 file changed, 12 insertions(+), 2 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index 93bbc1007efaf..20c8f33886e66 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -1149,8 +1149,18 @@ void AP_GPS::update(void) void AP_GPS::update_primary(void) { #if defined(GPS_BLENDED_INSTANCE) - // if blending is requested, attempt to calculate weighting for each GPS - if ((GPSAutoSwitch)_auto_switch.get() == GPSAutoSwitch::BLEND) { + /* + if blending is requested, attempt to calculate weighting for + each GPS + we do not do blending if using moving baseline yaw as the rover is + significant lagged and gives no more information on position or + velocity + */ + const bool using_moving_base = (_type[0] == GPS_TYPE_UAVCAN_RTK_BASE || + _type[0] == GPS_TYPE_UBLOX_RTK_BASE || + _type[1] == GPS_TYPE_UAVCAN_RTK_BASE || + _type[1] == GPS_TYPE_UBLOX_RTK_BASE); + if ((GPSAutoSwitch)_auto_switch.get() == GPSAutoSwitch::BLEND && !using_moving_base) { _output_is_blended = calc_blend_weights(); // adjust blend health counter if (!_output_is_blended) {