Skip to content

Commit

Permalink
AP_GPS: remove blended GPS from small boards
Browse files Browse the repository at this point in the history
those boards which are not including all backends will lose blended after this
  • Loading branch information
peterbarker committed Mar 21, 2024
1 parent 2a47ac1 commit 5373236
Show file tree
Hide file tree
Showing 5 changed files with 43 additions and 36 deletions.
4 changes: 2 additions & 2 deletions libraries/AP_Arming/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -576,7 +576,7 @@ bool AP_Arming::gps_checks(bool report)
}

for (uint8_t i = 0; i < gps.num_sensors(); i++) {
#if defined(GPS_BLENDED_INSTANCE)
#if AP_GPS_BLENDED_ENABLED
if ((i != GPS_BLENDED_INSTANCE) &&
#else
if (
Expand Down Expand Up @@ -614,7 +614,7 @@ bool AP_Arming::gps_checks(bool report)
(double)distance_m);
return false;
}
#if defined(GPS_BLENDED_INSTANCE)
#if AP_GPS_BLENDED_ENABLED
if (!gps.blend_health_check()) {
check_failed(ARMING_CHECK_GPS, report, "GPS blending unhealthy");
return false;
Expand Down
18 changes: 9 additions & 9 deletions libraries/AP_GPS/AP_GPS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -214,7 +214,7 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = {

// 19 was GPS_DELAY_MS2

#if defined(GPS_BLENDED_INSTANCE)
#if AP_GPS_BLENDED_ENABLED
// @Param: _BLEND_MASK
// @DisplayName: Multi GPS Blending Mask
// @Description: Determines which of the accuracy measures Horizontal position, Vertical Position and Speed are used to calculate the weighting on each GPS receiver when soft switching has been selected by setting GPS_AUTO_SWITCH to 2(Blend)
Expand Down Expand Up @@ -400,7 +400,7 @@ void AP_GPS::convert_parameters()
// GPS solution is treated as an additional sensor.
uint8_t AP_GPS::num_sensors(void) const
{
#if defined(GPS_BLENDED_INSTANCE)
#if AP_GPS_BLENDED_ENABLED
if (_output_is_blended) {
return num_instances+1;
}
Expand Down Expand Up @@ -1072,7 +1072,7 @@ void AP_GPS::update(void)
#if GPS_MAX_RECEIVERS > 1
void AP_GPS::update_primary(void)
{
#if defined(GPS_BLENDED_INSTANCE)
#if AP_GPS_BLENDED_ENABLED
/*
if blending is requested, attempt to calculate weighting for
each GPS
Expand Down Expand Up @@ -1105,7 +1105,7 @@ void AP_GPS::update_primary(void)
primary_instance = GPS_BLENDED_INSTANCE;
return;
}
#endif // defined (GPS_BLENDED_INSTANCE)
#endif // AP_GPS_BLENDED_ENABLED

// check the primary param is set to possible GPS
int8_t primary_param = _primary.get();
Expand Down Expand Up @@ -1145,7 +1145,7 @@ void AP_GPS::update_primary(void)
}
}

#if defined(GPS_BLENDED_INSTANCE)
#if AP_GPS_BLENDED_ENABLED
// handling switching away from blended GPS
if (primary_instance == GPS_BLENDED_INSTANCE) {
primary_instance = 0;
Expand Down Expand Up @@ -1180,7 +1180,7 @@ void AP_GPS::update_primary(void)
_last_instance_swap_ms = now;
return;
}
#endif // defined(GPS_BLENDED_INSTANCE)
#endif // AP_GPS_BLENDED_ENABLED

// Use primary if 3D fix or better
if (((GPSAutoSwitch)_auto_switch.get() == GPSAutoSwitch::USE_PRIMARY_IF_3D_FIX) && (state[primary_param].status >= GPS_OK_FIX_3D)) {
Expand Down Expand Up @@ -1690,7 +1690,7 @@ bool AP_GPS::get_lag(uint8_t instance, float &lag_sec) const
return false;
}

#if defined(GPS_BLENDED_INSTANCE)
#if AP_GPS_BLENDED_ENABLED
// return lag of blended GPS
if (instance == GPS_BLENDED_INSTANCE) {
lag_sec = _blended_lag_sec;
Expand Down Expand Up @@ -1727,7 +1727,7 @@ const Vector3f &AP_GPS::get_antenna_offset(uint8_t instance) const
return params[0].antenna_offset;
}

#if defined(GPS_BLENDED_INSTANCE)
#if AP_GPS_BLENDED_ENABLED
if (instance == GPS_BLENDED_INSTANCE) {
// return an offset for the blended GPS solution
return _blended_antenna_offset;
Expand Down Expand Up @@ -1786,7 +1786,7 @@ bool AP_GPS::is_healthy(uint8_t instance) const
}
#endif // HAL_BUILD_AP_PERIPH

#if defined(GPS_BLENDED_INSTANCE)
#if AP_GPS_BLENDED_ENABLED
if (instance == GPS_BLENDED_INSTANCE) {
return blend_health_check();
}
Expand Down
24 changes: 1 addition & 23 deletions libraries/AP_GPS/AP_GPS.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,28 +30,6 @@
#include <SITL/SIM_GPS.h>
#include <GCS_MAVLink/GCS_MAVLink.h>

/**
maximum number of GPS instances available on this platform. If more
than 1 then redundant sensors may be available
*/
#ifndef GPS_MAX_RECEIVERS
#define GPS_MAX_RECEIVERS 2 // maximum number of physical GPS sensors allowed - does not include virtual GPS created by blending receiver data
#endif
#if !defined(GPS_MAX_INSTANCES)
#if GPS_MAX_RECEIVERS > 1
#define GPS_MAX_INSTANCES (GPS_MAX_RECEIVERS + 1) // maximum number of GPS instances including the 'virtual' GPS created by blending receiver data
#else
#define GPS_MAX_INSTANCES 1
#endif // GPS_MAX_RECEIVERS > 1
#endif // GPS_MAX_INSTANCES

#if GPS_MAX_RECEIVERS <= 1 && GPS_MAX_INSTANCES > 1
#error "GPS_MAX_INSTANCES should be 1 for GPS_MAX_RECEIVERS <= 1"
#endif

#if GPS_MAX_INSTANCES > GPS_MAX_RECEIVERS
#define GPS_BLENDED_INSTANCE GPS_MAX_RECEIVERS // the virtual blended GPS is always the highest instance (2)
#endif
#define GPS_UNKNOWN_DOP UINT16_MAX // set unknown DOP's to maximum value, which is also correct for MAVLink

// the number of GPS leap seconds - copied into SIM_GPS.cpp
Expand Down Expand Up @@ -761,7 +739,7 @@ class AP_GPS
void inject_data(const uint8_t *data, uint16_t len);
void inject_data(uint8_t instance, const uint8_t *data, uint16_t len);

#if defined(GPS_BLENDED_INSTANCE)
#if AP_GPS_BLENDED_ENABLED
// GPS blending and switching
Vector3f _blended_antenna_offset; // blended antenna offset
float _blended_lag_sec; // blended receiver lag in seconds
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_GPS/AP_GPS_Blended.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#include "AP_GPS.h"

#if defined(GPS_BLENDED_INSTANCE)
#if AP_GPS_BLENDED_ENABLED

// defines used to specify the mask position for use of different accuracy metrics in the blending algorithm
#define BLEND_MASK_USE_HPOS_ACC 1
Expand Down Expand Up @@ -377,4 +377,4 @@ void AP_GPS::calc_blended_state(void)
}
#endif
}
#endif // GPS_BLENDED_INSTANCE
#endif // AP_GPS_BLENDED_ENABLED
29 changes: 29 additions & 0 deletions libraries/AP_GPS/AP_GPS_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -7,10 +7,39 @@
#define AP_GPS_ENABLED 1
#endif

#if AP_GPS_ENABLED
/**
maximum number of GPS instances available on this platform. If more
than 1 then redundant sensors may be available
*/
#ifndef GPS_MAX_RECEIVERS
#define GPS_MAX_RECEIVERS 2 // maximum number of physical GPS sensors allowed - does not include virtual GPS created by blending receiver data
#endif
#if !defined(GPS_MAX_INSTANCES)
#if GPS_MAX_RECEIVERS > 1
#define GPS_MAX_INSTANCES (GPS_MAX_RECEIVERS + 1) // maximum number of GPS instances including the 'virtual' GPS created by blending receiver data
#else
#define GPS_MAX_INSTANCES 1
#endif // GPS_MAX_RECEIVERS > 1
#endif // GPS_MAX_INSTANCES

#if GPS_MAX_RECEIVERS <= 1 && GPS_MAX_INSTANCES > 1
#error "GPS_MAX_INSTANCES should be 1 for GPS_MAX_RECEIVERS <= 1"
#endif

#if GPS_MAX_INSTANCES > GPS_MAX_RECEIVERS
#define GPS_BLENDED_INSTANCE GPS_MAX_RECEIVERS // the virtual blended GPS is always the highest instance (2)
#endif
#endif

#ifndef AP_GPS_BACKEND_DEFAULT_ENABLED
#define AP_GPS_BACKEND_DEFAULT_ENABLED AP_GPS_ENABLED
#endif

#ifndef AP_GPS_BLENDED_ENABLED
#define AP_GPS_BLENDED_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED && defined(GPS_BLENDED_INSTANCE)
#endif

#ifndef AP_GPS_DRONECAN_ENABLED
#define AP_GPS_DRONECAN_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED && HAL_ENABLE_DRONECAN_DRIVERS
#endif
Expand Down

0 comments on commit 5373236

Please sign in to comment.