Browse Source

GCS_MAVLink: fixed critical error on prefight cal ops

master
Andrew Tridgell 5 years ago committed by Randy Mackay
parent
commit
418eb48bb2
  1. 1
      libraries/GCS_MAVLink/GCS_Common.cpp

1
libraries/GCS_MAVLink/GCS_Common.cpp

@ -3352,6 +3352,7 @@ MAV_RESULT GCS_MAVLINK::_handle_command_preflight_calibration_baro() @@ -3352,6 +3352,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…
Cancel
Save