From b32e8a4424b1762f801096472d083c1ac7913c6c Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Sun, 17 Feb 2019 10:48:21 -0800 Subject: [PATCH] AP_NavEKF2: remove HAL_CPU_CLASS_150 check, 150 is already a minimum requirement --- libraries/AP_NavEKF2/AP_NavEKF2.cpp | 2 -- libraries/AP_NavEKF2/AP_NavEKF2_AirDataFusion.cpp | 4 ---- libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp | 3 --- libraries/AP_NavEKF2/AP_NavEKF2_MagFusion.cpp | 4 ---- libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp | 2 -- libraries/AP_NavEKF2/AP_NavEKF2_OptFlowFusion.cpp | 3 --- libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp | 3 --- libraries/AP_NavEKF2/AP_NavEKF2_PosVelFusion.cpp | 3 --- libraries/AP_NavEKF2/AP_NavEKF2_RngBcnFusion.cpp | 3 --- libraries/AP_NavEKF2/AP_NavEKF2_VehicleStatus.cpp | 4 ---- libraries/AP_NavEKF2/AP_NavEKF2_core.cpp | 3 --- libraries/AP_NavEKF2/AP_NavEKF_GyroBias.cpp | 3 --- 12 files changed, 37 deletions(-) diff --git a/libraries/AP_NavEKF2/AP_NavEKF2.cpp b/libraries/AP_NavEKF2/AP_NavEKF2.cpp index da18084645..8fbc6ca1eb 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2.cpp @@ -1,5 +1,4 @@ #include -#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150 #include "AP_NavEKF2_core.h" #include @@ -1493,4 +1492,3 @@ void NavEKF2::writeExtNavData(const Vector3f &sensOffset, const Vector3f &pos, c } } -#endif //HAL_CPU_CLASS diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_AirDataFusion.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_AirDataFusion.cpp index 75779be407..5250f2d2f5 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_AirDataFusion.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_AirDataFusion.cpp @@ -1,7 +1,5 @@ #include -#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150 - #include "AP_NavEKF2.h" #include "AP_NavEKF2_core.h" #include @@ -439,5 +437,3 @@ void NavEKF2_core::FuseSideslip() * MISC FUNCTIONS * ********************************************************/ - -#endif // HAL_CPU_CLASS diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp index dfa0cde7c1..e81c1dd9a5 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp @@ -1,7 +1,5 @@ #include -#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150 - #include "AP_NavEKF2.h" #include "AP_NavEKF2_core.h" #include @@ -518,4 +516,3 @@ void NavEKF2_core::updateFilterStatus(void) filterStatus.flags.gps_quality_good = gpsGoodToAlign; } -#endif // HAL_CPU_CLASS diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_MagFusion.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_MagFusion.cpp index 9c5d3f9319..6e5a5803a6 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_MagFusion.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_MagFusion.cpp @@ -1,7 +1,5 @@ #include -#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150 - #include "AP_NavEKF2.h" #include "AP_NavEKF2_core.h" #include @@ -1167,5 +1165,3 @@ void NavEKF2_core::recordMagReset() yawInnovAtLastMagReset = innovYaw; } - -#endif // HAL_CPU_CLASS diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp index 4ec5450812..c7c9387c49 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp @@ -1,6 +1,5 @@ #include -#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150 #include "AP_NavEKF2.h" #include "AP_NavEKF2_core.h" #include @@ -857,4 +856,3 @@ void NavEKF2_core::writeExtNavData(const Vector3f &sensOffset, const Vector3f &p } -#endif // HAL_CPU_CLASS diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_OptFlowFusion.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_OptFlowFusion.cpp index 915c5a19d6..2ca2c4ceb6 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_OptFlowFusion.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_OptFlowFusion.cpp @@ -1,7 +1,5 @@ #include -#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150 - #include "AP_NavEKF2.h" #include "AP_NavEKF2_core.h" #include @@ -714,4 +712,3 @@ void NavEKF2_core::FuseOptFlow() * MISC FUNCTIONS * ********************************************************/ -#endif // HAL_CPU_CLASS diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp index 8e7b793c8b..947170ac98 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp @@ -1,7 +1,5 @@ #include -#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150 - #include "AP_NavEKF2.h" #include "AP_NavEKF2_core.h" #include @@ -617,4 +615,3 @@ void NavEKF2_core::getOutputTrackingError(Vector3f &error) const error = outputTrackError; } -#endif // HAL_CPU_CLASS diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_PosVelFusion.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_PosVelFusion.cpp index 83778070cc..5bcbfd9c54 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_PosVelFusion.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_PosVelFusion.cpp @@ -1,7 +1,5 @@ #include -#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150 - #include "AP_NavEKF2.h" #include "AP_NavEKF2_core.h" #include @@ -948,4 +946,3 @@ void NavEKF2_core::selectHeightForFusion() } } -#endif // HAL_CPU_CLASS diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_RngBcnFusion.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_RngBcnFusion.cpp index 6013acaf78..29be5dd524 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_RngBcnFusion.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_RngBcnFusion.cpp @@ -1,7 +1,5 @@ #include -#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150 - #include "AP_NavEKF2.h" #include "AP_NavEKF2_core.h" #include @@ -581,4 +579,3 @@ void NavEKF2_core::CalcRangeBeaconPosDownOffset(float obsVar, Vector3f &vehicleP } -#endif // HAL_CPU_CLASS diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_VehicleStatus.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_VehicleStatus.cpp index f90d04e456..ebefb2b136 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_VehicleStatus.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_VehicleStatus.cpp @@ -1,7 +1,5 @@ #include -#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150 - #include "AP_NavEKF2.h" #include "AP_NavEKF2_core.h" #include @@ -470,5 +468,3 @@ void NavEKF2_core::detectOptFlowTakeoff(void) } } - -#endif // HAL_CPU_CLASS diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_core.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_core.cpp index 015bfc6327..6bed91053f 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_core.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_core.cpp @@ -1,7 +1,5 @@ #include -#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150 - #include "AP_NavEKF2.h" #include "AP_NavEKF2_core.h" #include @@ -1577,4 +1575,3 @@ void NavEKF2_core::zeroAttCovOnly() } } -#endif // HAL_CPU_CLASS diff --git a/libraries/AP_NavEKF2/AP_NavEKF_GyroBias.cpp b/libraries/AP_NavEKF2/AP_NavEKF_GyroBias.cpp index 46090689e7..84c94a000c 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF_GyroBias.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF_GyroBias.cpp @@ -1,6 +1,5 @@ #include -#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150 #include "AP_NavEKF2.h" #include "AP_NavEKF2_core.h" @@ -33,5 +32,3 @@ float NavEKF2_core::InitialGyroBiasUncertainty(void) const return 2.5f; } - -#endif // HAL_CPU_CLASS