mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_Math: remove HAL_CPU_CLASS_16
This commit is contained in:
parent
1e84e07edc
commit
1abeb03d2b
@ -26,24 +26,8 @@
|
|||||||
|
|
||||||
float longitude_scale(const struct Location &loc)
|
float longitude_scale(const struct Location &loc)
|
||||||
{
|
{
|
||||||
#if HAL_CPU_CLASS < HAL_CPU_CLASS_150
|
|
||||||
static int32_t last_lat;
|
|
||||||
static float scale = 1.0;
|
|
||||||
// don't optimise on faster CPUs. It causes some minor errors on Replay
|
|
||||||
if (labs(last_lat - loc.lat) < 100000) {
|
|
||||||
// we are within 0.01 degrees (about 1km) of the
|
|
||||||
// same latitude. We can avoid the cos() and return
|
|
||||||
// the same scale factor.
|
|
||||||
return scale;
|
|
||||||
}
|
|
||||||
scale = cosf(loc.lat * 1.0e-7f * DEG_TO_RAD);
|
|
||||||
scale = constrain_float(scale, 0.01f, 1.0f);
|
|
||||||
last_lat = loc.lat;
|
|
||||||
return scale;
|
|
||||||
#else
|
|
||||||
float scale = cosf(loc.lat * 1.0e-7f * DEG_TO_RAD);
|
float scale = cosf(loc.lat * 1.0e-7f * DEG_TO_RAD);
|
||||||
return constrain_float(scale, 0.01f, 1.0f);
|
return constrain_float(scale, 0.01f, 1.0f);
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user