Skip to content

Commit

Permalink
PLane: return MAV_RESULT_COMMAND_INT_ONLY if command-long support not…
Browse files Browse the repository at this point in the history
… compiled in
  • Loading branch information
peterbarker committed Nov 26, 2023
1 parent 6b9e82e commit 9294b08
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion ArduPlane/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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) {
Expand Down

0 comments on commit 9294b08

Please sign in to comment.