mirror of https://github.com/ArduPilot/ardupilot
AP_InertialSensor: fixed watchdog on AHRS trim gyro wait
This commit is contained in:
parent
914e6c5497
commit
992016069a
|
@ -1127,8 +1127,6 @@ AP_InertialSensor::_init_gyro()
|
|||
// cold start
|
||||
hal.console->printf("Init Gyro");
|
||||
|
||||
EXPECT_DELAY_MS(60000);
|
||||
|
||||
/*
|
||||
we do the gyro calibration with no board rotation. This avoids
|
||||
having to rotate readings during the calibration
|
||||
|
@ -1164,6 +1162,8 @@ AP_InertialSensor::_init_gyro()
|
|||
float diff_norm[INS_MAX_INSTANCES];
|
||||
uint8_t i;
|
||||
|
||||
EXPECT_DELAY_MS(1000);
|
||||
|
||||
memset(diff_norm, 0, sizeof(diff_norm));
|
||||
|
||||
hal.console->printf("*");
|
||||
|
|
Loading…
Reference in New Issue