mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Copter: reset ahrs gyro drift after gyro calibration
This commit is contained in:
parent
95538d2992
commit
7b4cd9ee37
@ -1113,6 +1113,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) {
|
||||||
|
@ -320,6 +320,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);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user