mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Copter: move read_AHRS() before run_rate_controllers()
this ensures the rate controllers use the latest data
This commit is contained in:
parent
4a9e3a068a
commit
49a5b664cc
@ -1034,13 +1034,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();
|
||||
@ -1049,6 +1042,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