mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_GPS: change GPS_AUTO_SWITCH #define list to enum class
enumeration entry had to change to NONE to avoid name conflict with DISABLED
This commit is contained in:
parent
ff007dd017
commit
8f6e9caf93
@ -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;
|
||||
|
@ -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;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user