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.
This commit is contained in:
Alexey Bulatov 2017-06-02 16:55:21 +03:00 committed by Tom Pittenger
parent e0acbd3e53
commit 8accfb97f6

View File

@ -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;
}