@ -1106,6 +1106,8 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
if (packet.param1 == 1) {
// gyro offset calibration
ins.init_gyro();
// reset ahrs gyro bias
ahrs.reset_gyro_drift();
result = MAV_RESULT_ACCEPTED;
}
if (packet.param3 == 1) {
@ -318,6 +318,11 @@ static void startup_ground(bool force_gyro_cal)
report_ins();
#endif
if (force_gyro_cal) {
// setup fast AHRS gains to get right attitude
ahrs.set_fast_gains(true);