@ -62,10 +62,10 @@ class NavEKF2_core
@@ -62,10 +62,10 @@ class NavEKF2_core
{
public :
// Constructor
NavEKF2_core ( voi d) ;
NavEKF2_core ( NavEKF2 * _fronten d) ;
// setup this core backend
bool setup_core ( NavEKF2 * _frontend , uint8_t _imu_index , uint8_t _core_index ) ;
bool setup_core ( uint8_t _imu_index , uint8_t _core_index ) ;
// Initialise the states from accelerometer and magnetometer data (if present)
// This method can only be used when the vehicle is static
@ -327,6 +327,9 @@ public:
@@ -327,6 +327,9 @@ public:
// return true when external nav data is also being used as a yaw observation
bool isExtNavUsedForYaw ( void ) ;
// return size of core_common for use in frontend allocation
static uint32_t get_core_common_size ( void ) { return sizeof ( core_common ) ; }
private :
// Reference to the global EKF frontend for parameters
NavEKF2 * frontend ;
@ -482,6 +485,26 @@ private:
@@ -482,6 +485,26 @@ private:
bool posReset ; // true when the position measurement has been reset
} ;
/*
common intermediate variables used by all cores . These save a
lot memory by avoiding allocating these arrays on every core
Having these as stack variables would save even more memory , but
would give us very high stack usage in some functions , which
poses a risk of stack overflow until we have infrastructure in
place to calculate maximum stack usage using static analysis .
*/
struct core_common {
Vector28 Kfusion ;
Matrix24 KH ;
Matrix24 KHP ;
Matrix24 nextP ;
Vector24 processNoise ;
Vector25 SF ;
Vector5 SG ;
Vector8 SQ ;
Vector23 SPP ;
} * common ;
// bias estimates for the IMUs that are enabled but not being used
// by this core.
struct {
@ -799,9 +822,9 @@ private:
@@ -799,9 +822,9 @@ private:
bool badIMUdata ; // boolean true if the bad IMU data is detected
float gpsNoiseScaler ; // Used to scale the GPS measurement noise and consistency gates to compensate for operation with small satellite counts
Vector28 Kfusion ; // Kalman gain vector
Matrix24 KH ; // intermediate result used for covariance updates
Matrix24 KHP ; // intermediate result used for covariance updates
Vector28 & Kfusion ; // Kalman gain vector
Matrix24 & KH ; // intermediate result used for covariance updates
Matrix24 & KHP ; // intermediate result used for covariance updates
Matrix24 P ; // covariance matrix
imu_ring_buffer_t < imu_elements > storedIMU ; // IMU data buffer
obs_ring_buffer_t < gps_elements > storedGPS ; // GPS data buffer
@ -856,12 +879,12 @@ private:
@@ -856,12 +879,12 @@ private:
bool allMagSensorsFailed ; // true if all magnetometer sensors have timed out on this flight and we are no longer using magnetometer data
uint32_t lastYawTime_ms ; // time stamp when yaw observation was last fused (msec)
uint32_t ekfStartTime_ms ; // time the EKF was started (msec)
Matrix24 nextP ; // Predicted covariance matrix before addition of process noise to diagonals
Vector24 processNoise ; // process noise added to diagonals of predicted covariance matrix
Vector25 SF ; // intermediate variables used to calculate predicted covariance matrix
Vector5 SG ; // intermediate variables used to calculate predicted covariance matrix
Vector8 SQ ; // intermediate variables used to calculate predicted covariance matrix
Vector23 SPP ; // intermediate variables used to calculate predicted covariance matrix
Matrix24 & nextP ; // Predicted covariance matrix before addition of process noise to diagonals
Vector24 & processNoise ; // process noise added to diagonals of predicted covariance matrix
Vector25 & SF ; // intermediate variables used to calculate predicted covariance matrix
Vector5 & SG ; // intermediate variables used to calculate predicted covariance matrix
Vector8 & SQ ; // intermediate variables used to calculate predicted covariance matrix
Vector23 & SPP ; // intermediate variables used to calculate predicted covariance matrix
Vector2f lastKnownPositionNE ; // last known position
uint32_t lastDecayTime_ms ; // time of last decay of GPS position offset
float velTestRatio ; // sum of squares of GPS velocity innovation divided by fail threshold