mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
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:
parent
044c929488
commit
5afe4954e9
@ -425,12 +425,14 @@ AP_GPS_UBLOX::_request_next_config(void)
|
|||||||
|
|
||||||
|
|
||||||
case STEP_M10: {
|
case STEP_M10: {
|
||||||
// special handling of M10 config
|
if (_hardware_generation == UBLOX_M10) {
|
||||||
const config_list *list = config_M10;
|
// special handling of M10 config
|
||||||
const uint8_t list_length = ARRAY_SIZE(config_M10);
|
const config_list *list = config_M10;
|
||||||
Debug("Sending M10 settings");
|
const uint8_t list_length = ARRAY_SIZE(config_M10);
|
||||||
if (!_configure_config_set(list, list_length, CONFIG_M10, UBX_VALSET_LAYER_RAM | UBX_VALSET_LAYER_BBR)) {
|
Debug("Sending M10 settings");
|
||||||
_next_message--;
|
if (!_configure_config_set(list, list_length, CONFIG_M10, UBX_VALSET_LAYER_RAM | UBX_VALSET_LAYER_BBR)) {
|
||||||
|
_next_message--;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
@ -143,6 +143,11 @@ public:
|
|||||||
#endif // CONFIG_HAL_BOARD != HAL_BOARD_SITL
|
#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 broadcast_configuration_failure_reason(void) const override;
|
||||||
void Write_AP_Logger_Log_Startup_messages() const override;
|
void Write_AP_Logger_Log_Startup_messages() const override;
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user