diff --git a/ArduPlane/system.pde b/ArduPlane/system.pde index f48252a046..1b7ea90960 100644 --- a/ArduPlane/system.pde +++ b/ArduPlane/system.pde @@ -435,12 +435,14 @@ static void startup_INS_ground(bool force_accel_level) mavlink_delay(1000); ins.init(AP_InertialSensor::COLD_START, mavlink_delay, flash_leds, &timer_scheduler); +#if HIL_MODE == HIL_MODE_DISABLED if (force_accel_level || g.manual_level == 0) { // when MANUAL_LEVEL is set to 1 we don't do accelerometer // levelling on each boot, and instead rely on the user to do // it once via the ground station ins.init_accel(mavlink_delay, flash_leds); } +#endif ahrs.set_fly_forward(true); ahrs.reset();