From a8733ae8a808707f7dd476ff10630e792ac34894 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 8 Oct 2014 20:19:18 +0900 Subject: [PATCH] Copter: support pre-flight calibration of gyro --- ArduCopter/GCS_Mavlink.pde | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index 374ee772f4..7873aea518 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -1100,10 +1100,9 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) break; case MAV_CMD_PREFLIGHT_CALIBRATION: - if (packet.param1 == 1 || - packet.param2 == 1) { - ins.init_accel(); - ahrs.set_trim(Vector3f(0,0,0)); // clear out saved trim + if (packet.param1 == 1) { + // gyro offset calibration + ins.init_gyro(); result = MAV_RESULT_ACCEPTED; } if (packet.param3 == 1) {