From 8f6e9caf93b3bd93677085d70c12478ca434e927 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Tue, 23 Jun 2020 19:07:35 -0700 Subject: [PATCH] AP_GPS: change GPS_AUTO_SWITCH #define list to enum class enumeration entry had to change to NONE to avoid name conflict with DISABLED --- libraries/AP_GPS/AP_GPS.cpp | 10 +++++----- libraries/AP_GPS/AP_GPS.h | 7 +++++++ 2 files changed, 12 insertions(+), 5 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index 1671ebe9ff..1b4c67a64a 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -101,7 +101,7 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = { // @Description: Automatic switchover to GPS reporting best lock // @Values: 0:Disabled,1:UseBest,2:Blend,3:UseSecond // @User: Advanced - AP_GROUPINFO("AUTO_SWITCH", 3, AP_GPS, _auto_switch, 1), + AP_GROUPINFO("AUTO_SWITCH", 3, AP_GPS, _auto_switch, (int8_t)GPSAutoSwitch::USE_BEST), #endif // @Param: MIN_DGPS @@ -276,7 +276,7 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = { #if defined(GPS_BLENDED_INSTANCE) // @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 + // @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) // @Bitmask: 0:Horiz Pos,1:Vert Pos,2:Speed // @User: Advanced AP_GROUPINFO("BLEND_MASK", 20, AP_GPS, _blend_mask, 5), @@ -837,7 +837,7 @@ void AP_GPS::update_primary(void) { #if defined(GPS_BLENDED_INSTANCE) // if blending is requested, attempt to calculate weighting for each GPS - if (_auto_switch == 2) { + if ((GPSAutoSwitch)_auto_switch.get() == GPSAutoSwitch::BLEND) { _output_is_blended = calc_blend_weights(); // adjust blend health counter if (!_output_is_blended) { @@ -862,13 +862,13 @@ void AP_GPS::update_primary(void) return; } - if (_auto_switch == 0) { + if ((GPSAutoSwitch)_auto_switch.get() == GPSAutoSwitch::NONE) { // AUTO_SWITCH is 0 so no switching of GPSs, always use first instance primary_instance = 0; return; } - if (_auto_switch == 3) { + if ((GPSAutoSwitch)_auto_switch.get() == GPSAutoSwitch::USE_SECOND) { // always select the second GPS instance primary_instance = 1; return; diff --git a/libraries/AP_GPS/AP_GPS.h b/libraries/AP_GPS/AP_GPS.h index 49e016122e..2ba4125ae7 100644 --- a/libraries/AP_GPS/AP_GPS.h +++ b/libraries/AP_GPS/AP_GPS.h @@ -632,6 +632,13 @@ private: GPS_AUTO_CONFIG_ENABLE = 1 }; + enum class GPSAutoSwitch { + NONE = 0, + USE_BEST = 1, + BLEND = 2, + USE_SECOND = 3, + }; + // used for flight testing with GPS loss bool _force_disable_gps;