APM: support DO_SET_SERVO command

This commit is contained in:
Andrew Tridgell 2012-09-03 20:56:36 +10:00
parent 96ea350143
commit 130b26e1f9

View File

@ -1105,6 +1105,10 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
}
break;
case MAV_CMD_DO_SET_SERVO:
APM_RC.OutputCh(packet.param1 - 1, packet.param2);
result = MAV_RESULT_ACCEPTED;
break;
default:
result = MAV_RESULT_UNSUPPORTED;