Copter: fix nack result_unsupported when arming fails

We should return unsupported if param1 does not equal 0 or 1
This commit is contained in:
Randy Mackay 2015-02-14 14:27:47 +09:00
parent 7ae1436b97
commit da4a36c4e0
1 changed files with 2 additions and 0 deletions

View File

@ -1208,6 +1208,8 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
} else if (packet.param1 == 0.0f && (mode_has_manual_throttle(control_mode) || ap.land_complete)) {
init_disarm_motors();
result = MAV_RESULT_ACCEPTED;
} else {
result = MAV_RESULT_UNSUPPORTED;
}
break;