mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 17:18:28 -04:00
AP_NavEKF: only build on fast CPUs
This commit is contained in:
parent
1647ba9bd0
commit
4adf6000f3
@ -2,6 +2,8 @@
|
|||||||
|
|
||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
|
|
||||||
|
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150
|
||||||
|
|
||||||
// uncomment this to force the optimisation of this code, note that
|
// uncomment this to force the optimisation of this code, note that
|
||||||
// this makes debugging harder
|
// this makes debugging harder
|
||||||
// #pragma GCC optimize("O3")
|
// #pragma GCC optimize("O3")
|
||||||
@ -2011,3 +2013,5 @@ void NavEKF::calcEarthRateNED(Vector3f &omega, float latitude)
|
|||||||
omega.y = 0;
|
omega.y = 0;
|
||||||
omega.z = -earthRate*sinf(latitude);
|
omega.z = -earthRate*sinf(latitude);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif // HAL_CPU_CLASS
|
||||||
|
Loading…
Reference in New Issue
Block a user