mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF2: remove HAL_CPU_CLASS_150 check, 150 is already a minimum requirement
This commit is contained in:
parent
c9c1c2678b
commit
b32e8a4424
|
@ -1,5 +1,4 @@
|
|||
#include <AP_HAL/AP_HAL.h>
|
||||
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150
|
||||
|
||||
#include "AP_NavEKF2_core.h"
|
||||
#include <AP_Vehicle/AP_Vehicle.h>
|
||||
|
@ -1493,4 +1492,3 @@ void NavEKF2::writeExtNavData(const Vector3f &sensOffset, const Vector3f &pos, c
|
|||
}
|
||||
}
|
||||
|
||||
#endif //HAL_CPU_CLASS
|
||||
|
|
|
@ -1,7 +1,5 @@
|
|||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150
|
||||
|
||||
#include "AP_NavEKF2.h"
|
||||
#include "AP_NavEKF2_core.h"
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
|
@ -439,5 +437,3 @@ void NavEKF2_core::FuseSideslip()
|
|||
* MISC FUNCTIONS *
|
||||
********************************************************/
|
||||
|
||||
|
||||
#endif // HAL_CPU_CLASS
|
||||
|
|
|
@ -1,7 +1,5 @@
|
|||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150
|
||||
|
||||
#include "AP_NavEKF2.h"
|
||||
#include "AP_NavEKF2_core.h"
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
|
@ -518,4 +516,3 @@ void NavEKF2_core::updateFilterStatus(void)
|
|||
filterStatus.flags.gps_quality_good = gpsGoodToAlign;
|
||||
}
|
||||
|
||||
#endif // HAL_CPU_CLASS
|
||||
|
|
|
@ -1,7 +1,5 @@
|
|||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150
|
||||
|
||||
#include "AP_NavEKF2.h"
|
||||
#include "AP_NavEKF2_core.h"
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
|
@ -1167,5 +1165,3 @@ void NavEKF2_core::recordMagReset()
|
|||
yawInnovAtLastMagReset = innovYaw;
|
||||
}
|
||||
|
||||
|
||||
#endif // HAL_CPU_CLASS
|
||||
|
|
|
@ -1,6 +1,5 @@
|
|||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150
|
||||
#include "AP_NavEKF2.h"
|
||||
#include "AP_NavEKF2_core.h"
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
|
@ -857,4 +856,3 @@ void NavEKF2_core::writeExtNavData(const Vector3f &sensOffset, const Vector3f &p
|
|||
|
||||
}
|
||||
|
||||
#endif // HAL_CPU_CLASS
|
||||
|
|
|
@ -1,7 +1,5 @@
|
|||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150
|
||||
|
||||
#include "AP_NavEKF2.h"
|
||||
#include "AP_NavEKF2_core.h"
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
|
@ -714,4 +712,3 @@ void NavEKF2_core::FuseOptFlow()
|
|||
* MISC FUNCTIONS *
|
||||
********************************************************/
|
||||
|
||||
#endif // HAL_CPU_CLASS
|
||||
|
|
|
@ -1,7 +1,5 @@
|
|||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150
|
||||
|
||||
#include "AP_NavEKF2.h"
|
||||
#include "AP_NavEKF2_core.h"
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
|
@ -617,4 +615,3 @@ void NavEKF2_core::getOutputTrackingError(Vector3f &error) const
|
|||
error = outputTrackError;
|
||||
}
|
||||
|
||||
#endif // HAL_CPU_CLASS
|
||||
|
|
|
@ -1,7 +1,5 @@
|
|||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150
|
||||
|
||||
#include "AP_NavEKF2.h"
|
||||
#include "AP_NavEKF2_core.h"
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
|
@ -948,4 +946,3 @@ void NavEKF2_core::selectHeightForFusion()
|
|||
}
|
||||
}
|
||||
|
||||
#endif // HAL_CPU_CLASS
|
||||
|
|
|
@ -1,7 +1,5 @@
|
|||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150
|
||||
|
||||
#include "AP_NavEKF2.h"
|
||||
#include "AP_NavEKF2_core.h"
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
|
@ -581,4 +579,3 @@ void NavEKF2_core::CalcRangeBeaconPosDownOffset(float obsVar, Vector3f &vehicleP
|
|||
|
||||
}
|
||||
|
||||
#endif // HAL_CPU_CLASS
|
||||
|
|
|
@ -1,7 +1,5 @@
|
|||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150
|
||||
|
||||
#include "AP_NavEKF2.h"
|
||||
#include "AP_NavEKF2_core.h"
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
|
@ -470,5 +468,3 @@ void NavEKF2_core::detectOptFlowTakeoff(void)
|
|||
}
|
||||
}
|
||||
|
||||
|
||||
#endif // HAL_CPU_CLASS
|
||||
|
|
|
@ -1,7 +1,5 @@
|
|||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150
|
||||
|
||||
#include "AP_NavEKF2.h"
|
||||
#include "AP_NavEKF2_core.h"
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
|
@ -1577,4 +1575,3 @@ void NavEKF2_core::zeroAttCovOnly()
|
|||
}
|
||||
}
|
||||
|
||||
#endif // HAL_CPU_CLASS
|
||||
|
|
|
@ -1,6 +1,5 @@
|
|||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#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
|
||||
|
|
Loading…
Reference in New Issue