AP_GPS: don't try and configure M10 options on non-M10 GPS

this fixes a pre-arm failure "GPS 1 failing configuration checks" on
non-M10 GPS modules, including AP_Periph

it also adds the ublox unconfigured msgs to the DroneCAN GNSS.Status
errors field for easier diagnosis of this type of issue in the future
This commit is contained in:
Andrew Tridgell 2023-02-18 09:17:43 +11:00 committed by Randy Mackay
parent aa6c2fe864
commit 6978df3348
2 changed files with 13 additions and 6 deletions

View File

@ -425,6 +425,7 @@ AP_GPS_UBLOX::_request_next_config(void)
case STEP_M10: {
if (_hardware_generation == UBLOX_M10) {
// special handling of M10 config
const config_list *list = config_M10;
const uint8_t list_length = ARRAY_SIZE(config_M10);
@ -432,6 +433,7 @@ AP_GPS_UBLOX::_request_next_config(void)
if (!_configure_config_set(list, list_length, CONFIG_M10, UBX_VALSET_LAYER_RAM | UBX_VALSET_LAYER_BBR)) {
_next_message--;
}
}
break;
}

View File

@ -143,6 +143,11 @@ public:
#endif // CONFIG_HAL_BOARD != HAL_BOARD_SITL
}
bool get_error_codes(uint32_t &error_codes) const override {
error_codes = _unconfigured_messages;
return true;
};
void broadcast_configuration_failure_reason(void) const override;
void Write_AP_Logger_Log_Startup_messages() const override;