diff --git a/ArduCopter/setup.pde b/ArduCopter/setup.pde index d88ff37bd4..6e2ef9f450 100644 --- a/ArduCopter/setup.pde +++ b/ArduCopter/setup.pde @@ -247,6 +247,7 @@ setup_motors(uint8_t argc, const Menu::arg *argv) static int8_t setup_accel(uint8_t argc, const Menu::arg *argv) { + ahrs.init(); ins.init(AP_InertialSensor::COLD_START, ins_sample_rate, flash_leds); @@ -285,6 +286,7 @@ static int8_t setup_accel_scale(uint8_t argc, const Menu::arg *argv) { cliSerial->println_P(PSTR("Initialising gyros")); + ahrs.init(); ins.init(AP_InertialSensor::COLD_START, ins_sample_rate, flash_leds); diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index a30feae748..042342b805 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -333,6 +333,9 @@ static void startup_ground(void) { gcs_send_text_P(SEVERITY_LOW,PSTR("GROUND START")); + // initialise ahrs (may push imu calibration into the mpu6000 if using that device). + ahrs.init(); + // Warm up and read Gyro offsets // ----------------------------- ins.init(AP_InertialSensor::COLD_START, @@ -342,9 +345,6 @@ static void startup_ground(void) report_ins(); #endif - // initialise ahrs (may push imu calibration into the mpu6000 if using that device). - ahrs.init(); - // setup fast AHRS gains to get right attitude ahrs.set_fast_gains(true); diff --git a/ArduCopter/test.pde b/ArduCopter/test.pde index acd3a9782f..68aed9500c 100644 --- a/ArduCopter/test.pde +++ b/ArduCopter/test.pde @@ -461,6 +461,7 @@ test_ins(uint8_t argc, const Menu::arg *argv) cliSerial->printf_P(PSTR("INS\n")); delay(1000); + ahrs.init(); ins.init(AP_InertialSensor::COLD_START, ins_sample_rate, flash_leds);