mirror of https://github.com/ArduPilot/ardupilot
APM: support DO_SET_SERVO command
This commit is contained in:
parent
12c5e00db9
commit
9b2a2b2c2e
|
@ -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;
|
||||
|
|
Loading…
Reference in New Issue