mirror of https://github.com/ArduPilot/ardupilot
Plane: faster startup
make it less likely to send wrong INS_PRODUCT_ID, plus don't waste as much time
This commit is contained in:
parent
145bbd1656
commit
fe3943e686
|
@ -419,15 +419,8 @@ static void startup_INS_ground(bool do_accel_init)
|
|||
}
|
||||
|
||||
if (style == AP_InertialSensor::COLD_START) {
|
||||
gcs_send_text_P(SEVERITY_MEDIUM, PSTR("Warming up ADC..."));
|
||||
mavlink_delay(500);
|
||||
|
||||
// Makes the servos wiggle twice - about to begin INS calibration - HOLD LEVEL AND STILL!!
|
||||
// -----------------------
|
||||
demo_servos(2);
|
||||
|
||||
gcs_send_text_P(SEVERITY_MEDIUM, PSTR("Beginning INS calibration; do not move plane"));
|
||||
mavlink_delay(1000);
|
||||
mavlink_delay(100);
|
||||
}
|
||||
|
||||
ahrs.init();
|
||||
|
|
Loading…
Reference in New Issue