mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-09 09:24:01 -04:00
Plane: removed an unnecessary delay on init
This commit is contained in:
parent
f4d8026d6d
commit
3481eda759
@ -587,7 +587,6 @@ void Plane::startup_INS_ground(void)
|
|||||||
|
|
||||||
if (ins.gyro_calibration_timing() != AP_InertialSensor::GYRO_CAL_NEVER) {
|
if (ins.gyro_calibration_timing() != AP_InertialSensor::GYRO_CAL_NEVER) {
|
||||||
gcs().send_text(MAV_SEVERITY_ALERT, "Beginning INS calibration. Do not move plane");
|
gcs().send_text(MAV_SEVERITY_ALERT, "Beginning INS calibration. Do not move plane");
|
||||||
hal.scheduler->delay(100);
|
|
||||||
} else {
|
} else {
|
||||||
gcs().send_text(MAV_SEVERITY_ALERT, "Skipping INS calibration");
|
gcs().send_text(MAV_SEVERITY_ALERT, "Skipping INS calibration");
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user