mirror of https://github.com/ArduPilot/ardupilot
AP_Frsky_Telem: add define AP_AIRSPEED_ENABLED
This commit is contained in:
parent
9355fcd6b3
commit
f219d56e9c
|
@ -130,10 +130,12 @@ MAV_RESULT AP_Frsky_MAVliteMsgHandler::handle_command_preflight_calibration_baro
|
||||||
AP::baro().update_calibration();
|
AP::baro().update_calibration();
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "Barometer calibration complete");
|
gcs().send_text(MAV_SEVERITY_INFO, "Barometer calibration complete");
|
||||||
|
|
||||||
|
#if AP_AIRSPEED_ENABLED
|
||||||
AP_Airspeed *airspeed = AP_Airspeed::get_singleton();
|
AP_Airspeed *airspeed = AP_Airspeed::get_singleton();
|
||||||
if (airspeed != nullptr) {
|
if (airspeed != nullptr) {
|
||||||
airspeed->calibrate(false);
|
airspeed->calibrate(false);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
return MAV_RESULT_ACCEPTED;
|
return MAV_RESULT_ACCEPTED;
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue