ArduPlane: calibrate accel with imu.init_accel after imu.init

* complements commit 73418559, where init_accel was eliminated
  from AP_IMU_INS::init cold start.
This commit is contained in:
Pat Hickey 2011-12-10 13:32:47 -08:00
parent 56b0be3124
commit f2652d23bf

View File

@ -452,6 +452,7 @@ static void startup_IMU_ground(void)
mavlink_delay(1000);
imu.init(IMU::COLD_START, mavlink_delay, &timer_scheduler);
imu.init_accel(mavlink_delay);
dcm.set_centripetal(1);
// read Baro pressure at ground