mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AP_AirSpeed: notify of calibration start
This commit is contained in:
parent
58d41e40d3
commit
30f944b921
@ -307,6 +307,7 @@ void AP_Airspeed::calibrate(bool in_startup)
|
|||||||
state[i].cal.sum = 0;
|
state[i].cal.sum = 0;
|
||||||
state[i].cal.read_count = 0;
|
state[i].cal.read_count = 0;
|
||||||
}
|
}
|
||||||
|
gcs().send_text(MAV_SEVERITY_INFO,"Airspeed calibration started");
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
Loading…
Reference in New Issue
Block a user