diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index f2c65707a0..e2571439b0 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -1510,6 +1510,14 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg) result = MAV_RESULT_ACCEPTED; } break; + + case MAV_CMD_ACCELCAL_VEHICLE_POS: + result = MAV_RESULT_FAILED; + + if (plane.ins.get_acal()->gcs_vehicle_position(packet.param1)) { + result = MAV_RESULT_ACCEPTED; + } + break; default: break;