AP_DroneCAN: cope with null stats (for SLCAN interface)

this caused a crash on CubeOrange on boot if SLCAN is enabled
This commit is contained in:
Andrew Tridgell 2023-11-16 16:35:56 +11:00 committed by Tom Pittenger
parent 8ff2fa4fd9
commit 4cb2562ee5
1 changed files with 1 additions and 1 deletions

View File

@ -217,7 +217,7 @@ void CanardInterface::processTx(bool raw_commands_only = false) {
// volatile as the value can change at any time during can interrupt
// we need to ensure that this is not optimized
volatile const auto *stats = ifaces[iface]->get_statistics();
uint64_t last_transmit_us = stats->last_transmit_us;
uint64_t last_transmit_us = stats==nullptr?0:stats->last_transmit_us;
bool iface_down = true;
if (stats == nullptr || (AP_HAL::micros64() - last_transmit_us) < 200000UL) {
/*