mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_GPS: fixed pre-arm check on ublox M9 GPS
this prevents a failure from config of SOL and TMODE messages
This commit is contained in:
parent
93eb226cdc
commit
8d284938db
@ -1176,15 +1176,24 @@ AP_GPS_UBLOX::_parse_gps(void)
|
|||||||
state.instance + 1,
|
state.instance + 1,
|
||||||
_version.hwVersion,
|
_version.hwVersion,
|
||||||
_version.swVersion);
|
_version.swVersion);
|
||||||
// check for F9. The F9 does not respond to SVINFO, so we need to use MON_VER
|
// check for F9 and M9. The F9 does not respond to SVINFO,
|
||||||
// for hardware generation
|
// so we need to use MON_VER for hardware generation
|
||||||
if (strncmp(_version.hwVersion, "00190000", 8) == 0) {
|
if (strncmp(_version.hwVersion, "00190000", 8) == 0) {
|
||||||
if (_hardware_generation != UBLOX_F9) {
|
if (strncmp(_version.swVersion, "EXT CORE 1", 10) == 0) {
|
||||||
// need to ensure time mode is correctly setup on F9
|
// a F9
|
||||||
_unconfigured_messages |= CONFIG_TMODE_MODE;
|
if (_hardware_generation != UBLOX_F9) {
|
||||||
|
// need to ensure time mode is correctly setup on F9
|
||||||
|
_unconfigured_messages |= CONFIG_TMODE_MODE;
|
||||||
|
}
|
||||||
|
_hardware_generation = UBLOX_F9;
|
||||||
|
}
|
||||||
|
if (strncmp(_version.swVersion, "EXT CORE 4", 10) == 0) {
|
||||||
|
// a M9
|
||||||
|
_hardware_generation = UBLOX_M9;
|
||||||
}
|
}
|
||||||
_hardware_generation = UBLOX_F9;
|
|
||||||
}
|
}
|
||||||
|
// none of the 9 series support the SOL message
|
||||||
|
_unconfigured_messages &= ~CONFIG_RATE_SOL;
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
unexpected_message();
|
unexpected_message();
|
||||||
@ -1874,6 +1883,7 @@ bool AP_GPS_UBLOX::get_lag(float &lag_sec) const
|
|||||||
lag_sec = 0.12f;
|
lag_sec = 0.12f;
|
||||||
break;
|
break;
|
||||||
case UBLOX_F9:
|
case UBLOX_F9:
|
||||||
|
case UBLOX_M9:
|
||||||
// F9 lag not verified yet from flight log, but likely to be at least
|
// F9 lag not verified yet from flight log, but likely to be at least
|
||||||
// as good as M8
|
// as good as M8
|
||||||
lag_sec = 0.12f;
|
lag_sec = 0.12f;
|
||||||
@ -1960,5 +1970,5 @@ bool AP_GPS_UBLOX::is_healthy(void) const
|
|||||||
// return true if GPS is capable of F9 config
|
// return true if GPS is capable of F9 config
|
||||||
bool AP_GPS_UBLOX::supports_F9_config(void) const
|
bool AP_GPS_UBLOX::supports_F9_config(void) const
|
||||||
{
|
{
|
||||||
return _hardware_generation >= UBLOX_F9 && _hardware_generation != UBLOX_UNKNOWN_HARDWARE_GENERATION;
|
return _hardware_generation == UBLOX_F9 && _hardware_generation != UBLOX_UNKNOWN_HARDWARE_GENERATION;
|
||||||
}
|
}
|
||||||
|
@ -626,7 +626,8 @@ private:
|
|||||||
UBLOX_6,
|
UBLOX_6,
|
||||||
UBLOX_7,
|
UBLOX_7,
|
||||||
UBLOX_M8,
|
UBLOX_M8,
|
||||||
UBLOX_F9 = 0x80, // comes from MON_VER hwVersion string
|
UBLOX_F9 = 0x80, // comes from MON_VER hwVersion/swVersion strings
|
||||||
|
UBLOX_M9 = 0x81, // comes from MON_VER hwVersion/swVersion strings
|
||||||
UBLOX_UNKNOWN_HARDWARE_GENERATION = 0xff // not in the ublox spec used for
|
UBLOX_UNKNOWN_HARDWARE_GENERATION = 0xff // not in the ublox spec used for
|
||||||
// flagging state in the driver
|
// flagging state in the driver
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user