From fb28f426da565b807b08cb4b7e6b661a73d6fe6d Mon Sep 17 00:00:00 2001 From: Lucas De Marchi Date: Tue, 3 Nov 2015 11:46:39 -0200 Subject: [PATCH] AP_Math: remove check for AVR CPUs Remove the checks for HAL_CPU_CLASS > HAL_CPU_CLASS_16 and HAL_CPU_CLASS >= HAL_CPU_CLASS_75. Corresponding dead code will be removed on separate commits. --- libraries/AP_Math/AP_Math.h | 14 +++++--------- libraries/AP_Math/examples/location/location.cpp | 4 ---- libraries/AP_Math/location.cpp | 5 ----- libraries/AP_Math/matrix3.cpp | 2 -- libraries/AP_Math/matrix3.h | 4 +--- libraries/AP_Math/vector3.cpp | 2 -- libraries/AP_Math/vector3.h | 4 +--- 7 files changed, 7 insertions(+), 28 deletions(-) diff --git a/libraries/AP_Math/AP_Math.h b/libraries/AP_Math/AP_Math.h index c6604ddc7f..47495b071d 100644 --- a/libraries/AP_Math/AP_Math.h +++ b/libraries/AP_Math/AP_Math.h @@ -37,11 +37,9 @@ //GPS Specific double precision conversions //The precision here does matter when using the wsg* functions for converting -//between LLH and ECEF coordinates. Test code in examlpes/location/location.pde -#if HAL_CPU_CLASS >= HAL_CPU_CLASS_75 - #define DEG_TO_RAD_DOUBLE 0.0174532925199432954743716805978692718781530857086181640625 // equals to (M_PI / 180.0) - #define RAD_TO_DEG_DOUBLE 57.29577951308232286464772187173366546630859375 // equals to (180.0 / M_PI) -#endif +//between LLH and ECEF coordinates. Test code in examlpes/location/location.cpp +#define DEG_TO_RAD_DOUBLE 0.0174532925199432954743716805978692718781530857086181640625 // equals to (M_PI / 180.0) +#define RAD_TO_DEG_DOUBLE 57.29577951308232286464772187173366546630859375 // equals to (180.0 / M_PI) #define RadiansToCentiDegrees(x) ((x) * 5729.5779513082320876798154814105f) @@ -157,17 +155,15 @@ bool locations_are_same(const struct Location &loc1, const struct Location &loc2 */ void print_latlon(AP_HAL::BetterStream *s, int32_t lat_or_lon); -#if HAL_CPU_CLASS >= HAL_CPU_CLASS_75 // Converts from WGS84 geodetic coordinates (lat, lon, height) // into WGS84 Earth Centered, Earth Fixed (ECEF) coordinates // (X, Y, Z) void wgsllh2ecef(const Vector3d &llh, Vector3d &ecef); -// Converts from WGS84 Earth Centered, Earth Fixed (ECEF) -// coordinates (X, Y, Z), into WHS84 geodetic +// Converts from WGS84 Earth Centered, Earth Fixed (ECEF) +// coordinates (X, Y, Z), into WHS84 geodetic // coordinates (lat, lon, height) void wgsecef2llh(const Vector3d &ecef, Vector3d &llh); -#endif // constrain a value // constrain a value diff --git a/libraries/AP_Math/examples/location/location.cpp b/libraries/AP_Math/examples/location/location.cpp index f10554b919..bd48253bb8 100644 --- a/libraries/AP_Math/examples/location/location.cpp +++ b/libraries/AP_Math/examples/location/location.cpp @@ -234,7 +234,6 @@ static void test_wrap_cd(void) hal.console->printf("wrap_cd tests done\n"); } -#if HAL_CPU_CLASS >= HAL_CPU_CLASS_75 static void test_wgs_conversion_functions(void) { @@ -319,7 +318,6 @@ static void test_wgs_conversion_functions(void) } } -#endif //HAL_CPU_CLASS /* * polygon tests @@ -330,9 +328,7 @@ void setup(void) test_offset(); test_accuracy(); test_wrap_cd(); -#if HAL_CPU_CLASS >= HAL_CPU_CLASS_75 test_wgs_conversion_functions(); -#endif hal.console->printf("ALL TESTS DONE\n"); } diff --git a/libraries/AP_Math/location.cpp b/libraries/AP_Math/location.cpp index 6130cb0990..db8e0c0248 100644 --- a/libraries/AP_Math/location.cpp +++ b/libraries/AP_Math/location.cpp @@ -246,8 +246,6 @@ void print_latlon(AP_HAL::BetterStream *s, int32_t lat_or_lon) s->printf("%ld.%07ld",(long)dec_portion,(long)frac_portion); } -#if HAL_CPU_CLASS >= HAL_CPU_CLASS_75 - void wgsllh2ecef(const Vector3d &llh, Vector3d &ecef) { double d = WGS84_E * sin(llh[0]); double N = WGS84_A / sqrt(1. - d*d); @@ -349,6 +347,3 @@ void wgsecef2llh(const Vector3d &ecef, Vector3d &llh) { llh[0] = copysign(1.0, ecef[2]) * atan(S / (e_c*C)); llh[2] = (p*e_c*C + fabs(ecef[2])*S - WGS84_A*e_c*A_n) / sqrt(e_c*e_c*C*C + S*S); } - -#endif - diff --git a/libraries/AP_Math/matrix3.cpp b/libraries/AP_Math/matrix3.cpp index 53e2a201ce..b2e915845c 100644 --- a/libraries/AP_Math/matrix3.cpp +++ b/libraries/AP_Math/matrix3.cpp @@ -244,7 +244,6 @@ template Matrix3 Matrix3::operator *(const Matrix3 &m) cons template Matrix3 Matrix3::transposed(void) const; template Vector2 Matrix3::mulXY(const Vector3 &v) const; -#if HAL_CPU_CLASS >= HAL_CPU_CLASS_75 template void Matrix3::zero(void); template void Matrix3::rotate(const Vector3 &g); template void Matrix3::rotateXY(const Vector3 &g); @@ -256,4 +255,3 @@ template Vector3 Matrix3::mul_transpose(const Vector3 &v template Matrix3 Matrix3::operator *(const Matrix3 &m) const; template Matrix3 Matrix3::transposed(void) const; template Vector2 Matrix3::mulXY(const Vector3 &v) const; -#endif diff --git a/libraries/AP_Math/matrix3.h b/libraries/AP_Math/matrix3.h index f620b1fa25..c7bd9d236a 100644 --- a/libraries/AP_Math/matrix3.h +++ b/libraries/AP_Math/matrix3.h @@ -241,8 +241,6 @@ typedef Matrix3 Matrix3ui; typedef Matrix3 Matrix3l; typedef Matrix3 Matrix3ul; typedef Matrix3 Matrix3f; -#if HAL_CPU_CLASS >= HAL_CPU_CLASS_75 - typedef Matrix3 Matrix3d; -#endif +typedef Matrix3 Matrix3d; #endif // MATRIX3_H diff --git a/libraries/AP_Math/vector3.cpp b/libraries/AP_Math/vector3.cpp index a343580a0f..145e4a685a 100644 --- a/libraries/AP_Math/vector3.cpp +++ b/libraries/AP_Math/vector3.cpp @@ -385,7 +385,6 @@ template bool Vector3::is_nan(void) const; template bool Vector3::is_inf(void) const; template float Vector3::angle(const Vector3 &v) const; -#if HAL_CPU_CLASS >= HAL_CPU_CLASS_75 template void Vector3::rotate(enum Rotation); template float Vector3::length(void) const; template Vector3 Vector3::operator %(const Vector3 &v) const; @@ -406,4 +405,3 @@ template bool Vector3::operator !=(const Vector3 &v) const; template bool Vector3::is_nan(void) const; template bool Vector3::is_inf(void) const; template float Vector3::angle(const Vector3 &v) const; -#endif diff --git a/libraries/AP_Math/vector3.h b/libraries/AP_Math/vector3.h index a00c3fe937..186a18d3a6 100644 --- a/libraries/AP_Math/vector3.h +++ b/libraries/AP_Math/vector3.h @@ -217,8 +217,6 @@ typedef Vector3 Vector3ui; typedef Vector3 Vector3l; typedef Vector3 Vector3ul; typedef Vector3 Vector3f; -#if HAL_CPU_CLASS >= HAL_CPU_CLASS_75 - typedef Vector3 Vector3d; -#endif +typedef Vector3 Vector3d; #endif // VECTOR3_H