From b4e01b7936863a37b0219ceffa4621b56c6b3664 Mon Sep 17 00:00:00 2001
From: Andrew Tridgell <tridge@samba.org>
Date: Fri, 21 Nov 2014 19:08:58 +1100
Subject: [PATCH] Plane: if SKIP_GYRO_CAL is set the do a gyro cal on 3D accel
 cal

otherwise the user has no opportunity to do a gyro calibration
---
 ArduPlane/GCS_Mavlink.pde | 5 +++++
 1 file changed, 5 insertions(+)

diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde
index 2bda15cfc..c32ba7c5c 100644
--- a/ArduPlane/GCS_Mavlink.pde
+++ b/ArduPlane/GCS_Mavlink.pde
@@ -1025,6 +1025,11 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
             else if (packet.param5 == 1) {
                 float trim_roll, trim_pitch;
                 AP_InertialSensor_UserInteract_MAVLink interact(chan);
+                if (g.skip_gyro_cal) {
+                    // start with gyro calibration, otherwise if the user
+                    // has SKIP_GYRO_CAL=1 they don't get to do it
+                    ins.init_gyro();
+                }
                 if(ins.calibrate_accel(&interact, trim_roll, trim_pitch)) {
                     // reset ahrs's trim to suggested values from calibration routine
                     ahrs.set_trim(Vector3f(trim_roll, trim_pitch, 0));
-- 
GitLab