mirror of https://github.com/ArduPilot/ardupilot
PLane: return MAV_RESULT_COMMAND_INT_ONLY if command-long support not compiled in
This commit is contained in:
parent
4dae077787
commit
6c105d2649
|
@ -1095,6 +1095,7 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_DO_CHANGE_SPEED(const mavlink_comma
|
|||
}
|
||||
|
||||
#if HAL_QUADPLANE_ENABLED
|
||||
#if AP_MAVLINK_COMMAND_LONG_ENABLED
|
||||
void GCS_MAVLINK_Plane::convert_MAV_CMD_NAV_TAKEOFF_to_COMMAND_INT(const mavlink_command_long_t &in, mavlink_command_int_t &out)
|
||||
{
|
||||
// convert to MAV_FRAME_LOCAL_OFFSET_NED, "NED local tangent frame
|
||||
|
@ -1115,7 +1116,6 @@ void GCS_MAVLINK_Plane::convert_MAV_CMD_NAV_TAKEOFF_to_COMMAND_INT(const mavlink
|
|||
out.z = -in.param7; // up -> down
|
||||
}
|
||||
|
||||
#if AP_MAVLINK_COMMAND_LONG_ENABLED
|
||||
void GCS_MAVLINK_Plane::convert_COMMAND_LONG_to_COMMAND_INT(const mavlink_command_long_t &in, mavlink_command_int_t &out, MAV_FRAME frame)
|
||||
{
|
||||
switch (in.command) {
|
||||
|
|
Loading…
Reference in New Issue