GCS_MAVLink: set RC is_calibrating from command_preflight_calibration param4

This commit is contained in:
Iampete1 2021-08-30 16:54:57 +01:00 committed by Andrew Tridgell
parent c9107b2e98
commit a45e7608f2

View File

@ -3826,6 +3826,8 @@ MAV_RESULT GCS_MAVLINK::_handle_command_preflight_calibration(const mavlink_comm
return _handle_command_preflight_calibration_baro();
}
rc().calibrating(is_positive(packet.param4));
#if HAL_INS_ENABLED
if (is_equal(packet.param5,1.0f)) {
// start with gyro calibration