AP_AirSpeed: notify of calibration start

This commit is contained in:
Peter Barker 2018-03-28 13:30:50 +11:00 committed by Francisco Ferreira
parent 58d41e40d3
commit 30f944b921
1 changed files with 1 additions and 0 deletions

View File

@ -307,6 +307,7 @@ void AP_Airspeed::calibrate(bool in_startup)
state[i].cal.sum = 0;
state[i].cal.read_count = 0;
}
gcs().send_text(MAV_SEVERITY_INFO,"Airspeed calibration started");
}
/*