mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Sub: Run rate controllers before AHRS/EKF update
This commit is contained in:
parent
8a24b074f7
commit
4a3917a349
@ -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();
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user