mirror of https://github.com/ArduPilot/ardupilot
Plane: accept DO_ENGINE_CONTROL as both COMMAND_LONG and COMMAND_INT
This commit is contained in:
parent
4317a40fef
commit
4103d5cdb9
|
@ -973,6 +973,14 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_in
|
||||||
return MAV_RESULT_DENIED;
|
return MAV_RESULT_DENIED;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if AP_ICENGINE_ENABLED
|
||||||
|
case MAV_CMD_DO_ENGINE_CONTROL:
|
||||||
|
if (!plane.g2.ice_control.engine_control(packet.param1, packet.param2, packet.param3)) {
|
||||||
|
return MAV_RESULT_FAILED;
|
||||||
|
}
|
||||||
|
return MAV_RESULT_ACCEPTED;
|
||||||
|
#endif
|
||||||
|
|
||||||
default:
|
default:
|
||||||
return GCS_MAVLINK::handle_command_int_packet(packet, msg);
|
return GCS_MAVLINK::handle_command_int_packet(packet, msg);
|
||||||
}
|
}
|
||||||
|
@ -1094,14 +1102,6 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_l
|
||||||
return MAV_RESULT_ACCEPTED;
|
return MAV_RESULT_ACCEPTED;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if AP_ICENGINE_ENABLED
|
|
||||||
case MAV_CMD_DO_ENGINE_CONTROL:
|
|
||||||
if (!plane.g2.ice_control.engine_control(packet.param1, packet.param2, packet.param3)) {
|
|
||||||
return MAV_RESULT_FAILED;
|
|
||||||
}
|
|
||||||
return MAV_RESULT_ACCEPTED;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
default:
|
default:
|
||||||
return GCS_MAVLINK::handle_command_long_packet(packet, msg);
|
return GCS_MAVLINK::handle_command_long_packet(packet, msg);
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue