Plane: fixed arming bit in MAVLink heartbeat message

This commit is contained in:
Andrew Tridgell 2013-12-11 16:08:56 +11:00
parent 24658197ff
commit b0236610b2

View File

@ -91,7 +91,7 @@ static NOINLINE void send_heartbeat(mavlink_channel_t chan)
#endif
// we are armed if we are not initialising
if (control_mode != INITIALISING) {
if (control_mode != INITIALISING && arming.is_armed()) {
base_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
}