Copter: move update_flight_mode to fast loop

This commit is contained in:
Randy Mackay 2014-01-11 17:03:05 +09:00 committed by Andrew Tridgell
parent 0e0a15f4a8
commit 7e37b16ccb
1 changed files with 3 additions and 3 deletions

View File

@ -1069,6 +1069,9 @@ static void fast_loop()
// --------------------
read_inertia();
// run the attitude controllers
update_flight_mode();
// optical flow
// --------------------
#if OPTFLOW == ENABLED
@ -1087,9 +1090,6 @@ static void rc_loop()
// -----------------------------------------
read_radio();
read_control_switch();
// run the attitude controllers
update_flight_mode();
}
// throttle_loop - should be run at 50 hz