Browse Source

Copter: fix guided attitude type_mask check

mission-4.1.18
vooon 9 years ago committed by Randy Mackay
parent
commit
f3cbbef418
  1. 4
      ArduCopter/GCS_Mavlink.cpp

4
ArduCopter/GCS_Mavlink.cpp

@ -1538,8 +1538,8 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) @@ -1538,8 +1538,8 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
mavlink_set_attitude_target_t packet;
mavlink_msg_set_attitude_target_decode(msg, &packet);
// ensure attitude and thrust are provided
if (((packet.type_mask & (1<<6)) == 0) || ((packet.type_mask & (1<<7)) == 0)) {
// ensure type_mask specifies to use attitude and thrust
if ((packet.type_mask & ((1<<7)|(1<<6))) != 0) {
break;
}

Loading…
Cancel
Save