Sub: Run rate controllers before AHRS/EKF update

This commit is contained in:
Jacob Walser 2017-03-06 14:01:02 -05:00 committed by Randy Mackay
parent 8a24b074f7
commit 4a3917a349

View File

@ -172,16 +172,15 @@ void Sub::loop()
// Main loop - 400hz
void Sub::fast_loop()
{
// IMU DCM Algorithm
// --------------------
read_AHRS();
if (control_mode != MANUAL) { //don't run rate controller in manual mode
// run low level rate controllers that only require IMU data
attitude_control.rate_controller_run();
}
// IMU DCM Algorithm
// --------------------
read_AHRS();
// send outputs to the motors library
motors_output();