Skip to content

Commit

Permalink
Copter: reset ahrs gyro drift after gyro calibration
Browse files Browse the repository at this point in the history
  • Loading branch information
rmackay9 committed Oct 28, 2014
1 parent dffcfb4 commit 0ac3267
Show file tree
Hide file tree
Showing 2 changed files with 7 additions and 0 deletions.
2 changes: 2 additions & 0 deletions ArduCopter/GCS_Mavlink.pde
Original file line number Diff line number Diff line change
Expand Up @@ -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) {
Expand Down
5 changes: 5 additions & 0 deletions ArduCopter/system.pde
Original file line number Diff line number Diff line change
Expand Up @@ -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);

Expand Down

0 comments on commit 0ac3267

Please sign in to comment.