mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
GCS_MAVLink: set RC is_calibrating from command_preflight_calibration param4
This commit is contained in:
parent
c9107b2e98
commit
a45e7608f2
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user