diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index d2fd53ca6f..10e7727b59 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -347,7 +347,6 @@ void Plane::airspeed_ratio_update(void) } const Vector3f &vg = gps.velocity(); airspeed.update_calibration(vg, aparm.airspeed_max); - gcs_send_airspeed_calibration(vg); } diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 09dcba97f1..0599b84eb9 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -1416,14 +1416,6 @@ void Plane::mavlink_delay_cb() logger.EnableWrites(true); } -/* - send airspeed calibration data - */ -void Plane::gcs_send_airspeed_calibration(const Vector3f &vg) -{ - gcs().send_airspeed_calibration(vg); -} - void GCS_MAVLINK_Plane::handle_mission_set_current(AP_Mission &mission, mavlink_message_t *msg) { plane.auto_state.next_wp_crosstrack = false; diff --git a/ArduPlane/GCS_Plane.cpp b/ArduPlane/GCS_Plane.cpp index e93c68eb8d..aeb2d96264 100644 --- a/ArduPlane/GCS_Plane.cpp +++ b/ArduPlane/GCS_Plane.cpp @@ -1,17 +1,6 @@ #include "GCS_Plane.h" #include "Plane.h" -void GCS_Plane::send_airspeed_calibration(const Vector3f &vg) -{ - for (uint8_t i=0; i