From 4cb2562ee523932ec0cfb4e42769e41eb0124c78 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 16 Nov 2023 16:35:56 +1100 Subject: [PATCH] AP_DroneCAN: cope with null stats (for SLCAN interface) this caused a crash on CubeOrange on boot if SLCAN is enabled --- libraries/AP_DroneCAN/AP_Canard_iface.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_DroneCAN/AP_Canard_iface.cpp b/libraries/AP_DroneCAN/AP_Canard_iface.cpp index 5fa96606f5..60980e510f 100644 --- a/libraries/AP_DroneCAN/AP_Canard_iface.cpp +++ b/libraries/AP_DroneCAN/AP_Canard_iface.cpp @@ -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) { /*