APM: ensure DO_SET_SERVO channels are enabled
This commit is contained in:
parent
1e51988ecc
commit
cf9dd9281c
@ -1106,6 +1106,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||||||
break;
|
break;
|
||||||
|
|
||||||
case MAV_CMD_DO_SET_SERVO:
|
case MAV_CMD_DO_SET_SERVO:
|
||||||
|
APM_RC.enable_out(packet.param1 - 1);
|
||||||
APM_RC.OutputCh(packet.param1 - 1, packet.param2);
|
APM_RC.OutputCh(packet.param1 - 1, packet.param2);
|
||||||
result = MAV_RESULT_ACCEPTED;
|
result = MAV_RESULT_ACCEPTED;
|
||||||
break;
|
break;
|
||||||
|
@ -576,6 +576,7 @@ static void do_set_home()
|
|||||||
|
|
||||||
static void do_set_servo()
|
static void do_set_servo()
|
||||||
{
|
{
|
||||||
|
APM_RC.enable_out(next_nonnav_command.p1 - 1);
|
||||||
APM_RC.OutputCh(next_nonnav_command.p1 - 1, next_nonnav_command.alt);
|
APM_RC.OutputCh(next_nonnav_command.p1 - 1, next_nonnav_command.alt);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user