mirror of https://github.com/ArduPilot/ardupilot
AP_InertialSensor: rename to EXPECT_DELAY_MS()
This commit is contained in:
parent
48302427c7
commit
3823ba539c
|
@ -1122,7 +1122,7 @@ AP_InertialSensor::_init_gyro()
|
||||||
// cold start
|
// cold start
|
||||||
hal.console->printf("Init Gyro");
|
hal.console->printf("Init Gyro");
|
||||||
|
|
||||||
EXPECT_DELAY(hal, 60000);
|
EXPECT_DELAY_MS(60000);
|
||||||
|
|
||||||
/*
|
/*
|
||||||
we do the gyro calibration with no board rotation. This avoids
|
we do the gyro calibration with no board rotation. This avoids
|
||||||
|
@ -1702,7 +1702,7 @@ void AP_InertialSensor::acal_update()
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
EXPECT_DELAY(hal, 20000);
|
EXPECT_DELAY_MS(20000);
|
||||||
_acal->update();
|
_acal->update();
|
||||||
|
|
||||||
if (hal.util->get_soft_armed() && _acal->get_status() != ACCEL_CAL_NOT_STARTED) {
|
if (hal.util->get_soft_armed() && _acal->get_status() != ACCEL_CAL_NOT_STARTED) {
|
||||||
|
@ -1864,7 +1864,7 @@ MAV_RESULT AP_InertialSensor::simple_accel_cal()
|
||||||
return MAV_RESULT_TEMPORARILY_REJECTED;
|
return MAV_RESULT_TEMPORARILY_REJECTED;
|
||||||
}
|
}
|
||||||
|
|
||||||
EXPECT_DELAY(hal, 20000);
|
EXPECT_DELAY_MS(20000);
|
||||||
// record we are calibrating
|
// record we are calibrating
|
||||||
_calibrating = true;
|
_calibrating = true;
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue