@ -10,7 +10,7 @@
@@ -10,7 +10,7 @@
extern const AP_HAL : : HAL & hal ;
// constructor
NavEKF3_core : : NavEKF3_core ( voi d) :
NavEKF3_core : : NavEKF3_core ( NavEKF3 * _fronten d) :
_perf_UpdateFilter ( hal . util - > perf_alloc ( AP_HAL : : Util : : PC_ELAPSED , " EK3_UpdateFilter " ) ) ,
_perf_CovariancePrediction ( hal . util - > perf_alloc ( AP_HAL : : Util : : PC_ELAPSED , " EK3_CovariancePrediction " ) ) ,
_perf_FuseVelPosNED ( hal . util - > perf_alloc ( AP_HAL : : Util : : PC_ELAPSED , " EK3_FuseVelPosNED " ) ) ,
@ -19,7 +19,14 @@ NavEKF3_core::NavEKF3_core(void) :
@@ -19,7 +19,14 @@ NavEKF3_core::NavEKF3_core(void) :
_perf_FuseSideslip ( hal . util - > perf_alloc ( AP_HAL : : Util : : PC_ELAPSED , " EK3_FuseSideslip " ) ) ,
_perf_TerrainOffset ( hal . util - > perf_alloc ( AP_HAL : : Util : : PC_ELAPSED , " EK3_TerrainOffset " ) ) ,
_perf_FuseOptFlow ( hal . util - > perf_alloc ( AP_HAL : : Util : : PC_ELAPSED , " EK3_FuseOptFlow " ) ) ,
_perf_FuseBodyOdom ( hal . util - > perf_alloc ( AP_HAL : : Util : : PC_ELAPSED , " EK3_FuseBodyOdom " ) )
_perf_FuseBodyOdom ( hal . util - > perf_alloc ( AP_HAL : : Util : : PC_ELAPSED , " EK3_FuseBodyOdom " ) ) ,
frontend ( _frontend ) ,
// setup the intermediate variables shared by all cores (to save memory)
common ( ( struct core_common * ) _frontend - > core_common ) ,
Kfusion ( common - > Kfusion ) ,
KH ( common - > KH ) ,
KHP ( common - > KHP ) ,
nextP ( common - > nextP )
{
_perf_test [ 0 ] = hal . util - > perf_alloc ( AP_HAL : : Util : : PC_ELAPSED , " EK3_Test0 " ) ;
_perf_test [ 1 ] = hal . util - > perf_alloc ( AP_HAL : : Util : : PC_ELAPSED , " EK3_Test1 " ) ;
@ -36,9 +43,8 @@ NavEKF3_core::NavEKF3_core(void) :
@@ -36,9 +43,8 @@ NavEKF3_core::NavEKF3_core(void) :
}
// setup this core backend
bool NavEKF3_core : : setup_core ( NavEKF3 * _frontend , uint8_t _imu_index , uint8_t _core_index )
bool NavEKF3_core : : setup_core ( uint8_t _imu_index , uint8_t _core_index )
{
frontend = _frontend ;
imu_index = _imu_index ;
gyro_index_active = imu_index ;
accel_index_active = imu_index ;
@ -59,15 +65,15 @@ bool NavEKF3_core::setup_core(NavEKF3 *_frontend, uint8_t _imu_index, uint8_t _c
@@ -59,15 +65,15 @@ bool NavEKF3_core::setup_core(NavEKF3 *_frontend, uint8_t _imu_index, uint8_t _c
}
// find the maximum time delay for all potential sensors
uint16_t maxTimeDelay_ms = MAX ( _ frontend- > _hgtDelay_ms ,
MAX ( _ frontend- > _flowDelay_ms ,
MAX ( _ frontend- > _rngBcnDelay_ms ,
MAX ( _ frontend- > magDelay_ms ,
uint16_t maxTimeDelay_ms = MAX ( frontend - > _hgtDelay_ms ,
MAX ( frontend - > _flowDelay_ms ,
MAX ( frontend - > _rngBcnDelay_ms ,
MAX ( frontend - > magDelay_ms ,
( uint16_t ) ( EKF_TARGET_DT_MS )
) ) ) ) ;
// GPS sensing can have large delays and should not be included if disabled
if ( _ frontend- > _fusionModeGPS ! = 3 ) {
if ( frontend - > _fusionModeGPS ! = 3 ) {
// Wait for the configuration of all GPS units to be confirmed. Until this has occurred the GPS driver cannot provide a correct time delay
float gps_delay_sec = 0 ;
if ( ! AP : : gps ( ) . get_lag ( gps_delay_sec ) ) {
@ -90,7 +96,7 @@ bool NavEKF3_core::setup_core(NavEKF3 *_frontend, uint8_t _imu_index, uint8_t _c
@@ -90,7 +96,7 @@ bool NavEKF3_core::setup_core(NavEKF3 *_frontend, uint8_t _imu_index, uint8_t _c
// airspeed sensing can have large delays and should not be included if disabled
if ( _ahrs - > airspeed_sensor_enabled ( ) ) {
maxTimeDelay_ms = MAX ( maxTimeDelay_ms , _ frontend- > tasDelay_ms ) ;
maxTimeDelay_ms = MAX ( maxTimeDelay_ms , frontend - > tasDelay_ms ) ;
}
// calculate the IMU buffer length required to accommodate the maximum delay with some allowance for jitter
@ -100,13 +106,13 @@ bool NavEKF3_core::setup_core(NavEKF3 *_frontend, uint8_t _imu_index, uint8_t _c
@@ -100,13 +106,13 @@ bool NavEKF3_core::setup_core(NavEKF3 *_frontend, uint8_t _imu_index, uint8_t _c
// with the worst case delay from current time to ekf fusion time
// allow for worst case 50% extension of the ekf fusion time horizon delay due to timing jitter
uint16_t ekf_delay_ms = maxTimeDelay_ms + ( int ) ( ceilf ( ( float ) maxTimeDelay_ms * 0.5f ) ) ;
obs_buffer_length = ( ekf_delay_ms / _ frontend- > sensorIntervalMin_ms ) + 1 ;
obs_buffer_length = ( ekf_delay_ms / frontend - > sensorIntervalMin_ms ) + 1 ;
// limit to be no longer than the IMU buffer (we can't process data faster than the EKF prediction rate)
obs_buffer_length = MIN ( obs_buffer_length , imu_buffer_length ) ;
// calculate buffer size for optical flow data
const uint8_t flow_buffer_length = MIN ( ( ekf_delay_ms / _ frontend- > flowIntervalMin_ms ) + 1 , imu_buffer_length ) ;
const uint8_t flow_buffer_length = MIN ( ( ekf_delay_ms / frontend - > flowIntervalMin_ms ) + 1 , imu_buffer_length ) ;
if ( ! storedGPS . init ( obs_buffer_length ) ) {
return false ;
@ -211,7 +217,7 @@ void NavEKF3_core::InitialiseVariables()
@@ -211,7 +217,7 @@ void NavEKF3_core::InitialiseVariables()
lastKnownPositionNE . zero ( ) ;
prevTnb . zero ( ) ;
memset ( & P [ 0 ] [ 0 ] , 0 , sizeof ( P ) ) ;
memset ( & nextP [ 0 ] [ 0 ] , 0 , sizeof ( nextP ) ) ;
memset ( common , 0 , sizeof ( * commo n) ) ;
flowDataValid = false ;
rangeDataToFuse = false ;
Popt = 0.0f ;
@ -567,6 +573,12 @@ void NavEKF3_core::CovarianceInit()
@@ -567,6 +573,12 @@ void NavEKF3_core::CovarianceInit()
// Update Filter States - this should be called whenever new IMU data is available
void NavEKF3_core : : UpdateFilter ( bool predict )
{
# if CONFIG_HAL_BOARD == HAL_BOARD_SITL
// fill the common variables with NaN, so we catch any cases in
// SITL where they are used without initialisation
fill_nanf ( ( float * ) common , sizeof ( * common ) / sizeof ( float ) ) ;
# endif
// Set the flag to indicate to the filter that the front-end has given permission for a new state prediction cycle to be started
startPredictEnabled = predict ;