ACM: use ahrs.set_fast_gains() on arm/disarm

This commit is contained in:
Andrew Tridgell 2012-08-21 15:38:31 +10:00
parent ac72db8f00
commit 1b0f5ac84f
2 changed files with 12 additions and 2 deletions

View File

@ -158,6 +158,9 @@ static void init_arm_motors()
// temp hack
motor_light = true;
digitalWrite(A_LED_PIN, LED_ON);
// go back to normal AHRS gains
ahrs.set_fast_gains(false);
}
@ -181,6 +184,9 @@ static void init_disarm_motors()
piezo_beep();
}
#endif
// setup fast AHRS gains to get right attitude
ahrs.set_fast_gains(true);
}
/*****************************************

View File

@ -385,10 +385,14 @@ static void startup_ground(void)
#if CLI_ENABLED == ENABLED
report_imu();
#endif
// initialise ahrs (may push imu calibration into the mpu6000 if using that device).
ahrs.init();
#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);
// reset the leds
// ---------------------------
clear_leds();