mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
AP_GPS: add primary param
This commit is contained in:
parent
0c2037438b
commit
347723dbaf
@ -101,8 +101,8 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = {
|
|||||||
#if GPS_MAX_RECEIVERS > 1
|
#if GPS_MAX_RECEIVERS > 1
|
||||||
// @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, 1:UseBest selects the GPS with highest status, if both are equal the GPS with highest satellite count is used
|
||||||
// @Values: 0:Disabled,1:UseBest,2:Blend,3:UseSecond
|
// @Values: 0:Use primary, 1:UseBest, 2:Blend
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("AUTO_SWITCH", 3, AP_GPS, _auto_switch, (int8_t)GPSAutoSwitch::USE_BEST),
|
AP_GROUPINFO("AUTO_SWITCH", 3, AP_GPS, _auto_switch, (int8_t)GPSAutoSwitch::USE_BEST),
|
||||||
#endif
|
#endif
|
||||||
@ -336,6 +336,16 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = {
|
|||||||
|
|
||||||
#endif // GPS_MOVING_BASELINE
|
#endif // GPS_MOVING_BASELINE
|
||||||
|
|
||||||
|
#if GPS_MAX_RECEIVERS > 1
|
||||||
|
// @Param: PRIMARY
|
||||||
|
// @DisplayName: Primary GPS
|
||||||
|
// @Description: This GPS will be used when GPS_AUTO_SWITCH is 0 and used preferentially with GPS_AUTO_SWITCH = 4.
|
||||||
|
// @Increment: 1
|
||||||
|
// @Values: 0:FirstGPS, 1:SecondGPS
|
||||||
|
// @User: Advanced
|
||||||
|
AP_GROUPINFO("PRIMARY", 27, AP_GPS, _primary, 0),
|
||||||
|
#endif
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
@ -372,7 +382,11 @@ bool AP_GPS::needs_uart(GPS_Type type) const
|
|||||||
/// Startup initialisation.
|
/// Startup initialisation.
|
||||||
void AP_GPS::init(const AP_SerialManager& serial_manager)
|
void AP_GPS::init(const AP_SerialManager& serial_manager)
|
||||||
{
|
{
|
||||||
primary_instance = 0;
|
// Set new primary param based on old auto_switch use second option
|
||||||
|
if ((_auto_switch.get() == 3) && !_primary.configured()) {
|
||||||
|
_primary.set_and_save(1);
|
||||||
|
_auto_switch.set_and_save(0);
|
||||||
|
}
|
||||||
|
|
||||||
// search for serial ports with gps protocol
|
// search for serial ports with gps protocol
|
||||||
uint8_t uart_idx = 0;
|
uint8_t uart_idx = 0;
|
||||||
@ -903,15 +917,19 @@ void AP_GPS::update_primary(void)
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
if ((GPSAutoSwitch)_auto_switch.get() == GPSAutoSwitch::NONE) {
|
// check the primary param is set to possible GPS
|
||||||
// AUTO_SWITCH is 0 so no switching of GPSs, always use first instance
|
int8_t primary_param = _primary.get();
|
||||||
primary_instance = 0;
|
if ((primary_param < 0) || (primary_param>=GPS_MAX_RECEIVERS)) {
|
||||||
return;
|
primary_param = 0;
|
||||||
|
}
|
||||||
|
// if primary is not enabled try first instance
|
||||||
|
if (get_type(primary_param) == GPS_TYPE_NONE) {
|
||||||
|
primary_param = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
if ((GPSAutoSwitch)_auto_switch.get() == GPSAutoSwitch::USE_SECOND) {
|
if ((GPSAutoSwitch)_auto_switch.get() == GPSAutoSwitch::NONE) {
|
||||||
// always select the second GPS instance
|
// No switching of GPSs, always use the primary instance
|
||||||
primary_instance = 1;
|
primary_instance = primary_param;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -1782,6 +1800,10 @@ bool AP_GPS::is_healthy(uint8_t instance) const
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (get_type(_primary.get()) == GPS_TYPE_NONE) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
allow two lost frames before declaring the GPS unhealthy, but
|
allow two lost frames before declaring the GPS unhealthy, but
|
||||||
require the average frame rate to be close to 5Hz. We allow for
|
require the average frame rate to be close to 5Hz. We allow for
|
||||||
|
@ -659,7 +659,7 @@ private:
|
|||||||
NONE = 0,
|
NONE = 0,
|
||||||
USE_BEST = 1,
|
USE_BEST = 1,
|
||||||
BLEND = 2,
|
BLEND = 2,
|
||||||
USE_SECOND = 3,
|
//USE_SECOND = 3, deprecated for new primary param
|
||||||
};
|
};
|
||||||
|
|
||||||
// used for flight testing with GPS loss
|
// used for flight testing with GPS loss
|
||||||
|
Loading…
Reference in New Issue
Block a user