mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-28 10:43:58 -04:00
AP_GPS: prevent NULL ptr deref
if we get an unexpected VALSET NACK we could dereference NULL. This could happen if we reboot while configuring an invalid key
This commit is contained in:
parent
69c540a0de
commit
500d190df3
@ -1123,12 +1123,14 @@ AP_GPS_UBLOX::_parse_gps(void)
|
||||
}
|
||||
break;
|
||||
case MSG_CFG_VALSET:
|
||||
CFG_Debug("NACK VALSET 0x%x 0x%x", (unsigned)_buffer.nack.msgID,
|
||||
unsigned(active_config.list[active_config.set_index].key));
|
||||
if (is_gnss_key(active_config.list[active_config.set_index].key)) {
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "GPS %u: unable to configure band 0x%02x",
|
||||
unsigned(state.instance + 1), unsigned(active_config.list[active_config.set_index].key));
|
||||
if (active_config.list != nullptr) {
|
||||
CFG_Debug("NACK VALSET 0x%x 0x%x", (unsigned)_buffer.nack.msgID,
|
||||
unsigned(active_config.list[active_config.set_index].key));
|
||||
if (is_gnss_key(active_config.list[active_config.set_index].key)) {
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "GPS %u: unable to configure band 0x%02x",
|
||||
unsigned(state.instance + 1), unsigned(active_config.list[active_config.set_index].key));
|
||||
|
||||
}
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user