mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 18:48:30 -04:00
GCS_MAVLink: calibrate airspeed sensor if it is present
This commit is contained in:
parent
c6d7f5151a
commit
d2ab76b2c6
@ -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;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user