mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
GCS_MAVLink: fixed critical error on prefight cal ops
This commit is contained in:
parent
a8b440d6f1
commit
2f5e020a39
@ -3281,6 +3281,7 @@ MAV_RESULT GCS_MAVLINK::_handle_command_preflight_calibration_baro()
|
||||
|
||||
MAV_RESULT GCS_MAVLINK::_handle_command_preflight_calibration(const mavlink_command_long_t &packet)
|
||||
{
|
||||
EXPECT_DELAY_MS(30000);
|
||||
if (is_equal(packet.param1,1.0f)) {
|
||||
if (!calibrate_gyros()) {
|
||||
return MAV_RESULT_FAILED;
|
||||
|
Loading…
Reference in New Issue
Block a user