mirror of https://github.com/ArduPilot/ardupilot
HIL: allow for fast HIL attitude update in HIL_MODE_ATTITUDE
this runs it at the full loop rate
This commit is contained in:
parent
995921ac55
commit
d69afc3945
|
@ -1170,7 +1170,7 @@ static void read_AHRS(void)
|
||||||
{
|
{
|
||||||
// Perform IMU calculations and get attitude info
|
// Perform IMU calculations and get attitude info
|
||||||
//-----------------------------------------------
|
//-----------------------------------------------
|
||||||
#if HIL_MODE == HIL_MODE_SENSORS
|
#if HIL_MODE != HIL_MODE_DISABLED
|
||||||
// update hil before dcm update
|
// update hil before dcm update
|
||||||
gcs_update();
|
gcs_update();
|
||||||
#endif
|
#endif
|
||||||
|
|
Loading…
Reference in New Issue