From 8accfb97f6e02b4e6711ffadd3cbdb10eaf813f1 Mon Sep 17 00:00:00 2001 From: Alexey Bulatov Date: Fri, 2 Jun 2017 16:55:21 +0300 Subject: [PATCH] ArduCopter: Check for nullptr for motors class pointer Because of added initialisation of UAVCAN send_heartbeat function starts before motors initialisation. So we need check is object created. --- ArduCopter/GCS_Mavlink.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 32218b1267..c7a287f27c 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -70,7 +70,7 @@ NOINLINE void Copter::send_heartbeat(mavlink_channel_t chan) #endif // we are armed if we are not initialising - if (motors->armed()) { + if (motors != nullptr && motors->armed()) { base_mode |= MAV_MODE_FLAG_SAFETY_ARMED; }