Browse Source

AP_GPS: Use GPS_AUTO_SWITCH parameter to choose exacly which GPS to use

master
Dr.-Ing. Amilcar do Carmo Lucas 7 years ago committed by WickedShell
parent
commit
9c97f35b19
  1. 7
      libraries/AP_GPS/AP_GPS.cpp

7
libraries/AP_GPS/AP_GPS.cpp

@ -90,7 +90,7 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = {
// @Param: AUTO_SWITCH // @Param: AUTO_SWITCH
// @DisplayName: Automatic Switchover Setting // @DisplayName: Automatic Switchover Setting
// @Description: Automatic switchover to GPS reporting best lock // @Description: Automatic switchover to GPS reporting best lock
// @Values: 0:Disabled,1:UseBest,2:Blend // @Values: 0:Disabled,1:UseBest,2:Blend,3:UseSecond
// @User: Advanced // @User: Advanced
AP_GROUPINFO("AUTO_SWITCH", 3, AP_GPS, _auto_switch, 1), AP_GROUPINFO("AUTO_SWITCH", 3, AP_GPS, _auto_switch, 1),
@ -722,7 +722,10 @@ void AP_GPS::update(void)
} else { } else {
// use switch logic to find best GPS // use switch logic to find best GPS
uint32_t now = AP_HAL::millis(); uint32_t now = AP_HAL::millis();
if (_auto_switch >= 1) { if (_auto_switch == 3) {
// select the second GPS instance
primary_instance = 1;
} else if (_auto_switch >= 1) {
// handling switching away from blended GPS // handling switching away from blended GPS
if (primary_instance == GPS_BLENDED_INSTANCE) { if (primary_instance == GPS_BLENDED_INSTANCE) {
primary_instance = 0; primary_instance = 0;

Loading…
Cancel
Save