GCS_MAVLink: calibrate airspeed sensor if it is present

This commit is contained in:
Peter Barker 2018-03-28 13:28:01 +11:00 committed by Francisco Ferreira
parent c6d7f5151a
commit d2ab76b2c6

View File

@ -2236,6 +2236,11 @@ MAV_RESULT GCS_MAVLINK::_handle_command_preflight_calibration_baro()
AP::baro().update_calibration();
gcs().send_text(MAV_SEVERITY_INFO, "Barometer calibration complete");
AP_Airspeed *airspeed = AP_Airspeed::get_singleton();
if (airspeed != nullptr) {
airspeed->calibrate(false);
}
return MAV_RESULT_ACCEPTED;
}