Copter: ensure ahrs.init() is called

This commit is contained in:
Andrew Tridgell 2013-01-13 16:04:04 +11:00
parent c88766850a
commit 36e38eeef7
3 changed files with 6 additions and 3 deletions

View File

@ -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);

View File

@ -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);

View File

@ -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);