Skip to content

Commit 421c6f0

Browse files
GCS_MAVLink: check airspeed is enabled before trying to calibrate
1 parent 880abf7 commit 421c6f0

File tree

1 file changed

+1
-1
lines changed

1 file changed

+1
-1
lines changed

libraries/GCS_MAVLink/GCS_Common.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -4774,7 +4774,7 @@ MAV_RESULT GCS_MAVLINK::_handle_command_preflight_calibration_baro(const mavlink
47744774
#if AP_AIRSPEED_ENABLED
47754775

47764776
AP_Airspeed *airspeed = AP_Airspeed::get_singleton();
4777-
if (airspeed != nullptr) {
4777+
if (airspeed != nullptr && airspeed->enabled()) {
47784778
GCS_MAVLINK_InProgress *task = GCS_MAVLINK_InProgress::get_task(MAV_CMD_PREFLIGHT_CALIBRATION, GCS_MAVLINK_InProgress::Type::AIRSPEED_CAL, msg.sysid, msg.compid, chan);
47794779
if (task == nullptr) {
47804780
return MAV_RESULT_TEMPORARILY_REJECTED;

0 commit comments

Comments
 (0)