Browse Source

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.
master
Alexey Bulatov 8 years ago committed by Tom Pittenger
parent
commit
8accfb97f6
  1. 2
      ArduCopter/GCS_Mavlink.cpp

2
ArduCopter/GCS_Mavlink.cpp

@ -70,7 +70,7 @@ NOINLINE void Copter::send_heartbeat(mavlink_channel_t chan) @@ -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;
}

Loading…
Cancel
Save