From 819d892bafb84b54d802732d8e2f335476a4d973 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 4 Jul 2018 13:44:54 +1000 Subject: [PATCH] Copter: handle MAV_CMD_ACCELCAL_VEHICLE_POS in GCS base class --- ArduCopter/GCS_Mavlink.cpp | 6 ------ 1 file changed, 6 deletions(-) diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 05c9820348..25e363ec3c 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -995,12 +995,6 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_ return MAV_RESULT_ACCEPTED; } - case MAV_CMD_ACCELCAL_VEHICLE_POS: - if (!copter.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); }