Browse Source

Copter: reset ahrs gyro drift after gyro calibration

mission-4.1.18
Randy Mackay 10 years ago
parent
commit
0ac3267d52
  1. 2
      ArduCopter/GCS_Mavlink.pde
  2. 5
      ArduCopter/system.pde

2
ArduCopter/GCS_Mavlink.pde

@ -1106,6 +1106,8 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) @@ -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) {

5
ArduCopter/system.pde

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

Loading…
Cancel
Save