Skip to content

Commit

Permalink
AP_GPS: prevent use of blended GPS with moving baseline
Browse files Browse the repository at this point in the history
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
  • Loading branch information
tridge committed Sep 19, 2023
1 parent 33c3b28 commit 8e7d587
Showing 1 changed file with 12 additions and 2 deletions.
14 changes: 12 additions & 2 deletions libraries/AP_GPS/AP_GPS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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) {
Expand Down

0 comments on commit 8e7d587

Please sign in to comment.