From 9294b0834da8a45e47f84f927256d665a0b3b196 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 27 Nov 2023 08:08:23 +1100 Subject: [PATCH] PLane: return MAV_RESULT_COMMAND_INT_ONLY if command-long support not compiled in --- ArduPlane/GCS_Mavlink.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 9427b99e0cdac9..3715776f77ab64 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -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) {