From 94ad85a67d00e7c6be1cbea744b76bd44a9e2c37 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 4 Jul 2018 13:43:14 +1000 Subject: [PATCH] Plane: handle MAV_CMD_ACCELCAL_VEHICLE_POS in GCS base class --- ArduPlane/GCS_Mavlink.cpp | 6 ------ 1 file changed, 6 deletions(-) diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 50aed3afba..477405f0c6 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -1105,12 +1105,6 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_l } return MAV_RESULT_ACCEPTED; - case MAV_CMD_ACCELCAL_VEHICLE_POS: - if (!plane.ins.get_acal()->gcs_vehicle_position(packet.param1)) { - return MAV_RESULT_FAILED; - } - return MAV_RESULT_ACCEPTED; - default: return GCS_MAVLINK::handle_command_long_packet(packet); }