Copter: move read_AHRS() before run_rate_controllers()
this ensures the rate controllers use the latest data
This commit is contained in:
parent
f25f1cb3bf
commit
b0c710b67f
@ -1038,13 +1038,6 @@ void loop()
|
||||
// Main loop - 100hz
|
||||
static void fast_loop()
|
||||
{
|
||||
// run low level rate controllers that only require IMU data
|
||||
run_rate_controllers();
|
||||
|
||||
// write out the servo PWM values
|
||||
// ------------------------------
|
||||
set_servos_4();
|
||||
|
||||
// IMU DCM Algorithm
|
||||
// --------------------
|
||||
read_AHRS();
|
||||
@ -1053,6 +1046,13 @@ static void fast_loop()
|
||||
// --------------------------------------------------------------------
|
||||
update_trig();
|
||||
|
||||
// run low level rate controllers that only require IMU data
|
||||
run_rate_controllers();
|
||||
|
||||
// write out the servo PWM values
|
||||
// ------------------------------
|
||||
set_servos_4();
|
||||
|
||||
// Inertial Nav
|
||||
// --------------------
|
||||
read_inertia();
|
||||
|
Loading…
Reference in New Issue
Block a user