Copter: reset ahrs gyro drift after gyro calibration

This commit is contained in:
Randy Mackay 2014-10-28 20:23:18 +09:00
parent dffcfb42bc
commit 0ac3267d52
2 changed files with 7 additions and 0 deletions

View File

@ -1106,6 +1106,8 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
if (packet.param1 == 1) { if (packet.param1 == 1) {
// gyro offset calibration // gyro offset calibration
ins.init_gyro(); ins.init_gyro();
// reset ahrs gyro bias
ahrs.reset_gyro_drift();
result = MAV_RESULT_ACCEPTED; result = MAV_RESULT_ACCEPTED;
} }
if (packet.param3 == 1) { if (packet.param3 == 1) {

View File

@ -318,6 +318,11 @@ static void startup_ground(bool force_gyro_cal)
report_ins(); report_ins();
#endif #endif
// reset ahrs gyro bias
if (force_gyro_cal) {
ahrs.reset_gyro_drift();
}
// setup fast AHRS gains to get right attitude // setup fast AHRS gains to get right attitude
ahrs.set_fast_gains(true); ahrs.set_fast_gains(true);