Browse Source

APM: ensure DO_SET_SERVO channels are enabled

mission-4.1.18
Andrew Tridgell 13 years ago
parent
commit
127117b640
  1. 1
      ArduPlane/GCS_Mavlink.pde
  2. 1
      ArduPlane/commands_logic.pde

1
ArduPlane/GCS_Mavlink.pde

@ -1106,6 +1106,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) @@ -1106,6 +1106,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
break;
case MAV_CMD_DO_SET_SERVO:
APM_RC.enable_out(packet.param1 - 1);
APM_RC.OutputCh(packet.param1 - 1, packet.param2);
result = MAV_RESULT_ACCEPTED;
break;

1
ArduPlane/commands_logic.pde

@ -576,6 +576,7 @@ static void do_set_home() @@ -576,6 +576,7 @@ static void do_set_home()
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);
}

Loading…
Cancel
Save