mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: correct mavlink result when airspeed not available
only in progress if we have started a task running
This commit is contained in:
parent
f7767d9068
commit
ae0fada9e6
|
@ -4233,10 +4233,11 @@ MAV_RESULT GCS_MAVLINK::_handle_command_preflight_calibration_baro(const mavlink
|
||||||
return MAV_RESULT_TEMPORARILY_REJECTED;
|
return MAV_RESULT_TEMPORARILY_REJECTED;
|
||||||
}
|
}
|
||||||
airspeed->calibrate(false);
|
airspeed->calibrate(false);
|
||||||
|
return MAV_RESULT_IN_PROGRESS;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
return MAV_RESULT_IN_PROGRESS;
|
return MAV_RESULT_ACCEPTED;
|
||||||
}
|
}
|
||||||
|
|
||||||
MAV_RESULT GCS_MAVLINK::_handle_command_preflight_calibration(const mavlink_command_long_t &packet, const mavlink_message_t &msg)
|
MAV_RESULT GCS_MAVLINK::_handle_command_preflight_calibration(const mavlink_command_long_t &packet, const mavlink_message_t &msg)
|
||||||
|
|
Loading…
Reference in New Issue