mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
Copter: re-arrange fast_loop for minimum latency
this makes motor outputs as responsive as possible to gyros
This commit is contained in:
parent
a11dca5229
commit
b4d9397821
@ -255,10 +255,16 @@ void Copter::loop()
|
|||||||
// Main loop - 400hz
|
// Main loop - 400hz
|
||||||
void Copter::fast_loop()
|
void Copter::fast_loop()
|
||||||
{
|
{
|
||||||
|
// update INS immediately to get current gyro data populated
|
||||||
|
ins.update();
|
||||||
|
|
||||||
// run low level rate controllers that only require IMU data
|
// run low level rate controllers that only require IMU data
|
||||||
attitude_control->rate_controller_run();
|
attitude_control->rate_controller_run();
|
||||||
|
|
||||||
// IMU DCM Algorithm
|
// send outputs to the motors library immediately
|
||||||
|
motors_output();
|
||||||
|
|
||||||
|
// run EKF state estimator (expensive)
|
||||||
// --------------------
|
// --------------------
|
||||||
read_AHRS();
|
read_AHRS();
|
||||||
|
|
||||||
@ -266,9 +272,6 @@ void Copter::fast_loop()
|
|||||||
update_heli_control_dynamics();
|
update_heli_control_dynamics();
|
||||||
#endif //HELI_FRAME
|
#endif //HELI_FRAME
|
||||||
|
|
||||||
// send outputs to the motors library
|
|
||||||
motors_output();
|
|
||||||
|
|
||||||
// Inertial Nav
|
// Inertial Nav
|
||||||
// --------------------
|
// --------------------
|
||||||
read_inertia();
|
read_inertia();
|
||||||
@ -626,7 +629,8 @@ void Copter::read_AHRS(void)
|
|||||||
gcs_check_input();
|
gcs_check_input();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
ahrs.update();
|
// we tell AHRS to skip INS update as we have already done it in fast_loop()
|
||||||
|
ahrs.update(true);
|
||||||
}
|
}
|
||||||
|
|
||||||
// read baro and rangefinder altitude at 10hz
|
// read baro and rangefinder altitude at 10hz
|
||||||
|
Loading…
Reference in New Issue
Block a user