mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-28 10:43:58 -04:00
AP_GPS: correct uBlox config debugging
This commit is contained in:
parent
76aed8f89c
commit
922f86a7ed
@ -457,7 +457,7 @@ AP_GPS_UBLOX::_request_next_config(void)
|
||||
uint8_t cfg_count = populate_F9_gnss();
|
||||
// special handling of F9 config
|
||||
if (cfg_count > 0) {
|
||||
CFG_Debug("Sending F9 settings, GNSS=%u", params.gnss_mode);
|
||||
CFG_Debug("Sending F9 settings, GNSS=%u", unsigned(params.gnss_mode));
|
||||
|
||||
if (!_configure_list_valset(config_GNSS, cfg_count, UBX_VALSET_LAYER_RAM | UBX_VALSET_LAYER_BBR)) {
|
||||
_next_message--;
|
||||
@ -480,7 +480,7 @@ AP_GPS_UBLOX::_request_next_config(void)
|
||||
uint8_t cfg_count = populate_F9_gnss();
|
||||
// special handling of F9 config
|
||||
if (cfg_count > 0) {
|
||||
CFG_Debug("Validating F9 settings, GNSS=%u", params.gnss_mode);
|
||||
CFG_Debug("Validating F9 settings, GNSS=%u", unsigned(params.gnss_mode));
|
||||
// now validate all of the settings, this is a no-op if the first call succeeded
|
||||
if (!_configure_config_set(config_GNSS, cfg_count, CONFIG_F9, UBX_VALSET_LAYER_RAM | UBX_VALSET_LAYER_BBR)) {
|
||||
_next_message--;
|
||||
@ -1334,7 +1334,7 @@ AP_GPS_UBLOX::_parse_gps(void)
|
||||
// see if it is in active config list
|
||||
int8_t cfg_idx = find_active_config_index(id);
|
||||
if (cfg_idx >= 0) {
|
||||
CFG_Debug("valset(0x%lx): %u", uint32_t(id), (*cfg_data) & 0x1);
|
||||
CFG_Debug("valset(0x%lx): %u", (long unsigned)id, unsigned((*cfg_data) & 0x1));
|
||||
const uint8_t key_size = config_key_size(id);
|
||||
if (cfg_len < key_size
|
||||
// for keys of length 1 only the LSB is significant
|
||||
@ -1367,7 +1367,7 @@ AP_GPS_UBLOX::_parse_gps(void)
|
||||
}
|
||||
}
|
||||
} else {
|
||||
CFG_Debug("valget no active config for 0x%lx", (uint32_t)id);
|
||||
CFG_Debug("valget no active config for 0x%lx", (long unsigned)id);
|
||||
}
|
||||
|
||||
// step over the value
|
||||
|
Loading…
Reference in New Issue
Block a user