2013-12-25 18:58:02 -04:00
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2013-12-29 22:25:02 -04:00
2013-12-25 18:58:02 -04:00
# include <AP_HAL.h>
2013-12-30 06:27:50 -04:00
2013-12-30 19:24:21 -04:00
# if HAL_CPU_CLASS >= HAL_CPU_CLASS_150
2014-01-03 03:52:37 -04:00
// uncomment this to force the optimisation of this code, note that
2013-12-30 06:27:50 -04:00
// this makes debugging harder
2014-01-05 01:37:24 -04:00
# if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
2014-01-01 22:45:59 -04:00
# pragma GCC optimize("O0")
# else
2014-01-30 18:11:54 -04:00
# pragma GCC optimize("O3")
2014-01-01 22:45:59 -04:00
# endif
2013-12-30 06:27:50 -04:00
2013-12-25 18:58:02 -04:00
# include "AP_NavEKF.h"
2014-01-01 21:15:22 -04:00
# include <AP_AHRS.h>
2014-01-05 01:37:24 -04:00
# include <stdio.h>
2013-12-25 18:58:02 -04:00
2013-12-29 03:37:55 -04:00
extern const AP_HAL : : HAL & hal ;
# define earthRate 0.000072921f
// constructor
2014-01-01 21:15:22 -04:00
NavEKF : : NavEKF ( const AP_AHRS * ahrs , AP_Baro & baro ) :
2013-12-29 03:37:55 -04:00
_ahrs ( ahrs ) ,
_baro ( baro ) ,
2013-12-30 01:19:50 -04:00
useAirspeed ( true ) ,
2013-12-29 03:37:55 -04:00
useCompass ( true ) ,
2014-01-04 00:20:14 -04:00
fusionModeGPS ( 0 ) , // 0 = GPS outputs 3D velocity, 1 = GPS outputs 2D velocity, 2 = GPS outputs, no velocity, 3 = Force postion and velocity measurements to zero (only used during pre-arm or ground testing)
2013-12-29 05:48:15 -04:00
covTimeStepMax ( 0.07f ) , // maximum time (sec) between covariance prediction updates
covDelAngMax ( 0.05f ) , // maximum delta angle between covariance prediction updates
2014-01-04 01:32:21 -04:00
yawVarScale ( 1.0f ) , // scale factor applied to yaw gyro errors when on ground
2013-12-30 08:12:01 -04:00
TASmsecMax ( 333 ) , // maximum allowed interal between airspeed measurement updates
MAGmsecMax ( 333 ) , // maximum allowed interval between magnetometer measurement updates
2013-12-31 17:54:56 -04:00
HGTmsecMax ( 1000 ) , // maximum interval between height measurement updates
2014-01-01 21:15:22 -04:00
fuseMeNow ( true ) , // forces fusion to occur on the IMU frame that data arrives
2014-01-04 00:20:14 -04:00
staticMode ( false ) , // staticMode forces position and velocity fusion with zero values
2013-12-29 05:48:15 -04:00
msecVelDelay ( 230 ) , // msec of GPS velocity delay
msecPosDelay ( 210 ) , // msec of GPS position delay
msecHgtDelay ( 350 ) , // msec of barometric height delay
msecMagDelay ( 30 ) , // msec of compass delay
2014-01-03 22:04:00 -04:00
msecTasDelay ( 210 ) // msec of true airspeed delay
2013-12-30 06:41:28 -04:00
# if CONFIG_HAL_BOARD == HAL_BOARD_PX4
, _perf_UpdateFilter ( perf_alloc ( PC_ELAPSED , " EKF_UpdateFilter " ) ) ,
_perf_CovariancePrediction ( perf_alloc ( PC_ELAPSED , " EKF_CovariancePrediction " ) ) ,
_perf_FuseVelPosNED ( perf_alloc ( PC_ELAPSED , " EKF_FuseVelPosNED " ) ) ,
_perf_FuseMagnetometer ( perf_alloc ( PC_ELAPSED , " EKF_FuseMagnetometer " ) ) ,
_perf_FuseAirspeed ( perf_alloc ( PC_ELAPSED , " EKF_FuseAirspeed " ) )
# endif
2013-12-25 18:58:02 -04:00
{
2014-01-01 08:15:37 -04:00
// Tuning parameters
2014-01-04 03:09:08 -04:00
_gpsHorizVelVar = 0.5f ; // GPS horizontal velocity variance (m/s)^2
_gpsVertVelVar = 0.5f ; // GPS vertical velocity variance (m/s)^2
_gpsHorizPosVar = 2.0f ; // GPS horizontal position variance m^2
_gpsVertPosVar = 0.04f ; // GPS or Baro vertical position variance m^2
2014-01-01 08:15:37 -04:00
_gpsVelVarAccScale = 0.2f ; // scale factor applied to velocity variance due to Vdot
_gpsPosVarAccScale = 0.2f ; // scale factor applied to position variance due to Vdot
_magVar = 0.0025f ; // magnetometer measurement variance Gauss^2
_magVarRateScale = 0.05f ; // scale factor applied to magnetometer variance due to angular rate
2014-01-01 17:12:06 -04:00
_easVar = 2.0f ; // equivalent airspeed noise variance (m/s)^2
_windStateNoise = 0.1f ; // RMS rate of change of wind (m/s^2)
_wndVarHgtRateScale = 0.5f ; // scale factor applied to wind process noise from height rate
2014-01-01 08:15:37 -04:00
// Misc initial conditions
2014-01-01 17:12:06 -04:00
hgtRate = 0.0f ;
2013-12-29 03:37:55 -04:00
mag_state . q0 = 1 ;
mag_state . DCM . identity ( ) ;
2013-12-25 18:58:02 -04:00
}
2014-01-03 20:16:19 -04:00
bool NavEKF : : healthy ( void ) const
2014-01-02 01:16:16 -04:00
{
if ( ! statesInitialised ) {
return false ;
}
Quaternion q ( states [ 0 ] , states [ 1 ] , states [ 2 ] , states [ 3 ] ) ;
if ( q . is_nan ( ) ) {
return false ;
}
if ( isnan ( states [ 4 ] ) | | isnan ( states [ 5 ] ) | | isnan ( states [ 6 ] ) ) {
return false ;
}
// all OK
return true ;
}
2014-01-30 18:46:10 -04:00
void NavEKF : : ResetPosition ( void )
{
// read the GPS
readGpsData ( ) ;
// read the barometer
readHgtData ( ) ;
// write to state vector
states [ 7 ] = posNE [ 0 ] ;
states [ 8 ] = posNE [ 1 ] ;
states [ 9 ] = - _baro . get_altitude ( ) ;
2014-01-04 00:20:14 -04:00
// set static mode to force positon and velocity measurements to zero
staticMode = true ;
2014-01-30 18:46:10 -04:00
}
2013-12-29 03:37:55 -04:00
void NavEKF : : InitialiseFilter ( void )
2013-12-25 18:58:02 -04:00
{
2014-01-02 20:47:09 -04:00
lastFixTime_ms = 0 ;
2014-01-02 07:05:09 -04:00
lastMagUpdate = 0 ;
lastAirspeedUpdate = 0 ;
2014-01-02 17:31:33 -04:00
velFailTime = 0 ;
posFailTime = 0 ;
hgtFailTime = 0 ;
storeIndex = 0 ;
memset ( & P [ 0 ] [ 0 ] , 0 , sizeof ( P ) ) ;
memset ( & nextP [ 0 ] [ 0 ] , 0 , sizeof ( nextP ) ) ;
memset ( & processNoise [ 0 ] , 0 , sizeof ( processNoise ) ) ;
memset ( & storedStates [ 0 ] [ 0 ] , 0 , sizeof ( storedStates ) ) ;
memset ( & statetimeStamp [ 0 ] , 0 , sizeof ( statetimeStamp ) ) ;
2014-01-03 22:04:00 -04:00
// get initial dtIMU
dtIMU = _ahrs - > get_ins ( ) . get_delta_time ( ) ;
2014-01-02 07:05:09 -04:00
2013-12-29 05:48:15 -04:00
// Calculate initial filter quaternion states from ahrs solution
2013-12-29 22:25:02 -04:00
Quaternion initQuat ;
2014-01-02 07:05:09 -04:00
initQuat . from_euler ( _ahrs - > roll , _ahrs - > pitch , _ahrs - > yaw ) ;
2013-12-29 05:48:15 -04:00
// Calculate initial Tbn matrix and rotate Mag measurements into NED
// to set initial NED magnetic field states
Matrix3f DCM ;
2014-01-02 07:05:09 -04:00
initQuat . rotation_matrix ( DCM ) ;
2013-12-29 05:48:15 -04:00
Vector3f initMagNED ;
Vector3f initMagXYZ ;
if ( useCompass )
{
readMagData ( ) ;
initMagXYZ = magData - magBias ;
2013-12-30 02:32:09 -04:00
initMagNED = DCM * initMagXYZ ;
2013-12-29 05:48:15 -04:00
}
2013-12-29 21:12:09 -04:00
// read the GPS
readGpsData ( ) ;
// read the barometer
readHgtData ( ) ;
2013-12-29 05:48:15 -04:00
2014-01-02 07:05:09 -04:00
// set onground flag
2013-12-29 21:12:09 -04:00
OnGroundCheck ( ) ;
2013-12-29 05:48:15 -04:00
// write to state vector
for ( uint8_t j = 0 ; j < = 3 ; j + + ) states [ j ] = initQuat [ j ] ; // quaternions
2013-12-29 21:12:09 -04:00
states [ 4 ] = velNED [ 0 ] ;
states [ 5 ] = velNED [ 1 ] ;
states [ 6 ] = velNED [ 2 ] ;
states [ 7 ] = posNE [ 0 ] ;
states [ 8 ] = posNE [ 1 ] ;
2014-01-02 07:05:09 -04:00
states [ 9 ] = - _baro . get_altitude ( ) ;
2014-01-03 03:52:37 -04:00
for ( uint8_t j = 0 ; j < = 4 ; j + + ) states [ j + 10 ] = 0.0 ; // dAngBias, windVel
states [ 15 ] = initMagNED . x ; // Magnetic Field North
states [ 16 ] = initMagNED . y ; // Magnetic Field East
states [ 17 ] = initMagNED . z ; // Magnetic Field Down
for ( uint8_t j = 0 ; j < = 2 ; j + + ) states [ j + 18 ] = magBias [ j ] ; // Magnetic Field Bias XYZ
2013-12-29 05:48:15 -04:00
statesInitialised = true ;
// initialise the covariance matrix
CovarianceInit ( ) ;
//Define Earth rotation vector in the NED navigation frame
2014-01-02 07:05:09 -04:00
calcEarthRateNED ( earthRateNED , _ahrs - > get_home ( ) . lat ) ;
2013-12-29 05:48:15 -04:00
//Initialise summed variables used by covariance prediction
summedDelAng . x = 0.0 ;
summedDelAng . y = 0.0 ;
summedDelAng . z = 0.0 ;
summedDelVel . x = 0.0 ;
summedDelVel . y = 0.0 ;
summedDelVel . z = 0.0 ;
dt = 0.0 ;
2013-12-29 21:12:09 -04:00
//Initialise IMU pre-processing states
readIMUData ( ) ;
2014-01-05 01:37:24 -04:00
#if 0
: : printf ( " NavEKF.InitialiseFilter: HOME.Alt=%.2f GPS.Alt=%.2f Baro.Alt=%.2f EKF.Alt=%.2f VEL=(%.2f,%.2f,%.2f) \n " ,
_ahrs - > get_home ( ) . alt * 0.01f ,
_ahrs - > get_gps ( ) - > altitude_cm * 0.01f ,
_baro . get_altitude ( ) ,
- states [ 9 ] ,
velNED [ 0 ] ,
velNED [ 1 ] ,
velNED [ 2 ] ) ;
# endif
2013-12-29 05:48:15 -04:00
}
void NavEKF : : UpdateFilter ( )
{
2014-01-02 07:05:09 -04:00
if ( ! statesInitialised ) {
return ;
}
2014-01-03 03:52:37 -04:00
2013-12-30 06:41:28 -04:00
perf_begin ( _perf_UpdateFilter ) ;
2013-12-29 05:48:15 -04:00
2014-01-02 07:05:09 -04:00
// This function will be called at 100Hz
//
// Read IMU data and convert to delta angles and velocities
readIMUData ( ) ;
if ( dtIMU > 0.2f ) {
// we have stalled for far too long - reset from DCM
InitialiseFilter ( ) ;
perf_end ( _perf_UpdateFilter ) ;
return ;
2013-12-29 05:48:15 -04:00
}
2014-01-02 07:05:09 -04:00
// Run the strapdown INS equations every IMU update
UpdateStrapdownEquationsNED ( ) ;
// store the predicted states for subsequent use by measurement fusion
StoreStates ( ) ;
// Check if on ground - status is used by covariance prediction
OnGroundCheck ( ) ;
// sum delta angles and time used by covariance prediction
summedDelAng = summedDelAng + correctedDelAng ;
summedDelVel = summedDelVel + correctedDelVel ;
dt + = dtIMU ;
// perform a covariance prediction if the total delta angle has exceeded the limit
// or the time limit will be exceeded at the next IMU update
// Do not predict covariance if magnetometer fusion still needs to be performed
if ( ( ( dt > = ( covTimeStepMax - dtIMU ) ) | | ( summedDelAng . length ( ) > covDelAngMax ) ) ) {
CovariancePrediction ( ) ;
covPredStep = true ;
summedDelAng . zero ( ) ;
summedDelVel . zero ( ) ;
dt = 0.0 ;
} else {
covPredStep = false ;
}
// Update states using GPS, altimeter, compass and airspeed observations
SelectVelPosFusion ( ) ;
SelectMagFusion ( ) ;
SelectTasFusion ( ) ;
2013-12-30 06:41:28 -04:00
perf_end ( _perf_UpdateFilter ) ;
2013-12-29 05:48:15 -04:00
}
void NavEKF : : SelectVelPosFusion ( )
{
2013-12-30 08:12:01 -04:00
if ( statesInitialised )
2013-12-29 05:48:15 -04:00
{
2013-12-30 08:12:01 -04:00
// Command fusion of GPS measurements if new ones available
readGpsData ( ) ;
2013-12-29 05:48:15 -04:00
readHgtData ( ) ;
2013-12-30 08:12:01 -04:00
if ( newDataGps )
{
fuseVelData = true ;
fusePosData = true ;
fuseHgtData = true ;
}
// Don't wait longer than HGTmsecMax msec between height updates
// if no GPS
else if ( ( IMUmsec - HGTmsecPrev ) > = HGTmsecMax )
{
2014-01-04 00:20:14 -04:00
// Static mode is used for pre-arm and bench testing and allows operation
// without GPS
if ( staticMode ) {
fuseVelData = true ;
fusePosData = true ;
fuseHgtData = true ;
}
else {
fuseVelData = false ;
fusePosData = false ;
fuseHgtData = true ;
}
2013-12-31 17:54:56 -04:00
HGTmsecPrev = IMUmsec ;
2013-12-30 08:12:01 -04:00
}
else
{
fuseVelData = false ;
fusePosData = false ;
fuseHgtData = false ;
}
// set flag to let other processes know that GPS and/or height fusion has
// ocurred in this frame
2014-01-03 03:52:37 -04:00
if ( fuseVelData | | fusePosData | | fuseHgtData )
2013-12-30 08:12:01 -04:00
{
FuseVelPosNED ( ) ;
newDataGps = false ;
posVelFuseStep = true ;
}
else
{
posVelFuseStep = false ;
}
2013-12-29 05:48:15 -04:00
}
}
void NavEKF : : SelectMagFusion ( )
{
2013-12-29 21:12:09 -04:00
readMagData ( ) ;
2013-12-30 08:12:01 -04:00
// Fuse Magnetometer Measurements - hold off if pos/vel fusion has occurred, unless maximum time interval exceeded
2014-01-02 07:05:09 -04:00
bool dataReady = statesInitialised & & useCompass & & newDataMag ;
bool timeout = ( ( IMUmsec - MAGmsecPrev ) > = MAGmsecMax ) ;
2013-12-31 17:54:56 -04:00
if ( dataReady & & ( ! posVelFuseStep | | timeout | | fuseMeNow ) )
2013-12-29 05:48:15 -04:00
{
MAGmsecPrev = IMUmsec ;
fuseMagData = true ;
}
else
{
fuseMagData = false ;
}
2013-12-30 08:12:01 -04:00
// Magnetometer fusion is always called if enabled because its fusion is spread across 3 time steps to reduce peak load
2013-12-29 05:48:15 -04:00
FuseMagnetometer ( ) ;
}
void NavEKF : : SelectTasFusion ( )
{
2013-12-29 21:12:09 -04:00
readAirSpdData ( ) ;
2013-12-30 08:12:01 -04:00
// Fuse Airspeed Measurements - hold off if pos/vel or magnetometer fusion has been performed, unless maximum time interval exceeded
2014-01-02 20:47:09 -04:00
bool dataReady = ( statesInitialised & & useAirspeed & & ! onGround & & newDataTas ) ;
bool clearFrame = ( ! posVelFuseStep & & ! magFusePerformed ) ;
bool timeout = ( ( IMUmsec - TASmsecPrev ) > = TASmsecMax ) ;
2013-12-31 17:54:56 -04:00
if ( dataReady & & ( clearFrame | | timeout | | fuseMeNow ) )
2013-12-29 05:48:15 -04:00
{
TASmsecPrev = IMUmsec ;
FuseAirspeed ( ) ;
}
}
void NavEKF : : UpdateStrapdownEquationsNED ( )
{
Vector3f delVelNav ;
float rotationMag ;
float rotScaler ;
2013-12-29 22:25:02 -04:00
Quaternion qUpdated ;
2013-12-29 05:48:15 -04:00
float quatMag ;
float quatMagInv ;
2013-12-29 22:25:02 -04:00
Quaternion deltaQuat ;
2013-12-29 05:48:15 -04:00
const Vector3f gravityNED ( 0 , 0 , GRAVITY_MSS ) ;
// Remove sensor bias errors
correctedDelAng . x = dAngIMU . x - states [ 10 ] ;
correctedDelAng . y = dAngIMU . y - states [ 11 ] ;
correctedDelAng . z = dAngIMU . z - states [ 12 ] ;
2014-01-03 03:52:37 -04:00
correctedDelVel . x = dVelIMU . x ;
correctedDelVel . y = dVelIMU . y ;
correctedDelVel . z = dVelIMU . z ;
2013-12-29 05:48:15 -04:00
// Save current measurements
prevDelAng = correctedDelAng ;
// Apply corrections for earths rotation rate and coning errors
2013-12-30 16:56:28 -04:00
// % * - and + operators have been overloaded
2013-12-29 05:48:15 -04:00
correctedDelAng = correctedDelAng - prevTnb * earthRateNED * dtIMU + ( prevDelAng % correctedDelAng ) * 8.333333333333333e-2 f ;
// Convert the rotation vector to its equivalent quaternion
rotationMag = correctedDelAng . length ( ) ;
if ( rotationMag < 1e-12 f )
{
deltaQuat [ 0 ] = 1 ;
deltaQuat [ 1 ] = 0 ;
deltaQuat [ 2 ] = 0 ;
deltaQuat [ 3 ] = 0 ;
}
else
{
deltaQuat [ 0 ] = cosf ( 0.5f * rotationMag ) ;
rotScaler = ( sinf ( 0.5f * rotationMag ) ) / rotationMag ;
deltaQuat [ 1 ] = correctedDelAng . x * rotScaler ;
deltaQuat [ 2 ] = correctedDelAng . y * rotScaler ;
deltaQuat [ 3 ] = correctedDelAng . z * rotScaler ;
}
// Update the quaternions by rotating from the previous attitude through
// the delta angle rotation quaternion
qUpdated [ 0 ] = states [ 0 ] * deltaQuat [ 0 ] - states [ 1 ] * deltaQuat [ 1 ] - states [ 2 ] * deltaQuat [ 2 ] - states [ 3 ] * deltaQuat [ 3 ] ;
qUpdated [ 1 ] = states [ 0 ] * deltaQuat [ 1 ] + states [ 1 ] * deltaQuat [ 0 ] + states [ 2 ] * deltaQuat [ 3 ] - states [ 3 ] * deltaQuat [ 2 ] ;
qUpdated [ 2 ] = states [ 0 ] * deltaQuat [ 2 ] + states [ 2 ] * deltaQuat [ 0 ] + states [ 3 ] * deltaQuat [ 1 ] - states [ 1 ] * deltaQuat [ 3 ] ;
qUpdated [ 3 ] = states [ 0 ] * deltaQuat [ 3 ] + states [ 3 ] * deltaQuat [ 0 ] + states [ 1 ] * deltaQuat [ 2 ] - states [ 2 ] * deltaQuat [ 1 ] ;
// Normalise the quaternions and update the quaternion states
2013-12-30 02:32:09 -04:00
quatMag = sqrtf ( sq ( qUpdated [ 0 ] ) + sq ( qUpdated [ 1 ] ) + sq ( qUpdated [ 2 ] ) + sq ( qUpdated [ 3 ] ) ) ;
2013-12-29 05:48:15 -04:00
if ( quatMag > 1e-16 f )
{
quatMagInv = 1.0f / quatMag ;
states [ 0 ] = quatMagInv * qUpdated [ 0 ] ;
states [ 1 ] = quatMagInv * qUpdated [ 1 ] ;
states [ 2 ] = quatMagInv * qUpdated [ 2 ] ;
states [ 3 ] = quatMagInv * qUpdated [ 3 ] ;
}
// Calculate the body to nav cosine matrix
2013-12-29 23:43:29 -04:00
Quaternion q ( states [ 0 ] , states [ 1 ] , states [ 2 ] , states [ 3 ] ) ;
Matrix3f Tbn_temp ;
q . rotation_matrix ( Tbn_temp ) ;
prevTnb = Tbn_temp . transposed ( ) ;
2013-12-29 05:48:15 -04:00
// transform body delta velocities to delta velocities in the nav frame
// * and + operators have been overloaded
2013-12-29 23:43:29 -04:00
delVelNav = Tbn_temp * correctedDelVel + gravityNED * dtIMU ;
2013-12-29 05:48:15 -04:00
// calculate the magnitude of the nav acceleration (required for GPS
// variance estimation)
accNavMag = delVelNav . length ( ) / dtIMU ;
// If calculating position save previous velocity
Vector3f lastVelocity ;
lastVelocity . x = states [ 4 ] ;
lastVelocity . y = states [ 5 ] ;
lastVelocity . z = states [ 6 ] ;
// Sum delta velocities to get velocity
states [ 4 ] = states [ 4 ] + delVelNav . x ;
states [ 5 ] = states [ 5 ] + delVelNav . y ;
states [ 6 ] = states [ 6 ] + delVelNav . z ;
// If calculating postions, do a trapezoidal integration for position
states [ 7 ] = states [ 7 ] + 0.5f * ( states [ 4 ] + lastVelocity [ 0 ] ) * dtIMU ;
states [ 8 ] = states [ 8 ] + 0.5f * ( states [ 5 ] + lastVelocity [ 1 ] ) * dtIMU ;
states [ 9 ] = states [ 9 ] + 0.5f * ( states [ 6 ] + lastVelocity [ 2 ] ) * dtIMU ;
}
void NavEKF : : CovariancePrediction ( )
{
2013-12-30 06:41:28 -04:00
perf_begin ( _perf_CovariancePrediction ) ;
2013-12-29 05:48:15 -04:00
// scalars
float windVelSigma ;
float dAngBiasSigma ;
float magEarthSigma ;
float magBodySigma ;
float daxCov ;
float dayCov ;
float dazCov ;
float dvxCov ;
float dvyCov ;
float dvzCov ;
float dvx ;
float dvy ;
float dvz ;
float dax ;
float day ;
float daz ;
float q0 ;
float q1 ;
float q2 ;
float q3 ;
float dax_b ;
float day_b ;
float daz_b ;
// calculate covariance prediction process noise
2014-01-01 17:12:06 -04:00
// filter height rate using a 10 second time constant filter
float alpha = 0.1f * dt ;
hgtRate = hgtRate * ( 1.0f - alpha ) - states [ 6 ] * alpha ;
// use filtered height rate to increase wind process noise when climbing or descending
// this allows for wind gradient effects.
windVelSigma = dt * _windStateNoise * ( 1.0f + _wndVarHgtRateScale * fabsf ( hgtRate ) ) ;
2013-12-29 05:48:15 -04:00
dAngBiasSigma = dt * 5.0e-7 f ;
2014-01-02 22:10:38 -04:00
magEarthSigma = dt * 3.0e-4 f ;
magBodySigma = dt * 3.0e-4 f ;
2013-12-29 05:48:15 -04:00
for ( uint8_t i = 0 ; i < = 9 ; i + + ) processNoise [ i ] = 1.0e-9 f ;
for ( uint8_t i = 10 ; i < = 12 ; i + + ) processNoise [ i ] = dAngBiasSigma ;
2013-12-31 02:06:56 -04:00
if ( onGround ) processNoise [ 12 ] = dAngBiasSigma * yawVarScale ;
2014-01-03 03:52:37 -04:00
for ( uint8_t i = 13 ; i < = 14 ; i + + ) processNoise [ i ] = windVelSigma ;
for ( uint8_t i = 15 ; i < = 17 ; i + + ) processNoise [ i ] = magEarthSigma ;
for ( uint8_t i = 18 ; i < = 20 ; i + + ) processNoise [ i ] = magBodySigma ;
for ( uint8_t i = 0 ; i < = 20 ; i + + ) processNoise [ i ] = sq ( processNoise [ i ] ) ;
2013-12-29 05:48:15 -04:00
// set variables used to calculate covariance growth
dvx = summedDelVel . x ;
dvy = summedDelVel . y ;
dvz = summedDelVel . z ;
dax = summedDelAng . x ;
day = summedDelAng . y ;
daz = summedDelAng . z ;
q0 = states [ 0 ] ;
q1 = states [ 1 ] ;
q2 = states [ 2 ] ;
q3 = states [ 3 ] ;
dax_b = states [ 10 ] ;
day_b = states [ 11 ] ;
daz_b = states [ 12 ] ;
daxCov = sq ( dt * 1.4544411e-2 f ) ;
dayCov = sq ( dt * 1.4544411e-2 f ) ;
2013-12-30 20:37:23 -04:00
dazCov = sq ( dt * 1.4544411e-2 f ) ;
2013-12-31 17:54:56 -04:00
if ( onGround ) dazCov = dazCov * sq ( yawVarScale ) ;
2013-12-29 05:48:15 -04:00
dvxCov = sq ( dt * 0.5f ) ;
dvyCov = sq ( dt * 0.5f ) ;
dvzCov = sq ( dt * 0.5f ) ;
// Predicted covariance calculation
2014-01-03 03:52:37 -04:00
SF [ 0 ] = 2 * dvx * q1 + 2 * dvy * q2 + 2 * dvz * q3 ;
SF [ 1 ] = 2 * dvx * q3 + 2 * dvy * q0 - 2 * dvz * q1 ;
SF [ 2 ] = 2 * dvx * q0 - 2 * dvy * q3 + 2 * dvz * q2 ;
SF [ 3 ] = day / 2 - day_b / 2 ;
SF [ 4 ] = daz / 2 - daz_b / 2 ;
SF [ 5 ] = dax / 2 - dax_b / 2 ;
SF [ 6 ] = dax_b / 2 - dax / 2 ;
SF [ 7 ] = daz_b / 2 - daz / 2 ;
SF [ 8 ] = day_b / 2 - day / 2 ;
SF [ 9 ] = q1 / 2 ;
SF [ 10 ] = q2 / 2 ;
SF [ 11 ] = q3 / 2 ;
SF [ 12 ] = 2 * dvz * q0 ;
SF [ 13 ] = 2 * dvy * q1 ;
2013-12-29 05:48:15 -04:00
SG [ 0 ] = q0 / 2 ;
SG [ 1 ] = sq ( q3 ) ;
SG [ 2 ] = sq ( q2 ) ;
SG [ 3 ] = sq ( q1 ) ;
SG [ 4 ] = sq ( q0 ) ;
SG [ 5 ] = 2 * q2 * q3 ;
SG [ 6 ] = 2 * q1 * q3 ;
SG [ 7 ] = 2 * q1 * q2 ;
SQ [ 0 ] = dvzCov * ( SG [ 5 ] - 2 * q0 * q1 ) * ( SG [ 1 ] - SG [ 2 ] - SG [ 3 ] + SG [ 4 ] ) - dvyCov * ( SG [ 5 ] + 2 * q0 * q1 ) * ( SG [ 1 ] - SG [ 2 ] + SG [ 3 ] - SG [ 4 ] ) + dvxCov * ( SG [ 6 ] - 2 * q0 * q2 ) * ( SG [ 7 ] + 2 * q0 * q3 ) ;
SQ [ 1 ] = dvzCov * ( SG [ 6 ] + 2 * q0 * q2 ) * ( SG [ 1 ] - SG [ 2 ] - SG [ 3 ] + SG [ 4 ] ) - dvxCov * ( SG [ 6 ] - 2 * q0 * q2 ) * ( SG [ 1 ] + SG [ 2 ] - SG [ 3 ] - SG [ 4 ] ) + dvyCov * ( SG [ 5 ] + 2 * q0 * q1 ) * ( SG [ 7 ] - 2 * q0 * q3 ) ;
SQ [ 2 ] = dvzCov * ( SG [ 5 ] - 2 * q0 * q1 ) * ( SG [ 6 ] + 2 * q0 * q2 ) - dvyCov * ( SG [ 7 ] - 2 * q0 * q3 ) * ( SG [ 1 ] - SG [ 2 ] + SG [ 3 ] - SG [ 4 ] ) - dvxCov * ( SG [ 7 ] + 2 * q0 * q3 ) * ( SG [ 1 ] + SG [ 2 ] - SG [ 3 ] - SG [ 4 ] ) ;
SQ [ 3 ] = ( dayCov * q1 * SG [ 0 ] ) / 2 - ( dazCov * q1 * SG [ 0 ] ) / 2 - ( daxCov * q2 * q3 ) / 4 ;
SQ [ 4 ] = ( dazCov * q2 * SG [ 0 ] ) / 2 - ( daxCov * q2 * SG [ 0 ] ) / 2 - ( dayCov * q1 * q3 ) / 4 ;
SQ [ 5 ] = ( daxCov * q3 * SG [ 0 ] ) / 2 - ( dayCov * q3 * SG [ 0 ] ) / 2 - ( dazCov * q1 * q2 ) / 4 ;
SQ [ 6 ] = ( daxCov * q1 * q2 ) / 4 - ( dazCov * q3 * SG [ 0 ] ) / 2 - ( dayCov * q1 * q2 ) / 4 ;
SQ [ 7 ] = ( dazCov * q1 * q3 ) / 4 - ( daxCov * q1 * q3 ) / 4 - ( dayCov * q2 * SG [ 0 ] ) / 2 ;
SQ [ 8 ] = ( dayCov * q2 * q3 ) / 4 - ( daxCov * q1 * SG [ 0 ] ) / 2 - ( dazCov * q2 * q3 ) / 4 ;
SQ [ 9 ] = sq ( SG [ 0 ] ) ;
SQ [ 10 ] = sq ( q1 ) ;
2014-01-03 03:52:37 -04:00
SPP [ 0 ] = SF [ 12 ] + SF [ 13 ] - 2 * dvx * q2 ;
SPP [ 1 ] = 2 * dvx * q0 - 2 * dvy * q3 + 2 * dvz * q2 ;
SPP [ 2 ] = 2 * dvx * q3 + 2 * dvy * q0 - 2 * dvz * q1 ;
SPP [ 3 ] = SF [ 11 ] ;
SPP [ 4 ] = SF [ 10 ] ;
SPP [ 5 ] = SF [ 9 ] ;
SPP [ 6 ] = SF [ 7 ] ;
SPP [ 7 ] = SF [ 8 ] ;
nextP [ 0 ] [ 0 ] = P [ 0 ] [ 0 ] + P [ 1 ] [ 0 ] * SF [ 6 ] + P [ 2 ] [ 0 ] * SPP [ 7 ] + P [ 3 ] [ 0 ] * SPP [ 6 ] + P [ 10 ] [ 0 ] * SPP [ 5 ] + P [ 11 ] [ 0 ] * SPP [ 4 ] + P [ 12 ] [ 0 ] * SPP [ 3 ] + ( daxCov * SQ [ 10 ] ) / 4 + SF [ 6 ] * ( P [ 0 ] [ 1 ] + P [ 1 ] [ 1 ] * SF [ 6 ] + P [ 2 ] [ 1 ] * SPP [ 7 ] + P [ 3 ] [ 1 ] * SPP [ 6 ] + P [ 10 ] [ 1 ] * SPP [ 5 ] + P [ 11 ] [ 1 ] * SPP [ 4 ] + P [ 12 ] [ 1 ] * SPP [ 3 ] ) + SPP [ 7 ] * ( P [ 0 ] [ 2 ] + P [ 1 ] [ 2 ] * SF [ 6 ] + P [ 2 ] [ 2 ] * SPP [ 7 ] + P [ 3 ] [ 2 ] * SPP [ 6 ] + P [ 10 ] [ 2 ] * SPP [ 5 ] + P [ 11 ] [ 2 ] * SPP [ 4 ] + P [ 12 ] [ 2 ] * SPP [ 3 ] ) + SPP [ 6 ] * ( P [ 0 ] [ 3 ] + P [ 1 ] [ 3 ] * SF [ 6 ] + P [ 2 ] [ 3 ] * SPP [ 7 ] + P [ 3 ] [ 3 ] * SPP [ 6 ] + P [ 10 ] [ 3 ] * SPP [ 5 ] + P [ 11 ] [ 3 ] * SPP [ 4 ] + P [ 12 ] [ 3 ] * SPP [ 3 ] ) + SPP [ 5 ] * ( P [ 0 ] [ 10 ] + P [ 1 ] [ 10 ] * SF [ 6 ] + P [ 2 ] [ 10 ] * SPP [ 7 ] + P [ 3 ] [ 10 ] * SPP [ 6 ] + P [ 10 ] [ 10 ] * SPP [ 5 ] + P [ 11 ] [ 10 ] * SPP [ 4 ] + P [ 12 ] [ 10 ] * SPP [ 3 ] ) + SPP [ 4 ] * ( P [ 0 ] [ 11 ] + P [ 1 ] [ 11 ] * SF [ 6 ] + P [ 2 ] [ 11 ] * SPP [ 7 ] + P [ 3 ] [ 11 ] * SPP [ 6 ] + P [ 10 ] [ 11 ] * SPP [ 5 ] + P [ 11 ] [ 11 ] * SPP [ 4 ] + P [ 12 ] [ 11 ] * SPP [ 3 ] ) + SPP [ 3 ] * ( P [ 0 ] [ 12 ] + P [ 1 ] [ 12 ] * SF [ 6 ] + P [ 2 ] [ 12 ] * SPP [ 7 ] + P [ 3 ] [ 12 ] * SPP [ 6 ] + P [ 10 ] [ 12 ] * SPP [ 5 ] + P [ 11 ] [ 12 ] * SPP [ 4 ] + P [ 12 ] [ 12 ] * SPP [ 3 ] ) + ( dayCov * sq ( q2 ) ) / 4 + ( dazCov * sq ( q3 ) ) / 4 ;
nextP [ 0 ] [ 1 ] = P [ 0 ] [ 1 ] + SQ [ 8 ] + P [ 1 ] [ 1 ] * SF [ 6 ] + P [ 2 ] [ 1 ] * SPP [ 7 ] + P [ 3 ] [ 1 ] * SPP [ 6 ] + P [ 10 ] [ 1 ] * SPP [ 5 ] + P [ 11 ] [ 1 ] * SPP [ 4 ] + P [ 12 ] [ 1 ] * SPP [ 3 ] + SF [ 5 ] * ( P [ 0 ] [ 0 ] + P [ 1 ] [ 0 ] * SF [ 6 ] + P [ 2 ] [ 0 ] * SPP [ 7 ] + P [ 3 ] [ 0 ] * SPP [ 6 ] + P [ 10 ] [ 0 ] * SPP [ 5 ] + P [ 11 ] [ 0 ] * SPP [ 4 ] + P [ 12 ] [ 0 ] * SPP [ 3 ] ) + SF [ 4 ] * ( P [ 0 ] [ 2 ] + P [ 1 ] [ 2 ] * SF [ 6 ] + P [ 2 ] [ 2 ] * SPP [ 7 ] + P [ 3 ] [ 2 ] * SPP [ 6 ] + P [ 10 ] [ 2 ] * SPP [ 5 ] + P [ 11 ] [ 2 ] * SPP [ 4 ] + P [ 12 ] [ 2 ] * SPP [ 3 ] ) + SPP [ 7 ] * ( P [ 0 ] [ 3 ] + P [ 1 ] [ 3 ] * SF [ 6 ] + P [ 2 ] [ 3 ] * SPP [ 7 ] + P [ 3 ] [ 3 ] * SPP [ 6 ] + P [ 10 ] [ 3 ] * SPP [ 5 ] + P [ 11 ] [ 3 ] * SPP [ 4 ] + P [ 12 ] [ 3 ] * SPP [ 3 ] ) + SPP [ 3 ] * ( P [ 0 ] [ 11 ] + P [ 1 ] [ 11 ] * SF [ 6 ] + P [ 2 ] [ 11 ] * SPP [ 7 ] + P [ 3 ] [ 11 ] * SPP [ 6 ] + P [ 10 ] [ 11 ] * SPP [ 5 ] + P [ 11 ] [ 11 ] * SPP [ 4 ] + P [ 12 ] [ 11 ] * SPP [ 3 ] ) - SPP [ 4 ] * ( P [ 0 ] [ 12 ] + P [ 1 ] [ 12 ] * SF [ 6 ] + P [ 2 ] [ 12 ] * SPP [ 7 ] + P [ 3 ] [ 12 ] * SPP [ 6 ] + P [ 10 ] [ 12 ] * SPP [ 5 ] + P [ 11 ] [ 12 ] * SPP [ 4 ] + P [ 12 ] [ 12 ] * SPP [ 3 ] ) - ( q0 * ( P [ 0 ] [ 10 ] + P [ 1 ] [ 10 ] * SF [ 6 ] + P [ 2 ] [ 10 ] * SPP [ 7 ] + P [ 3 ] [ 10 ] * SPP [ 6 ] + P [ 10 ] [ 10 ] * SPP [ 5 ] + P [ 11 ] [ 10 ] * SPP [ 4 ] + P [ 12 ] [ 10 ] * SPP [ 3 ] ) ) / 2 ;
nextP [ 0 ] [ 2 ] = P [ 0 ] [ 2 ] + SQ [ 7 ] + P [ 1 ] [ 2 ] * SF [ 6 ] + P [ 2 ] [ 2 ] * SPP [ 7 ] + P [ 3 ] [ 2 ] * SPP [ 6 ] + P [ 10 ] [ 2 ] * SPP [ 5 ] + P [ 11 ] [ 2 ] * SPP [ 4 ] + P [ 12 ] [ 2 ] * SPP [ 3 ] + SF [ 3 ] * ( P [ 0 ] [ 0 ] + P [ 1 ] [ 0 ] * SF [ 6 ] + P [ 2 ] [ 0 ] * SPP [ 7 ] + P [ 3 ] [ 0 ] * SPP [ 6 ] + P [ 10 ] [ 0 ] * SPP [ 5 ] + P [ 11 ] [ 0 ] * SPP [ 4 ] + P [ 12 ] [ 0 ] * SPP [ 3 ] ) + SF [ 5 ] * ( P [ 0 ] [ 3 ] + P [ 1 ] [ 3 ] * SF [ 6 ] + P [ 2 ] [ 3 ] * SPP [ 7 ] + P [ 3 ] [ 3 ] * SPP [ 6 ] + P [ 10 ] [ 3 ] * SPP [ 5 ] + P [ 11 ] [ 3 ] * SPP [ 4 ] + P [ 12 ] [ 3 ] * SPP [ 3 ] ) + SPP [ 6 ] * ( P [ 0 ] [ 1 ] + P [ 1 ] [ 1 ] * SF [ 6 ] + P [ 2 ] [ 1 ] * SPP [ 7 ] + P [ 3 ] [ 1 ] * SPP [ 6 ] + P [ 10 ] [ 1 ] * SPP [ 5 ] + P [ 11 ] [ 1 ] * SPP [ 4 ] + P [ 12 ] [ 1 ] * SPP [ 3 ] ) - SPP [ 3 ] * ( P [ 0 ] [ 10 ] + P [ 1 ] [ 10 ] * SF [ 6 ] + P [ 2 ] [ 10 ] * SPP [ 7 ] + P [ 3 ] [ 10 ] * SPP [ 6 ] + P [ 10 ] [ 10 ] * SPP [ 5 ] + P [ 11 ] [ 10 ] * SPP [ 4 ] + P [ 12 ] [ 10 ] * SPP [ 3 ] ) + SPP [ 5 ] * ( P [ 0 ] [ 12 ] + P [ 1 ] [ 12 ] * SF [ 6 ] + P [ 2 ] [ 12 ] * SPP [ 7 ] + P [ 3 ] [ 12 ] * SPP [ 6 ] + P [ 10 ] [ 12 ] * SPP [ 5 ] + P [ 11 ] [ 12 ] * SPP [ 4 ] + P [ 12 ] [ 12 ] * SPP [ 3 ] ) - ( q0 * ( P [ 0 ] [ 11 ] + P [ 1 ] [ 11 ] * SF [ 6 ] + P [ 2 ] [ 11 ] * SPP [ 7 ] + P [ 3 ] [ 11 ] * SPP [ 6 ] + P [ 10 ] [ 11 ] * SPP [ 5 ] + P [ 11 ] [ 11 ] * SPP [ 4 ] + P [ 12 ] [ 11 ] * SPP [ 3 ] ) ) / 2 ;
nextP [ 0 ] [ 3 ] = P [ 0 ] [ 3 ] + SQ [ 6 ] + P [ 1 ] [ 3 ] * SF [ 6 ] + P [ 2 ] [ 3 ] * SPP [ 7 ] + P [ 3 ] [ 3 ] * SPP [ 6 ] + P [ 10 ] [ 3 ] * SPP [ 5 ] + P [ 11 ] [ 3 ] * SPP [ 4 ] + P [ 12 ] [ 3 ] * SPP [ 3 ] + SF [ 4 ] * ( P [ 0 ] [ 0 ] + P [ 1 ] [ 0 ] * SF [ 6 ] + P [ 2 ] [ 0 ] * SPP [ 7 ] + P [ 3 ] [ 0 ] * SPP [ 6 ] + P [ 10 ] [ 0 ] * SPP [ 5 ] + P [ 11 ] [ 0 ] * SPP [ 4 ] + P [ 12 ] [ 0 ] * SPP [ 3 ] ) + SF [ 3 ] * ( P [ 0 ] [ 1 ] + P [ 1 ] [ 1 ] * SF [ 6 ] + P [ 2 ] [ 1 ] * SPP [ 7 ] + P [ 3 ] [ 1 ] * SPP [ 6 ] + P [ 10 ] [ 1 ] * SPP [ 5 ] + P [ 11 ] [ 1 ] * SPP [ 4 ] + P [ 12 ] [ 1 ] * SPP [ 3 ] ) + SF [ 6 ] * ( P [ 0 ] [ 2 ] + P [ 1 ] [ 2 ] * SF [ 6 ] + P [ 2 ] [ 2 ] * SPP [ 7 ] + P [ 3 ] [ 2 ] * SPP [ 6 ] + P [ 10 ] [ 2 ] * SPP [ 5 ] + P [ 11 ] [ 2 ] * SPP [ 4 ] + P [ 12 ] [ 2 ] * SPP [ 3 ] ) + SPP [ 4 ] * ( P [ 0 ] [ 10 ] + P [ 1 ] [ 10 ] * SF [ 6 ] + P [ 2 ] [ 10 ] * SPP [ 7 ] + P [ 3 ] [ 10 ] * SPP [ 6 ] + P [ 10 ] [ 10 ] * SPP [ 5 ] + P [ 11 ] [ 10 ] * SPP [ 4 ] + P [ 12 ] [ 10 ] * SPP [ 3 ] ) - SPP [ 5 ] * ( P [ 0 ] [ 11 ] + P [ 1 ] [ 11 ] * SF [ 6 ] + P [ 2 ] [ 11 ] * SPP [ 7 ] + P [ 3 ] [ 11 ] * SPP [ 6 ] + P [ 10 ] [ 11 ] * SPP [ 5 ] + P [ 11 ] [ 11 ] * SPP [ 4 ] + P [ 12 ] [ 11 ] * SPP [ 3 ] ) - ( q0 * ( P [ 0 ] [ 12 ] + P [ 1 ] [ 12 ] * SF [ 6 ] + P [ 2 ] [ 12 ] * SPP [ 7 ] + P [ 3 ] [ 12 ] * SPP [ 6 ] + P [ 10 ] [ 12 ] * SPP [ 5 ] + P [ 11 ] [ 12 ] * SPP [ 4 ] + P [ 12 ] [ 12 ] * SPP [ 3 ] ) ) / 2 ;
nextP [ 0 ] [ 4 ] = P [ 0 ] [ 4 ] + P [ 1 ] [ 4 ] * SF [ 6 ] + P [ 2 ] [ 4 ] * SPP [ 7 ] + P [ 3 ] [ 4 ] * SPP [ 6 ] + P [ 10 ] [ 4 ] * SPP [ 5 ] + P [ 11 ] [ 4 ] * SPP [ 4 ] + P [ 12 ] [ 4 ] * SPP [ 3 ] + SF [ 2 ] * ( P [ 0 ] [ 0 ] + P [ 1 ] [ 0 ] * SF [ 6 ] + P [ 2 ] [ 0 ] * SPP [ 7 ] + P [ 3 ] [ 0 ] * SPP [ 6 ] + P [ 10 ] [ 0 ] * SPP [ 5 ] + P [ 11 ] [ 0 ] * SPP [ 4 ] + P [ 12 ] [ 0 ] * SPP [ 3 ] ) + SF [ 0 ] * ( P [ 0 ] [ 1 ] + P [ 1 ] [ 1 ] * SF [ 6 ] + P [ 2 ] [ 1 ] * SPP [ 7 ] + P [ 3 ] [ 1 ] * SPP [ 6 ] + P [ 10 ] [ 1 ] * SPP [ 5 ] + P [ 11 ] [ 1 ] * SPP [ 4 ] + P [ 12 ] [ 1 ] * SPP [ 3 ] ) + SPP [ 0 ] * ( P [ 0 ] [ 2 ] + P [ 1 ] [ 2 ] * SF [ 6 ] + P [ 2 ] [ 2 ] * SPP [ 7 ] + P [ 3 ] [ 2 ] * SPP [ 6 ] + P [ 10 ] [ 2 ] * SPP [ 5 ] + P [ 11 ] [ 2 ] * SPP [ 4 ] + P [ 12 ] [ 2 ] * SPP [ 3 ] ) - SPP [ 2 ] * ( P [ 0 ] [ 3 ] + P [ 1 ] [ 3 ] * SF [ 6 ] + P [ 2 ] [ 3 ] * SPP [ 7 ] + P [ 3 ] [ 3 ] * SPP [ 6 ] + P [ 10 ] [ 3 ] * SPP [ 5 ] + P [ 11 ] [ 3 ] * SPP [ 4 ] + P [ 12 ] [ 3 ] * SPP [ 3 ] ) ;
nextP [ 0 ] [ 5 ] = P [ 0 ] [ 5 ] + P [ 1 ] [ 5 ] * SF [ 6 ] + P [ 2 ] [ 5 ] * SPP [ 7 ] + P [ 3 ] [ 5 ] * SPP [ 6 ] + P [ 10 ] [ 5 ] * SPP [ 5 ] + P [ 11 ] [ 5 ] * SPP [ 4 ] + P [ 12 ] [ 5 ] * SPP [ 3 ] + SF [ 1 ] * ( P [ 0 ] [ 0 ] + P [ 1 ] [ 0 ] * SF [ 6 ] + P [ 2 ] [ 0 ] * SPP [ 7 ] + P [ 3 ] [ 0 ] * SPP [ 6 ] + P [ 10 ] [ 0 ] * SPP [ 5 ] + P [ 11 ] [ 0 ] * SPP [ 4 ] + P [ 12 ] [ 0 ] * SPP [ 3 ] ) + SF [ 0 ] * ( P [ 0 ] [ 2 ] + P [ 1 ] [ 2 ] * SF [ 6 ] + P [ 2 ] [ 2 ] * SPP [ 7 ] + P [ 3 ] [ 2 ] * SPP [ 6 ] + P [ 10 ] [ 2 ] * SPP [ 5 ] + P [ 11 ] [ 2 ] * SPP [ 4 ] + P [ 12 ] [ 2 ] * SPP [ 3 ] ) + SF [ 2 ] * ( P [ 0 ] [ 3 ] + P [ 1 ] [ 3 ] * SF [ 6 ] + P [ 2 ] [ 3 ] * SPP [ 7 ] + P [ 3 ] [ 3 ] * SPP [ 6 ] + P [ 10 ] [ 3 ] * SPP [ 5 ] + P [ 11 ] [ 3 ] * SPP [ 4 ] + P [ 12 ] [ 3 ] * SPP [ 3 ] ) - SPP [ 0 ] * ( P [ 0 ] [ 1 ] + P [ 1 ] [ 1 ] * SF [ 6 ] + P [ 2 ] [ 1 ] * SPP [ 7 ] + P [ 3 ] [ 1 ] * SPP [ 6 ] + P [ 10 ] [ 1 ] * SPP [ 5 ] + P [ 11 ] [ 1 ] * SPP [ 4 ] + P [ 12 ] [ 1 ] * SPP [ 3 ] ) ;
nextP [ 0 ] [ 6 ] = P [ 0 ] [ 6 ] + P [ 1 ] [ 6 ] * SF [ 6 ] + P [ 2 ] [ 6 ] * SPP [ 7 ] + P [ 3 ] [ 6 ] * SPP [ 6 ] + P [ 10 ] [ 6 ] * SPP [ 5 ] + P [ 11 ] [ 6 ] * SPP [ 4 ] + P [ 12 ] [ 6 ] * SPP [ 3 ] + SF [ 1 ] * ( P [ 0 ] [ 1 ] + P [ 1 ] [ 1 ] * SF [ 6 ] + P [ 2 ] [ 1 ] * SPP [ 7 ] + P [ 3 ] [ 1 ] * SPP [ 6 ] + P [ 10 ] [ 1 ] * SPP [ 5 ] + P [ 11 ] [ 1 ] * SPP [ 4 ] + P [ 12 ] [ 1 ] * SPP [ 3 ] ) + SF [ 0 ] * ( P [ 0 ] [ 3 ] + P [ 1 ] [ 3 ] * SF [ 6 ] + P [ 2 ] [ 3 ] * SPP [ 7 ] + P [ 3 ] [ 3 ] * SPP [ 6 ] + P [ 10 ] [ 3 ] * SPP [ 5 ] + P [ 11 ] [ 3 ] * SPP [ 4 ] + P [ 12 ] [ 3 ] * SPP [ 3 ] ) + SPP [ 0 ] * ( P [ 0 ] [ 0 ] + P [ 1 ] [ 0 ] * SF [ 6 ] + P [ 2 ] [ 0 ] * SPP [ 7 ] + P [ 3 ] [ 0 ] * SPP [ 6 ] + P [ 10 ] [ 0 ] * SPP [ 5 ] + P [ 11 ] [ 0 ] * SPP [ 4 ] + P [ 12 ] [ 0 ] * SPP [ 3 ] ) - SPP [ 1 ] * ( P [ 0 ] [ 2 ] + P [ 1 ] [ 2 ] * SF [ 6 ] + P [ 2 ] [ 2 ] * SPP [ 7 ] + P [ 3 ] [ 2 ] * SPP [ 6 ] + P [ 10 ] [ 2 ] * SPP [ 5 ] + P [ 11 ] [ 2 ] * SPP [ 4 ] + P [ 12 ] [ 2 ] * SPP [ 3 ] ) ;
nextP [ 0 ] [ 7 ] = P [ 0 ] [ 7 ] + P [ 1 ] [ 7 ] * SF [ 6 ] + P [ 2 ] [ 7 ] * SPP [ 7 ] + P [ 3 ] [ 7 ] * SPP [ 6 ] + P [ 10 ] [ 7 ] * SPP [ 5 ] + P [ 11 ] [ 7 ] * SPP [ 4 ] + P [ 12 ] [ 7 ] * SPP [ 3 ] + dt * ( P [ 0 ] [ 4 ] + P [ 1 ] [ 4 ] * SF [ 6 ] + P [ 2 ] [ 4 ] * SPP [ 7 ] + P [ 3 ] [ 4 ] * SPP [ 6 ] + P [ 10 ] [ 4 ] * SPP [ 5 ] + P [ 11 ] [ 4 ] * SPP [ 4 ] + P [ 12 ] [ 4 ] * SPP [ 3 ] ) ;
nextP [ 0 ] [ 8 ] = P [ 0 ] [ 8 ] + P [ 1 ] [ 8 ] * SF [ 6 ] + P [ 2 ] [ 8 ] * SPP [ 7 ] + P [ 3 ] [ 8 ] * SPP [ 6 ] + P [ 10 ] [ 8 ] * SPP [ 5 ] + P [ 11 ] [ 8 ] * SPP [ 4 ] + P [ 12 ] [ 8 ] * SPP [ 3 ] + dt * ( P [ 0 ] [ 5 ] + P [ 1 ] [ 5 ] * SF [ 6 ] + P [ 2 ] [ 5 ] * SPP [ 7 ] + P [ 3 ] [ 5 ] * SPP [ 6 ] + P [ 10 ] [ 5 ] * SPP [ 5 ] + P [ 11 ] [ 5 ] * SPP [ 4 ] + P [ 12 ] [ 5 ] * SPP [ 3 ] ) ;
nextP [ 0 ] [ 9 ] = P [ 0 ] [ 9 ] + P [ 1 ] [ 9 ] * SF [ 6 ] + P [ 2 ] [ 9 ] * SPP [ 7 ] + P [ 3 ] [ 9 ] * SPP [ 6 ] + P [ 10 ] [ 9 ] * SPP [ 5 ] + P [ 11 ] [ 9 ] * SPP [ 4 ] + P [ 12 ] [ 9 ] * SPP [ 3 ] + dt * ( P [ 0 ] [ 6 ] + P [ 1 ] [ 6 ] * SF [ 6 ] + P [ 2 ] [ 6 ] * SPP [ 7 ] + P [ 3 ] [ 6 ] * SPP [ 6 ] + P [ 10 ] [ 6 ] * SPP [ 5 ] + P [ 11 ] [ 6 ] * SPP [ 4 ] + P [ 12 ] [ 6 ] * SPP [ 3 ] ) ;
nextP [ 0 ] [ 10 ] = P [ 0 ] [ 10 ] + P [ 1 ] [ 10 ] * SF [ 6 ] + P [ 2 ] [ 10 ] * SPP [ 7 ] + P [ 3 ] [ 10 ] * SPP [ 6 ] + P [ 10 ] [ 10 ] * SPP [ 5 ] + P [ 11 ] [ 10 ] * SPP [ 4 ] + P [ 12 ] [ 10 ] * SPP [ 3 ] ;
nextP [ 0 ] [ 11 ] = P [ 0 ] [ 11 ] + P [ 1 ] [ 11 ] * SF [ 6 ] + P [ 2 ] [ 11 ] * SPP [ 7 ] + P [ 3 ] [ 11 ] * SPP [ 6 ] + P [ 10 ] [ 11 ] * SPP [ 5 ] + P [ 11 ] [ 11 ] * SPP [ 4 ] + P [ 12 ] [ 11 ] * SPP [ 3 ] ;
nextP [ 0 ] [ 12 ] = P [ 0 ] [ 12 ] + P [ 1 ] [ 12 ] * SF [ 6 ] + P [ 2 ] [ 12 ] * SPP [ 7 ] + P [ 3 ] [ 12 ] * SPP [ 6 ] + P [ 10 ] [ 12 ] * SPP [ 5 ] + P [ 11 ] [ 12 ] * SPP [ 4 ] + P [ 12 ] [ 12 ] * SPP [ 3 ] ;
nextP [ 0 ] [ 13 ] = P [ 0 ] [ 13 ] + P [ 1 ] [ 13 ] * SF [ 6 ] + P [ 2 ] [ 13 ] * SPP [ 7 ] + P [ 3 ] [ 13 ] * SPP [ 6 ] + P [ 10 ] [ 13 ] * SPP [ 5 ] + P [ 11 ] [ 13 ] * SPP [ 4 ] + P [ 12 ] [ 13 ] * SPP [ 3 ] ;
nextP [ 0 ] [ 14 ] = P [ 0 ] [ 14 ] + P [ 1 ] [ 14 ] * SF [ 6 ] + P [ 2 ] [ 14 ] * SPP [ 7 ] + P [ 3 ] [ 14 ] * SPP [ 6 ] + P [ 10 ] [ 14 ] * SPP [ 5 ] + P [ 11 ] [ 14 ] * SPP [ 4 ] + P [ 12 ] [ 14 ] * SPP [ 3 ] ;
nextP [ 0 ] [ 15 ] = P [ 0 ] [ 15 ] + P [ 1 ] [ 15 ] * SF [ 6 ] + P [ 2 ] [ 15 ] * SPP [ 7 ] + P [ 3 ] [ 15 ] * SPP [ 6 ] + P [ 10 ] [ 15 ] * SPP [ 5 ] + P [ 11 ] [ 15 ] * SPP [ 4 ] + P [ 12 ] [ 15 ] * SPP [ 3 ] ;
nextP [ 0 ] [ 16 ] = P [ 0 ] [ 16 ] + P [ 1 ] [ 16 ] * SF [ 6 ] + P [ 2 ] [ 16 ] * SPP [ 7 ] + P [ 3 ] [ 16 ] * SPP [ 6 ] + P [ 10 ] [ 16 ] * SPP [ 5 ] + P [ 11 ] [ 16 ] * SPP [ 4 ] + P [ 12 ] [ 16 ] * SPP [ 3 ] ;
nextP [ 0 ] [ 17 ] = P [ 0 ] [ 17 ] + P [ 1 ] [ 17 ] * SF [ 6 ] + P [ 2 ] [ 17 ] * SPP [ 7 ] + P [ 3 ] [ 17 ] * SPP [ 6 ] + P [ 10 ] [ 17 ] * SPP [ 5 ] + P [ 11 ] [ 17 ] * SPP [ 4 ] + P [ 12 ] [ 17 ] * SPP [ 3 ] ;
nextP [ 0 ] [ 18 ] = P [ 0 ] [ 18 ] + P [ 1 ] [ 18 ] * SF [ 6 ] + P [ 2 ] [ 18 ] * SPP [ 7 ] + P [ 3 ] [ 18 ] * SPP [ 6 ] + P [ 10 ] [ 18 ] * SPP [ 5 ] + P [ 11 ] [ 18 ] * SPP [ 4 ] + P [ 12 ] [ 18 ] * SPP [ 3 ] ;
nextP [ 0 ] [ 19 ] = P [ 0 ] [ 19 ] + P [ 1 ] [ 19 ] * SF [ 6 ] + P [ 2 ] [ 19 ] * SPP [ 7 ] + P [ 3 ] [ 19 ] * SPP [ 6 ] + P [ 10 ] [ 19 ] * SPP [ 5 ] + P [ 11 ] [ 19 ] * SPP [ 4 ] + P [ 12 ] [ 19 ] * SPP [ 3 ] ;
nextP [ 0 ] [ 20 ] = P [ 0 ] [ 20 ] + P [ 1 ] [ 20 ] * SF [ 6 ] + P [ 2 ] [ 20 ] * SPP [ 7 ] + P [ 3 ] [ 20 ] * SPP [ 6 ] + P [ 10 ] [ 20 ] * SPP [ 5 ] + P [ 11 ] [ 20 ] * SPP [ 4 ] + P [ 12 ] [ 20 ] * SPP [ 3 ] ;
nextP [ 1 ] [ 0 ] = P [ 1 ] [ 0 ] + SQ [ 8 ] + P [ 0 ] [ 0 ] * SF [ 5 ] + P [ 2 ] [ 0 ] * SF [ 4 ] + P [ 3 ] [ 0 ] * SPP [ 7 ] + P [ 11 ] [ 0 ] * SPP [ 3 ] - P [ 12 ] [ 0 ] * SPP [ 4 ] - ( P [ 10 ] [ 0 ] * q0 ) / 2 + SF [ 6 ] * ( P [ 1 ] [ 1 ] + P [ 0 ] [ 1 ] * SF [ 5 ] + P [ 2 ] [ 1 ] * SF [ 4 ] + P [ 3 ] [ 1 ] * SPP [ 7 ] + P [ 11 ] [ 1 ] * SPP [ 3 ] - P [ 12 ] [ 1 ] * SPP [ 4 ] - ( P [ 10 ] [ 1 ] * q0 ) / 2 ) + SPP [ 7 ] * ( P [ 1 ] [ 2 ] + P [ 0 ] [ 2 ] * SF [ 5 ] + P [ 2 ] [ 2 ] * SF [ 4 ] + P [ 3 ] [ 2 ] * SPP [ 7 ] + P [ 11 ] [ 2 ] * SPP [ 3 ] - P [ 12 ] [ 2 ] * SPP [ 4 ] - ( P [ 10 ] [ 2 ] * q0 ) / 2 ) + SPP [ 6 ] * ( P [ 1 ] [ 3 ] + P [ 0 ] [ 3 ] * SF [ 5 ] + P [ 2 ] [ 3 ] * SF [ 4 ] + P [ 3 ] [ 3 ] * SPP [ 7 ] + P [ 11 ] [ 3 ] * SPP [ 3 ] - P [ 12 ] [ 3 ] * SPP [ 4 ] - ( P [ 10 ] [ 3 ] * q0 ) / 2 ) + SPP [ 5 ] * ( P [ 1 ] [ 10 ] + P [ 0 ] [ 10 ] * SF [ 5 ] + P [ 2 ] [ 10 ] * SF [ 4 ] + P [ 3 ] [ 10 ] * SPP [ 7 ] + P [ 11 ] [ 10 ] * SPP [ 3 ] - P [ 12 ] [ 10 ] * SPP [ 4 ] - ( P [ 10 ] [ 10 ] * q0 ) / 2 ) + SPP [ 4 ] * ( P [ 1 ] [ 11 ] + P [ 0 ] [ 11 ] * SF [ 5 ] + P [ 2 ] [ 11 ] * SF [ 4 ] + P [ 3 ] [ 11 ] * SPP [ 7 ] + P [ 11 ] [ 11 ] * SPP [ 3 ] - P [ 12 ] [ 11 ] * SPP [ 4 ] - ( P [ 10 ] [ 11 ] * q0 ) / 2 ) + SPP [ 3 ] * ( P [ 1 ] [ 12 ] + P [ 0 ] [ 12 ] * SF [ 5 ] + P [ 2 ] [ 12 ] * SF [ 4 ] + P [ 3 ] [ 12 ] * SPP [ 7 ] + P [ 11 ] [ 12 ] * SPP [ 3 ] - P [ 12 ] [ 12 ] * SPP [ 4 ] - ( P [ 10 ] [ 12 ] * q0 ) / 2 ) ;
nextP [ 1 ] [ 1 ] = P [ 1 ] [ 1 ] + P [ 0 ] [ 1 ] * SF [ 5 ] + P [ 2 ] [ 1 ] * SF [ 4 ] + P [ 3 ] [ 1 ] * SPP [ 7 ] + P [ 11 ] [ 1 ] * SPP [ 3 ] - P [ 12 ] [ 1 ] * SPP [ 4 ] + daxCov * SQ [ 9 ] - ( P [ 10 ] [ 1 ] * q0 ) / 2 + SF [ 5 ] * ( P [ 1 ] [ 0 ] + P [ 0 ] [ 0 ] * SF [ 5 ] + P [ 2 ] [ 0 ] * SF [ 4 ] + P [ 3 ] [ 0 ] * SPP [ 7 ] + P [ 11 ] [ 0 ] * SPP [ 3 ] - P [ 12 ] [ 0 ] * SPP [ 4 ] - ( P [ 10 ] [ 0 ] * q0 ) / 2 ) + SF [ 4 ] * ( P [ 1 ] [ 2 ] + P [ 0 ] [ 2 ] * SF [ 5 ] + P [ 2 ] [ 2 ] * SF [ 4 ] + P [ 3 ] [ 2 ] * SPP [ 7 ] + P [ 11 ] [ 2 ] * SPP [ 3 ] - P [ 12 ] [ 2 ] * SPP [ 4 ] - ( P [ 10 ] [ 2 ] * q0 ) / 2 ) + SPP [ 7 ] * ( P [ 1 ] [ 3 ] + P [ 0 ] [ 3 ] * SF [ 5 ] + P [ 2 ] [ 3 ] * SF [ 4 ] + P [ 3 ] [ 3 ] * SPP [ 7 ] + P [ 11 ] [ 3 ] * SPP [ 3 ] - P [ 12 ] [ 3 ] * SPP [ 4 ] - ( P [ 10 ] [ 3 ] * q0 ) / 2 ) + SPP [ 3 ] * ( P [ 1 ] [ 11 ] + P [ 0 ] [ 11 ] * SF [ 5 ] + P [ 2 ] [ 11 ] * SF [ 4 ] + P [ 3 ] [ 11 ] * SPP [ 7 ] + P [ 11 ] [ 11 ] * SPP [ 3 ] - P [ 12 ] [ 11 ] * SPP [ 4 ] - ( P [ 10 ] [ 11 ] * q0 ) / 2 ) - SPP [ 4 ] * ( P [ 1 ] [ 12 ] + P [ 0 ] [ 12 ] * SF [ 5 ] + P [ 2 ] [ 12 ] * SF [ 4 ] + P [ 3 ] [ 12 ] * SPP [ 7 ] + P [ 11 ] [ 12 ] * SPP [ 3 ] - P [ 12 ] [ 12 ] * SPP [ 4 ] - ( P [ 10 ] [ 12 ] * q0 ) / 2 ) + ( dayCov * sq ( q3 ) ) / 4 + ( dazCov * sq ( q2 ) ) / 4 - ( q0 * ( P [ 1 ] [ 10 ] + P [ 0 ] [ 10 ] * SF [ 5 ] + P [ 2 ] [ 10 ] * SF [ 4 ] + P [ 3 ] [ 10 ] * SPP [ 7 ] + P [ 11 ] [ 10 ] * SPP [ 3 ] - P [ 12 ] [ 10 ] * SPP [ 4 ] - ( P [ 10 ] [ 10 ] * q0 ) / 2 ) ) / 2 ;
nextP [ 1 ] [ 2 ] = P [ 1 ] [ 2 ] + SQ [ 5 ] + P [ 0 ] [ 2 ] * SF [ 5 ] + P [ 2 ] [ 2 ] * SF [ 4 ] + P [ 3 ] [ 2 ] * SPP [ 7 ] + P [ 11 ] [ 2 ] * SPP [ 3 ] - P [ 12 ] [ 2 ] * SPP [ 4 ] - ( P [ 10 ] [ 2 ] * q0 ) / 2 + SF [ 3 ] * ( P [ 1 ] [ 0 ] + P [ 0 ] [ 0 ] * SF [ 5 ] + P [ 2 ] [ 0 ] * SF [ 4 ] + P [ 3 ] [ 0 ] * SPP [ 7 ] + P [ 11 ] [ 0 ] * SPP [ 3 ] - P [ 12 ] [ 0 ] * SPP [ 4 ] - ( P [ 10 ] [ 0 ] * q0 ) / 2 ) + SF [ 5 ] * ( P [ 1 ] [ 3 ] + P [ 0 ] [ 3 ] * SF [ 5 ] + P [ 2 ] [ 3 ] * SF [ 4 ] + P [ 3 ] [ 3 ] * SPP [ 7 ] + P [ 11 ] [ 3 ] * SPP [ 3 ] - P [ 12 ] [ 3 ] * SPP [ 4 ] - ( P [ 10 ] [ 3 ] * q0 ) / 2 ) + SPP [ 6 ] * ( P [ 1 ] [ 1 ] + P [ 0 ] [ 1 ] * SF [ 5 ] + P [ 2 ] [ 1 ] * SF [ 4 ] + P [ 3 ] [ 1 ] * SPP [ 7 ] + P [ 11 ] [ 1 ] * SPP [ 3 ] - P [ 12 ] [ 1 ] * SPP [ 4 ] - ( P [ 10 ] [ 1 ] * q0 ) / 2 ) - SPP [ 3 ] * ( P [ 1 ] [ 10 ] + P [ 0 ] [ 10 ] * SF [ 5 ] + P [ 2 ] [ 10 ] * SF [ 4 ] + P [ 3 ] [ 10 ] * SPP [ 7 ] + P [ 11 ] [ 10 ] * SPP [ 3 ] - P [ 12 ] [ 10 ] * SPP [ 4 ] - ( P [ 10 ] [ 10 ] * q0 ) / 2 ) + SPP [ 5 ] * ( P [ 1 ] [ 12 ] + P [ 0 ] [ 12 ] * SF [ 5 ] + P [ 2 ] [ 12 ] * SF [ 4 ] + P [ 3 ] [ 12 ] * SPP [ 7 ] + P [ 11 ] [ 12 ] * SPP [ 3 ] - P [ 12 ] [ 12 ] * SPP [ 4 ] - ( P [ 10 ] [ 12 ] * q0 ) / 2 ) - ( q0 * ( P [ 1 ] [ 11 ] + P [ 0 ] [ 11 ] * SF [ 5 ] + P [ 2 ] [ 11 ] * SF [ 4 ] + P [ 3 ] [ 11 ] * SPP [ 7 ] + P [ 11 ] [ 11 ] * SPP [ 3 ] - P [ 12 ] [ 11 ] * SPP [ 4 ] - ( P [ 10 ] [ 11 ] * q0 ) / 2 ) ) / 2 ;
nextP [ 1 ] [ 3 ] = P [ 1 ] [ 3 ] + SQ [ 4 ] + P [ 0 ] [ 3 ] * SF [ 5 ] + P [ 2 ] [ 3 ] * SF [ 4 ] + P [ 3 ] [ 3 ] * SPP [ 7 ] + P [ 11 ] [ 3 ] * SPP [ 3 ] - P [ 12 ] [ 3 ] * SPP [ 4 ] - ( P [ 10 ] [ 3 ] * q0 ) / 2 + SF [ 4 ] * ( P [ 1 ] [ 0 ] + P [ 0 ] [ 0 ] * SF [ 5 ] + P [ 2 ] [ 0 ] * SF [ 4 ] + P [ 3 ] [ 0 ] * SPP [ 7 ] + P [ 11 ] [ 0 ] * SPP [ 3 ] - P [ 12 ] [ 0 ] * SPP [ 4 ] - ( P [ 10 ] [ 0 ] * q0 ) / 2 ) + SF [ 3 ] * ( P [ 1 ] [ 1 ] + P [ 0 ] [ 1 ] * SF [ 5 ] + P [ 2 ] [ 1 ] * SF [ 4 ] + P [ 3 ] [ 1 ] * SPP [ 7 ] + P [ 11 ] [ 1 ] * SPP [ 3 ] - P [ 12 ] [ 1 ] * SPP [ 4 ] - ( P [ 10 ] [ 1 ] * q0 ) / 2 ) + SF [ 6 ] * ( P [ 1 ] [ 2 ] + P [ 0 ] [ 2 ] * SF [ 5 ] + P [ 2 ] [ 2 ] * SF [ 4 ] + P [ 3 ] [ 2 ] * SPP [ 7 ] + P [ 11 ] [ 2 ] * SPP [ 3 ] - P [ 12 ] [ 2 ] * SPP [ 4 ] - ( P [ 10 ] [ 2 ] * q0 ) / 2 ) + SPP [ 4 ] * ( P [ 1 ] [ 10 ] + P [ 0 ] [ 10 ] * SF [ 5 ] + P [ 2 ] [ 10 ] * SF [ 4 ] + P [ 3 ] [ 10 ] * SPP [ 7 ] + P [ 11 ] [ 10 ] * SPP [ 3 ] - P [ 12 ] [ 10 ] * SPP [ 4 ] - ( P [ 10 ] [ 10 ] * q0 ) / 2 ) - SPP [ 5 ] * ( P [ 1 ] [ 11 ] + P [ 0 ] [ 11 ] * SF [ 5 ] + P [ 2 ] [ 11 ] * SF [ 4 ] + P [ 3 ] [ 11 ] * SPP [ 7 ] + P [ 11 ] [ 11 ] * SPP [ 3 ] - P [ 12 ] [ 11 ] * SPP [ 4 ] - ( P [ 10 ] [ 11 ] * q0 ) / 2 ) - ( q0 * ( P [ 1 ] [ 12 ] + P [ 0 ] [ 12 ] * SF [ 5 ] + P [ 2 ] [ 12 ] * SF [ 4 ] + P [ 3 ] [ 12 ] * SPP [ 7 ] + P [ 11 ] [ 12 ] * SPP [ 3 ] - P [ 12 ] [ 12 ] * SPP [ 4 ] - ( P [ 10 ] [ 12 ] * q0 ) / 2 ) ) / 2 ;
nextP [ 1 ] [ 4 ] = P [ 1 ] [ 4 ] + P [ 0 ] [ 4 ] * SF [ 5 ] + P [ 2 ] [ 4 ] * SF [ 4 ] + P [ 3 ] [ 4 ] * SPP [ 7 ] + P [ 11 ] [ 4 ] * SPP [ 3 ] - P [ 12 ] [ 4 ] * SPP [ 4 ] - ( P [ 10 ] [ 4 ] * q0 ) / 2 + SF [ 2 ] * ( P [ 1 ] [ 0 ] + P [ 0 ] [ 0 ] * SF [ 5 ] + P [ 2 ] [ 0 ] * SF [ 4 ] + P [ 3 ] [ 0 ] * SPP [ 7 ] + P [ 11 ] [ 0 ] * SPP [ 3 ] - P [ 12 ] [ 0 ] * SPP [ 4 ] - ( P [ 10 ] [ 0 ] * q0 ) / 2 ) + SF [ 0 ] * ( P [ 1 ] [ 1 ] + P [ 0 ] [ 1 ] * SF [ 5 ] + P [ 2 ] [ 1 ] * SF [ 4 ] + P [ 3 ] [ 1 ] * SPP [ 7 ] + P [ 11 ] [ 1 ] * SPP [ 3 ] - P [ 12 ] [ 1 ] * SPP [ 4 ] - ( P [ 10 ] [ 1 ] * q0 ) / 2 ) + SPP [ 0 ] * ( P [ 1 ] [ 2 ] + P [ 0 ] [ 2 ] * SF [ 5 ] + P [ 2 ] [ 2 ] * SF [ 4 ] + P [ 3 ] [ 2 ] * SPP [ 7 ] + P [ 11 ] [ 2 ] * SPP [ 3 ] - P [ 12 ] [ 2 ] * SPP [ 4 ] - ( P [ 10 ] [ 2 ] * q0 ) / 2 ) - SPP [ 2 ] * ( P [ 1 ] [ 3 ] + P [ 0 ] [ 3 ] * SF [ 5 ] + P [ 2 ] [ 3 ] * SF [ 4 ] + P [ 3 ] [ 3 ] * SPP [ 7 ] + P [ 11 ] [ 3 ] * SPP [ 3 ] - P [ 12 ] [ 3 ] * SPP [ 4 ] - ( P [ 10 ] [ 3 ] * q0 ) / 2 ) ;
nextP [ 1 ] [ 5 ] = P [ 1 ] [ 5 ] + P [ 0 ] [ 5 ] * SF [ 5 ] + P [ 2 ] [ 5 ] * SF [ 4 ] + P [ 3 ] [ 5 ] * SPP [ 7 ] + P [ 11 ] [ 5 ] * SPP [ 3 ] - P [ 12 ] [ 5 ] * SPP [ 4 ] - ( P [ 10 ] [ 5 ] * q0 ) / 2 + SF [ 1 ] * ( P [ 1 ] [ 0 ] + P [ 0 ] [ 0 ] * SF [ 5 ] + P [ 2 ] [ 0 ] * SF [ 4 ] + P [ 3 ] [ 0 ] * SPP [ 7 ] + P [ 11 ] [ 0 ] * SPP [ 3 ] - P [ 12 ] [ 0 ] * SPP [ 4 ] - ( P [ 10 ] [ 0 ] * q0 ) / 2 ) + SF [ 0 ] * ( P [ 1 ] [ 2 ] + P [ 0 ] [ 2 ] * SF [ 5 ] + P [ 2 ] [ 2 ] * SF [ 4 ] + P [ 3 ] [ 2 ] * SPP [ 7 ] + P [ 11 ] [ 2 ] * SPP [ 3 ] - P [ 12 ] [ 2 ] * SPP [ 4 ] - ( P [ 10 ] [ 2 ] * q0 ) / 2 ) + SF [ 2 ] * ( P [ 1 ] [ 3 ] + P [ 0 ] [ 3 ] * SF [ 5 ] + P [ 2 ] [ 3 ] * SF [ 4 ] + P [ 3 ] [ 3 ] * SPP [ 7 ] + P [ 11 ] [ 3 ] * SPP [ 3 ] - P [ 12 ] [ 3 ] * SPP [ 4 ] - ( P [ 10 ] [ 3 ] * q0 ) / 2 ) - SPP [ 0 ] * ( P [ 1 ] [ 1 ] + P [ 0 ] [ 1 ] * SF [ 5 ] + P [ 2 ] [ 1 ] * SF [ 4 ] + P [ 3 ] [ 1 ] * SPP [ 7 ] + P [ 11 ] [ 1 ] * SPP [ 3 ] - P [ 12 ] [ 1 ] * SPP [ 4 ] - ( P [ 10 ] [ 1 ] * q0 ) / 2 ) ;
nextP [ 1 ] [ 6 ] = P [ 1 ] [ 6 ] + P [ 0 ] [ 6 ] * SF [ 5 ] + P [ 2 ] [ 6 ] * SF [ 4 ] + P [ 3 ] [ 6 ] * SPP [ 7 ] + P [ 11 ] [ 6 ] * SPP [ 3 ] - P [ 12 ] [ 6 ] * SPP [ 4 ] - ( P [ 10 ] [ 6 ] * q0 ) / 2 + SF [ 1 ] * ( P [ 1 ] [ 1 ] + P [ 0 ] [ 1 ] * SF [ 5 ] + P [ 2 ] [ 1 ] * SF [ 4 ] + P [ 3 ] [ 1 ] * SPP [ 7 ] + P [ 11 ] [ 1 ] * SPP [ 3 ] - P [ 12 ] [ 1 ] * SPP [ 4 ] - ( P [ 10 ] [ 1 ] * q0 ) / 2 ) + SF [ 0 ] * ( P [ 1 ] [ 3 ] + P [ 0 ] [ 3 ] * SF [ 5 ] + P [ 2 ] [ 3 ] * SF [ 4 ] + P [ 3 ] [ 3 ] * SPP [ 7 ] + P [ 11 ] [ 3 ] * SPP [ 3 ] - P [ 12 ] [ 3 ] * SPP [ 4 ] - ( P [ 10 ] [ 3 ] * q0 ) / 2 ) + SPP [ 0 ] * ( P [ 1 ] [ 0 ] + P [ 0 ] [ 0 ] * SF [ 5 ] + P [ 2 ] [ 0 ] * SF [ 4 ] + P [ 3 ] [ 0 ] * SPP [ 7 ] + P [ 11 ] [ 0 ] * SPP [ 3 ] - P [ 12 ] [ 0 ] * SPP [ 4 ] - ( P [ 10 ] [ 0 ] * q0 ) / 2 ) - SPP [ 1 ] * ( P [ 1 ] [ 2 ] + P [ 0 ] [ 2 ] * SF [ 5 ] + P [ 2 ] [ 2 ] * SF [ 4 ] + P [ 3 ] [ 2 ] * SPP [ 7 ] + P [ 11 ] [ 2 ] * SPP [ 3 ] - P [ 12 ] [ 2 ] * SPP [ 4 ] - ( P [ 10 ] [ 2 ] * q0 ) / 2 ) ;
nextP [ 1 ] [ 7 ] = P [ 1 ] [ 7 ] + P [ 0 ] [ 7 ] * SF [ 5 ] + P [ 2 ] [ 7 ] * SF [ 4 ] + P [ 3 ] [ 7 ] * SPP [ 7 ] + P [ 11 ] [ 7 ] * SPP [ 3 ] - P [ 12 ] [ 7 ] * SPP [ 4 ] - ( P [ 10 ] [ 7 ] * q0 ) / 2 + dt * ( P [ 1 ] [ 4 ] + P [ 0 ] [ 4 ] * SF [ 5 ] + P [ 2 ] [ 4 ] * SF [ 4 ] + P [ 3 ] [ 4 ] * SPP [ 7 ] + P [ 11 ] [ 4 ] * SPP [ 3 ] - P [ 12 ] [ 4 ] * SPP [ 4 ] - ( P [ 10 ] [ 4 ] * q0 ) / 2 ) ;
nextP [ 1 ] [ 8 ] = P [ 1 ] [ 8 ] + P [ 0 ] [ 8 ] * SF [ 5 ] + P [ 2 ] [ 8 ] * SF [ 4 ] + P [ 3 ] [ 8 ] * SPP [ 7 ] + P [ 11 ] [ 8 ] * SPP [ 3 ] - P [ 12 ] [ 8 ] * SPP [ 4 ] - ( P [ 10 ] [ 8 ] * q0 ) / 2 + dt * ( P [ 1 ] [ 5 ] + P [ 0 ] [ 5 ] * SF [ 5 ] + P [ 2 ] [ 5 ] * SF [ 4 ] + P [ 3 ] [ 5 ] * SPP [ 7 ] + P [ 11 ] [ 5 ] * SPP [ 3 ] - P [ 12 ] [ 5 ] * SPP [ 4 ] - ( P [ 10 ] [ 5 ] * q0 ) / 2 ) ;
nextP [ 1 ] [ 9 ] = P [ 1 ] [ 9 ] + P [ 0 ] [ 9 ] * SF [ 5 ] + P [ 2 ] [ 9 ] * SF [ 4 ] + P [ 3 ] [ 9 ] * SPP [ 7 ] + P [ 11 ] [ 9 ] * SPP [ 3 ] - P [ 12 ] [ 9 ] * SPP [ 4 ] - ( P [ 10 ] [ 9 ] * q0 ) / 2 + dt * ( P [ 1 ] [ 6 ] + P [ 0 ] [ 6 ] * SF [ 5 ] + P [ 2 ] [ 6 ] * SF [ 4 ] + P [ 3 ] [ 6 ] * SPP [ 7 ] + P [ 11 ] [ 6 ] * SPP [ 3 ] - P [ 12 ] [ 6 ] * SPP [ 4 ] - ( P [ 10 ] [ 6 ] * q0 ) / 2 ) ;
nextP [ 1 ] [ 10 ] = P [ 1 ] [ 10 ] + P [ 0 ] [ 10 ] * SF [ 5 ] + P [ 2 ] [ 10 ] * SF [ 4 ] + P [ 3 ] [ 10 ] * SPP [ 7 ] + P [ 11 ] [ 10 ] * SPP [ 3 ] - P [ 12 ] [ 10 ] * SPP [ 4 ] - ( P [ 10 ] [ 10 ] * q0 ) / 2 ;
nextP [ 1 ] [ 11 ] = P [ 1 ] [ 11 ] + P [ 0 ] [ 11 ] * SF [ 5 ] + P [ 2 ] [ 11 ] * SF [ 4 ] + P [ 3 ] [ 11 ] * SPP [ 7 ] + P [ 11 ] [ 11 ] * SPP [ 3 ] - P [ 12 ] [ 11 ] * SPP [ 4 ] - ( P [ 10 ] [ 11 ] * q0 ) / 2 ;
nextP [ 1 ] [ 12 ] = P [ 1 ] [ 12 ] + P [ 0 ] [ 12 ] * SF [ 5 ] + P [ 2 ] [ 12 ] * SF [ 4 ] + P [ 3 ] [ 12 ] * SPP [ 7 ] + P [ 11 ] [ 12 ] * SPP [ 3 ] - P [ 12 ] [ 12 ] * SPP [ 4 ] - ( P [ 10 ] [ 12 ] * q0 ) / 2 ;
nextP [ 1 ] [ 13 ] = P [ 1 ] [ 13 ] + P [ 0 ] [ 13 ] * SF [ 5 ] + P [ 2 ] [ 13 ] * SF [ 4 ] + P [ 3 ] [ 13 ] * SPP [ 7 ] + P [ 11 ] [ 13 ] * SPP [ 3 ] - P [ 12 ] [ 13 ] * SPP [ 4 ] - ( P [ 10 ] [ 13 ] * q0 ) / 2 ;
nextP [ 1 ] [ 14 ] = P [ 1 ] [ 14 ] + P [ 0 ] [ 14 ] * SF [ 5 ] + P [ 2 ] [ 14 ] * SF [ 4 ] + P [ 3 ] [ 14 ] * SPP [ 7 ] + P [ 11 ] [ 14 ] * SPP [ 3 ] - P [ 12 ] [ 14 ] * SPP [ 4 ] - ( P [ 10 ] [ 14 ] * q0 ) / 2 ;
nextP [ 1 ] [ 15 ] = P [ 1 ] [ 15 ] + P [ 0 ] [ 15 ] * SF [ 5 ] + P [ 2 ] [ 15 ] * SF [ 4 ] + P [ 3 ] [ 15 ] * SPP [ 7 ] + P [ 11 ] [ 15 ] * SPP [ 3 ] - P [ 12 ] [ 15 ] * SPP [ 4 ] - ( P [ 10 ] [ 15 ] * q0 ) / 2 ;
nextP [ 1 ] [ 16 ] = P [ 1 ] [ 16 ] + P [ 0 ] [ 16 ] * SF [ 5 ] + P [ 2 ] [ 16 ] * SF [ 4 ] + P [ 3 ] [ 16 ] * SPP [ 7 ] + P [ 11 ] [ 16 ] * SPP [ 3 ] - P [ 12 ] [ 16 ] * SPP [ 4 ] - ( P [ 10 ] [ 16 ] * q0 ) / 2 ;
nextP [ 1 ] [ 17 ] = P [ 1 ] [ 17 ] + P [ 0 ] [ 17 ] * SF [ 5 ] + P [ 2 ] [ 17 ] * SF [ 4 ] + P [ 3 ] [ 17 ] * SPP [ 7 ] + P [ 11 ] [ 17 ] * SPP [ 3 ] - P [ 12 ] [ 17 ] * SPP [ 4 ] - ( P [ 10 ] [ 17 ] * q0 ) / 2 ;
nextP [ 1 ] [ 18 ] = P [ 1 ] [ 18 ] + P [ 0 ] [ 18 ] * SF [ 5 ] + P [ 2 ] [ 18 ] * SF [ 4 ] + P [ 3 ] [ 18 ] * SPP [ 7 ] + P [ 11 ] [ 18 ] * SPP [ 3 ] - P [ 12 ] [ 18 ] * SPP [ 4 ] - ( P [ 10 ] [ 18 ] * q0 ) / 2 ;
nextP [ 1 ] [ 19 ] = P [ 1 ] [ 19 ] + P [ 0 ] [ 19 ] * SF [ 5 ] + P [ 2 ] [ 19 ] * SF [ 4 ] + P [ 3 ] [ 19 ] * SPP [ 7 ] + P [ 11 ] [ 19 ] * SPP [ 3 ] - P [ 12 ] [ 19 ] * SPP [ 4 ] - ( P [ 10 ] [ 19 ] * q0 ) / 2 ;
nextP [ 1 ] [ 20 ] = P [ 1 ] [ 20 ] + P [ 0 ] [ 20 ] * SF [ 5 ] + P [ 2 ] [ 20 ] * SF [ 4 ] + P [ 3 ] [ 20 ] * SPP [ 7 ] + P [ 11 ] [ 20 ] * SPP [ 3 ] - P [ 12 ] [ 20 ] * SPP [ 4 ] - ( P [ 10 ] [ 20 ] * q0 ) / 2 ;
nextP [ 2 ] [ 0 ] = P [ 2 ] [ 0 ] + SQ [ 7 ] + P [ 0 ] [ 0 ] * SF [ 3 ] + P [ 3 ] [ 0 ] * SF [ 5 ] + P [ 1 ] [ 0 ] * SPP [ 6 ] - P [ 10 ] [ 0 ] * SPP [ 3 ] + P [ 12 ] [ 0 ] * SPP [ 5 ] - ( P [ 11 ] [ 0 ] * q0 ) / 2 + SF [ 6 ] * ( P [ 2 ] [ 1 ] + P [ 0 ] [ 1 ] * SF [ 3 ] + P [ 3 ] [ 1 ] * SF [ 5 ] + P [ 1 ] [ 1 ] * SPP [ 6 ] - P [ 10 ] [ 1 ] * SPP [ 3 ] + P [ 12 ] [ 1 ] * SPP [ 5 ] - ( P [ 11 ] [ 1 ] * q0 ) / 2 ) + SPP [ 7 ] * ( P [ 2 ] [ 2 ] + P [ 0 ] [ 2 ] * SF [ 3 ] + P [ 3 ] [ 2 ] * SF [ 5 ] + P [ 1 ] [ 2 ] * SPP [ 6 ] - P [ 10 ] [ 2 ] * SPP [ 3 ] + P [ 12 ] [ 2 ] * SPP [ 5 ] - ( P [ 11 ] [ 2 ] * q0 ) / 2 ) + SPP [ 6 ] * ( P [ 2 ] [ 3 ] + P [ 0 ] [ 3 ] * SF [ 3 ] + P [ 3 ] [ 3 ] * SF [ 5 ] + P [ 1 ] [ 3 ] * SPP [ 6 ] - P [ 10 ] [ 3 ] * SPP [ 3 ] + P [ 12 ] [ 3 ] * SPP [ 5 ] - ( P [ 11 ] [ 3 ] * q0 ) / 2 ) + SPP [ 5 ] * ( P [ 2 ] [ 10 ] + P [ 0 ] [ 10 ] * SF [ 3 ] + P [ 3 ] [ 10 ] * SF [ 5 ] + P [ 1 ] [ 10 ] * SPP [ 6 ] - P [ 10 ] [ 10 ] * SPP [ 3 ] + P [ 12 ] [ 10 ] * SPP [ 5 ] - ( P [ 11 ] [ 10 ] * q0 ) / 2 ) + SPP [ 4 ] * ( P [ 2 ] [ 11 ] + P [ 0 ] [ 11 ] * SF [ 3 ] + P [ 3 ] [ 11 ] * SF [ 5 ] + P [ 1 ] [ 11 ] * SPP [ 6 ] - P [ 10 ] [ 11 ] * SPP [ 3 ] + P [ 12 ] [ 11 ] * SPP [ 5 ] - ( P [ 11 ] [ 11 ] * q0 ) / 2 ) + SPP [ 3 ] * ( P [ 2 ] [ 12 ] + P [ 0 ] [ 12 ] * SF [ 3 ] + P [ 3 ] [ 12 ] * SF [ 5 ] + P [ 1 ] [ 12 ] * SPP [ 6 ] - P [ 10 ] [ 12 ] * SPP [ 3 ] + P [ 12 ] [ 12 ] * SPP [ 5 ] - ( P [ 11 ] [ 12 ] * q0 ) / 2 ) ;
nextP [ 2 ] [ 1 ] = P [ 2 ] [ 1 ] + SQ [ 5 ] + P [ 0 ] [ 1 ] * SF [ 3 ] + P [ 3 ] [ 1 ] * SF [ 5 ] + P [ 1 ] [ 1 ] * SPP [ 6 ] - P [ 10 ] [ 1 ] * SPP [ 3 ] + P [ 12 ] [ 1 ] * SPP [ 5 ] - ( P [ 11 ] [ 1 ] * q0 ) / 2 + SF [ 5 ] * ( P [ 2 ] [ 0 ] + P [ 0 ] [ 0 ] * SF [ 3 ] + P [ 3 ] [ 0 ] * SF [ 5 ] + P [ 1 ] [ 0 ] * SPP [ 6 ] - P [ 10 ] [ 0 ] * SPP [ 3 ] + P [ 12 ] [ 0 ] * SPP [ 5 ] - ( P [ 11 ] [ 0 ] * q0 ) / 2 ) + SF [ 4 ] * ( P [ 2 ] [ 2 ] + P [ 0 ] [ 2 ] * SF [ 3 ] + P [ 3 ] [ 2 ] * SF [ 5 ] + P [ 1 ] [ 2 ] * SPP [ 6 ] - P [ 10 ] [ 2 ] * SPP [ 3 ] + P [ 12 ] [ 2 ] * SPP [ 5 ] - ( P [ 11 ] [ 2 ] * q0 ) / 2 ) + SPP [ 7 ] * ( P [ 2 ] [ 3 ] + P [ 0 ] [ 3 ] * SF [ 3 ] + P [ 3 ] [ 3 ] * SF [ 5 ] + P [ 1 ] [ 3 ] * SPP [ 6 ] - P [ 10 ] [ 3 ] * SPP [ 3 ] + P [ 12 ] [ 3 ] * SPP [ 5 ] - ( P [ 11 ] [ 3 ] * q0 ) / 2 ) + SPP [ 3 ] * ( P [ 2 ] [ 11 ] + P [ 0 ] [ 11 ] * SF [ 3 ] + P [ 3 ] [ 11 ] * SF [ 5 ] + P [ 1 ] [ 11 ] * SPP [ 6 ] - P [ 10 ] [ 11 ] * SPP [ 3 ] + P [ 12 ] [ 11 ] * SPP [ 5 ] - ( P [ 11 ] [ 11 ] * q0 ) / 2 ) - SPP [ 4 ] * ( P [ 2 ] [ 12 ] + P [ 0 ] [ 12 ] * SF [ 3 ] + P [ 3 ] [ 12 ] * SF [ 5 ] + P [ 1 ] [ 12 ] * SPP [ 6 ] - P [ 10 ] [ 12 ] * SPP [ 3 ] + P [ 12 ] [ 12 ] * SPP [ 5 ] - ( P [ 11 ] [ 12 ] * q0 ) / 2 ) - ( q0 * ( P [ 2 ] [ 10 ] + P [ 0 ] [ 10 ] * SF [ 3 ] + P [ 3 ] [ 10 ] * SF [ 5 ] + P [ 1 ] [ 10 ] * SPP [ 6 ] - P [ 10 ] [ 10 ] * SPP [ 3 ] + P [ 12 ] [ 10 ] * SPP [ 5 ] - ( P [ 11 ] [ 10 ] * q0 ) / 2 ) ) / 2 ;
nextP [ 2 ] [ 2 ] = P [ 2 ] [ 2 ] + P [ 0 ] [ 2 ] * SF [ 3 ] + P [ 3 ] [ 2 ] * SF [ 5 ] + P [ 1 ] [ 2 ] * SPP [ 6 ] - P [ 10 ] [ 2 ] * SPP [ 3 ] + P [ 12 ] [ 2 ] * SPP [ 5 ] + dayCov * SQ [ 9 ] + ( dazCov * SQ [ 10 ] ) / 4 - ( P [ 11 ] [ 2 ] * q0 ) / 2 + SF [ 3 ] * ( P [ 2 ] [ 0 ] + P [ 0 ] [ 0 ] * SF [ 3 ] + P [ 3 ] [ 0 ] * SF [ 5 ] + P [ 1 ] [ 0 ] * SPP [ 6 ] - P [ 10 ] [ 0 ] * SPP [ 3 ] + P [ 12 ] [ 0 ] * SPP [ 5 ] - ( P [ 11 ] [ 0 ] * q0 ) / 2 ) + SF [ 5 ] * ( P [ 2 ] [ 3 ] + P [ 0 ] [ 3 ] * SF [ 3 ] + P [ 3 ] [ 3 ] * SF [ 5 ] + P [ 1 ] [ 3 ] * SPP [ 6 ] - P [ 10 ] [ 3 ] * SPP [ 3 ] + P [ 12 ] [ 3 ] * SPP [ 5 ] - ( P [ 11 ] [ 3 ] * q0 ) / 2 ) + SPP [ 6 ] * ( P [ 2 ] [ 1 ] + P [ 0 ] [ 1 ] * SF [ 3 ] + P [ 3 ] [ 1 ] * SF [ 5 ] + P [ 1 ] [ 1 ] * SPP [ 6 ] - P [ 10 ] [ 1 ] * SPP [ 3 ] + P [ 12 ] [ 1 ] * SPP [ 5 ] - ( P [ 11 ] [ 1 ] * q0 ) / 2 ) - SPP [ 3 ] * ( P [ 2 ] [ 10 ] + P [ 0 ] [ 10 ] * SF [ 3 ] + P [ 3 ] [ 10 ] * SF [ 5 ] + P [ 1 ] [ 10 ] * SPP [ 6 ] - P [ 10 ] [ 10 ] * SPP [ 3 ] + P [ 12 ] [ 10 ] * SPP [ 5 ] - ( P [ 11 ] [ 10 ] * q0 ) / 2 ) + SPP [ 5 ] * ( P [ 2 ] [ 12 ] + P [ 0 ] [ 12 ] * SF [ 3 ] + P [ 3 ] [ 12 ] * SF [ 5 ] + P [ 1 ] [ 12 ] * SPP [ 6 ] - P [ 10 ] [ 12 ] * SPP [ 3 ] + P [ 12 ] [ 12 ] * SPP [ 5 ] - ( P [ 11 ] [ 12 ] * q0 ) / 2 ) + ( daxCov * sq ( q3 ) ) / 4 - ( q0 * ( P [ 2 ] [ 11 ] + P [ 0 ] [ 11 ] * SF [ 3 ] + P [ 3 ] [ 11 ] * SF [ 5 ] + P [ 1 ] [ 11 ] * SPP [ 6 ] - P [ 10 ] [ 11 ] * SPP [ 3 ] + P [ 12 ] [ 11 ] * SPP [ 5 ] - ( P [ 11 ] [ 11 ] * q0 ) / 2 ) ) / 2 ;
nextP [ 2 ] [ 3 ] = P [ 2 ] [ 3 ] + SQ [ 3 ] + P [ 0 ] [ 3 ] * SF [ 3 ] + P [ 3 ] [ 3 ] * SF [ 5 ] + P [ 1 ] [ 3 ] * SPP [ 6 ] - P [ 10 ] [ 3 ] * SPP [ 3 ] + P [ 12 ] [ 3 ] * SPP [ 5 ] - ( P [ 11 ] [ 3 ] * q0 ) / 2 + SF [ 4 ] * ( P [ 2 ] [ 0 ] + P [ 0 ] [ 0 ] * SF [ 3 ] + P [ 3 ] [ 0 ] * SF [ 5 ] + P [ 1 ] [ 0 ] * SPP [ 6 ] - P [ 10 ] [ 0 ] * SPP [ 3 ] + P [ 12 ] [ 0 ] * SPP [ 5 ] - ( P [ 11 ] [ 0 ] * q0 ) / 2 ) + SF [ 3 ] * ( P [ 2 ] [ 1 ] + P [ 0 ] [ 1 ] * SF [ 3 ] + P [ 3 ] [ 1 ] * SF [ 5 ] + P [ 1 ] [ 1 ] * SPP [ 6 ] - P [ 10 ] [ 1 ] * SPP [ 3 ] + P [ 12 ] [ 1 ] * SPP [ 5 ] - ( P [ 11 ] [ 1 ] * q0 ) / 2 ) + SF [ 6 ] * ( P [ 2 ] [ 2 ] + P [ 0 ] [ 2 ] * SF [ 3 ] + P [ 3 ] [ 2 ] * SF [ 5 ] + P [ 1 ] [ 2 ] * SPP [ 6 ] - P [ 10 ] [ 2 ] * SPP [ 3 ] + P [ 12 ] [ 2 ] * SPP [ 5 ] - ( P [ 11 ] [ 2 ] * q0 ) / 2 ) + SPP [ 4 ] * ( P [ 2 ] [ 10 ] + P [ 0 ] [ 10 ] * SF [ 3 ] + P [ 3 ] [ 10 ] * SF [ 5 ] + P [ 1 ] [ 10 ] * SPP [ 6 ] - P [ 10 ] [ 10 ] * SPP [ 3 ] + P [ 12 ] [ 10 ] * SPP [ 5 ] - ( P [ 11 ] [ 10 ] * q0 ) / 2 ) - SPP [ 5 ] * ( P [ 2 ] [ 11 ] + P [ 0 ] [ 11 ] * SF [ 3 ] + P [ 3 ] [ 11 ] * SF [ 5 ] + P [ 1 ] [ 11 ] * SPP [ 6 ] - P [ 10 ] [ 11 ] * SPP [ 3 ] + P [ 12 ] [ 11 ] * SPP [ 5 ] - ( P [ 11 ] [ 11 ] * q0 ) / 2 ) - ( q0 * ( P [ 2 ] [ 12 ] + P [ 0 ] [ 12 ] * SF [ 3 ] + P [ 3 ] [ 12 ] * SF [ 5 ] + P [ 1 ] [ 12 ] * SPP [ 6 ] - P [ 10 ] [ 12 ] * SPP [ 3 ] + P [ 12 ] [ 12 ] * SPP [ 5 ] - ( P [ 11 ] [ 12 ] * q0 ) / 2 ) ) / 2 ;
nextP [ 2 ] [ 4 ] = P [ 2 ] [ 4 ] + P [ 0 ] [ 4 ] * SF [ 3 ] + P [ 3 ] [ 4 ] * SF [ 5 ] + P [ 1 ] [ 4 ] * SPP [ 6 ] - P [ 10 ] [ 4 ] * SPP [ 3 ] + P [ 12 ] [ 4 ] * SPP [ 5 ] - ( P [ 11 ] [ 4 ] * q0 ) / 2 + SF [ 2 ] * ( P [ 2 ] [ 0 ] + P [ 0 ] [ 0 ] * SF [ 3 ] + P [ 3 ] [ 0 ] * SF [ 5 ] + P [ 1 ] [ 0 ] * SPP [ 6 ] - P [ 10 ] [ 0 ] * SPP [ 3 ] + P [ 12 ] [ 0 ] * SPP [ 5 ] - ( P [ 11 ] [ 0 ] * q0 ) / 2 ) + SF [ 0 ] * ( P [ 2 ] [ 1 ] + P [ 0 ] [ 1 ] * SF [ 3 ] + P [ 3 ] [ 1 ] * SF [ 5 ] + P [ 1 ] [ 1 ] * SPP [ 6 ] - P [ 10 ] [ 1 ] * SPP [ 3 ] + P [ 12 ] [ 1 ] * SPP [ 5 ] - ( P [ 11 ] [ 1 ] * q0 ) / 2 ) + SPP [ 0 ] * ( P [ 2 ] [ 2 ] + P [ 0 ] [ 2 ] * SF [ 3 ] + P [ 3 ] [ 2 ] * SF [ 5 ] + P [ 1 ] [ 2 ] * SPP [ 6 ] - P [ 10 ] [ 2 ] * SPP [ 3 ] + P [ 12 ] [ 2 ] * SPP [ 5 ] - ( P [ 11 ] [ 2 ] * q0 ) / 2 ) - SPP [ 2 ] * ( P [ 2 ] [ 3 ] + P [ 0 ] [ 3 ] * SF [ 3 ] + P [ 3 ] [ 3 ] * SF [ 5 ] + P [ 1 ] [ 3 ] * SPP [ 6 ] - P [ 10 ] [ 3 ] * SPP [ 3 ] + P [ 12 ] [ 3 ] * SPP [ 5 ] - ( P [ 11 ] [ 3 ] * q0 ) / 2 ) ;
nextP [ 2 ] [ 5 ] = P [ 2 ] [ 5 ] + P [ 0 ] [ 5 ] * SF [ 3 ] + P [ 3 ] [ 5 ] * SF [ 5 ] + P [ 1 ] [ 5 ] * SPP [ 6 ] - P [ 10 ] [ 5 ] * SPP [ 3 ] + P [ 12 ] [ 5 ] * SPP [ 5 ] - ( P [ 11 ] [ 5 ] * q0 ) / 2 + SF [ 1 ] * ( P [ 2 ] [ 0 ] + P [ 0 ] [ 0 ] * SF [ 3 ] + P [ 3 ] [ 0 ] * SF [ 5 ] + P [ 1 ] [ 0 ] * SPP [ 6 ] - P [ 10 ] [ 0 ] * SPP [ 3 ] + P [ 12 ] [ 0 ] * SPP [ 5 ] - ( P [ 11 ] [ 0 ] * q0 ) / 2 ) + SF [ 0 ] * ( P [ 2 ] [ 2 ] + P [ 0 ] [ 2 ] * SF [ 3 ] + P [ 3 ] [ 2 ] * SF [ 5 ] + P [ 1 ] [ 2 ] * SPP [ 6 ] - P [ 10 ] [ 2 ] * SPP [ 3 ] + P [ 12 ] [ 2 ] * SPP [ 5 ] - ( P [ 11 ] [ 2 ] * q0 ) / 2 ) + SF [ 2 ] * ( P [ 2 ] [ 3 ] + P [ 0 ] [ 3 ] * SF [ 3 ] + P [ 3 ] [ 3 ] * SF [ 5 ] + P [ 1 ] [ 3 ] * SPP [ 6 ] - P [ 10 ] [ 3 ] * SPP [ 3 ] + P [ 12 ] [ 3 ] * SPP [ 5 ] - ( P [ 11 ] [ 3 ] * q0 ) / 2 ) - SPP [ 0 ] * ( P [ 2 ] [ 1 ] + P [ 0 ] [ 1 ] * SF [ 3 ] + P [ 3 ] [ 1 ] * SF [ 5 ] + P [ 1 ] [ 1 ] * SPP [ 6 ] - P [ 10 ] [ 1 ] * SPP [ 3 ] + P [ 12 ] [ 1 ] * SPP [ 5 ] - ( P [ 11 ] [ 1 ] * q0 ) / 2 ) ;
nextP [ 2 ] [ 6 ] = P [ 2 ] [ 6 ] + P [ 0 ] [ 6 ] * SF [ 3 ] + P [ 3 ] [ 6 ] * SF [ 5 ] + P [ 1 ] [ 6 ] * SPP [ 6 ] - P [ 10 ] [ 6 ] * SPP [ 3 ] + P [ 12 ] [ 6 ] * SPP [ 5 ] - ( P [ 11 ] [ 6 ] * q0 ) / 2 + SF [ 1 ] * ( P [ 2 ] [ 1 ] + P [ 0 ] [ 1 ] * SF [ 3 ] + P [ 3 ] [ 1 ] * SF [ 5 ] + P [ 1 ] [ 1 ] * SPP [ 6 ] - P [ 10 ] [ 1 ] * SPP [ 3 ] + P [ 12 ] [ 1 ] * SPP [ 5 ] - ( P [ 11 ] [ 1 ] * q0 ) / 2 ) + SF [ 0 ] * ( P [ 2 ] [ 3 ] + P [ 0 ] [ 3 ] * SF [ 3 ] + P [ 3 ] [ 3 ] * SF [ 5 ] + P [ 1 ] [ 3 ] * SPP [ 6 ] - P [ 10 ] [ 3 ] * SPP [ 3 ] + P [ 12 ] [ 3 ] * SPP [ 5 ] - ( P [ 11 ] [ 3 ] * q0 ) / 2 ) + SPP [ 0 ] * ( P [ 2 ] [ 0 ] + P [ 0 ] [ 0 ] * SF [ 3 ] + P [ 3 ] [ 0 ] * SF [ 5 ] + P [ 1 ] [ 0 ] * SPP [ 6 ] - P [ 10 ] [ 0 ] * SPP [ 3 ] + P [ 12 ] [ 0 ] * SPP [ 5 ] - ( P [ 11 ] [ 0 ] * q0 ) / 2 ) - SPP [ 1 ] * ( P [ 2 ] [ 2 ] + P [ 0 ] [ 2 ] * SF [ 3 ] + P [ 3 ] [ 2 ] * SF [ 5 ] + P [ 1 ] [ 2 ] * SPP [ 6 ] - P [ 10 ] [ 2 ] * SPP [ 3 ] + P [ 12 ] [ 2 ] * SPP [ 5 ] - ( P [ 11 ] [ 2 ] * q0 ) / 2 ) ;
nextP [ 2 ] [ 7 ] = P [ 2 ] [ 7 ] + P [ 0 ] [ 7 ] * SF [ 3 ] + P [ 3 ] [ 7 ] * SF [ 5 ] + P [ 1 ] [ 7 ] * SPP [ 6 ] - P [ 10 ] [ 7 ] * SPP [ 3 ] + P [ 12 ] [ 7 ] * SPP [ 5 ] - ( P [ 11 ] [ 7 ] * q0 ) / 2 + dt * ( P [ 2 ] [ 4 ] + P [ 0 ] [ 4 ] * SF [ 3 ] + P [ 3 ] [ 4 ] * SF [ 5 ] + P [ 1 ] [ 4 ] * SPP [ 6 ] - P [ 10 ] [ 4 ] * SPP [ 3 ] + P [ 12 ] [ 4 ] * SPP [ 5 ] - ( P [ 11 ] [ 4 ] * q0 ) / 2 ) ;
nextP [ 2 ] [ 8 ] = P [ 2 ] [ 8 ] + P [ 0 ] [ 8 ] * SF [ 3 ] + P [ 3 ] [ 8 ] * SF [ 5 ] + P [ 1 ] [ 8 ] * SPP [ 6 ] - P [ 10 ] [ 8 ] * SPP [ 3 ] + P [ 12 ] [ 8 ] * SPP [ 5 ] - ( P [ 11 ] [ 8 ] * q0 ) / 2 + dt * ( P [ 2 ] [ 5 ] + P [ 0 ] [ 5 ] * SF [ 3 ] + P [ 3 ] [ 5 ] * SF [ 5 ] + P [ 1 ] [ 5 ] * SPP [ 6 ] - P [ 10 ] [ 5 ] * SPP [ 3 ] + P [ 12 ] [ 5 ] * SPP [ 5 ] - ( P [ 11 ] [ 5 ] * q0 ) / 2 ) ;
nextP [ 2 ] [ 9 ] = P [ 2 ] [ 9 ] + P [ 0 ] [ 9 ] * SF [ 3 ] + P [ 3 ] [ 9 ] * SF [ 5 ] + P [ 1 ] [ 9 ] * SPP [ 6 ] - P [ 10 ] [ 9 ] * SPP [ 3 ] + P [ 12 ] [ 9 ] * SPP [ 5 ] - ( P [ 11 ] [ 9 ] * q0 ) / 2 + dt * ( P [ 2 ] [ 6 ] + P [ 0 ] [ 6 ] * SF [ 3 ] + P [ 3 ] [ 6 ] * SF [ 5 ] + P [ 1 ] [ 6 ] * SPP [ 6 ] - P [ 10 ] [ 6 ] * SPP [ 3 ] + P [ 12 ] [ 6 ] * SPP [ 5 ] - ( P [ 11 ] [ 6 ] * q0 ) / 2 ) ;
nextP [ 2 ] [ 10 ] = P [ 2 ] [ 10 ] + P [ 0 ] [ 10 ] * SF [ 3 ] + P [ 3 ] [ 10 ] * SF [ 5 ] + P [ 1 ] [ 10 ] * SPP [ 6 ] - P [ 10 ] [ 10 ] * SPP [ 3 ] + P [ 12 ] [ 10 ] * SPP [ 5 ] - ( P [ 11 ] [ 10 ] * q0 ) / 2 ;
nextP [ 2 ] [ 11 ] = P [ 2 ] [ 11 ] + P [ 0 ] [ 11 ] * SF [ 3 ] + P [ 3 ] [ 11 ] * SF [ 5 ] + P [ 1 ] [ 11 ] * SPP [ 6 ] - P [ 10 ] [ 11 ] * SPP [ 3 ] + P [ 12 ] [ 11 ] * SPP [ 5 ] - ( P [ 11 ] [ 11 ] * q0 ) / 2 ;
nextP [ 2 ] [ 12 ] = P [ 2 ] [ 12 ] + P [ 0 ] [ 12 ] * SF [ 3 ] + P [ 3 ] [ 12 ] * SF [ 5 ] + P [ 1 ] [ 12 ] * SPP [ 6 ] - P [ 10 ] [ 12 ] * SPP [ 3 ] + P [ 12 ] [ 12 ] * SPP [ 5 ] - ( P [ 11 ] [ 12 ] * q0 ) / 2 ;
nextP [ 2 ] [ 13 ] = P [ 2 ] [ 13 ] + P [ 0 ] [ 13 ] * SF [ 3 ] + P [ 3 ] [ 13 ] * SF [ 5 ] + P [ 1 ] [ 13 ] * SPP [ 6 ] - P [ 10 ] [ 13 ] * SPP [ 3 ] + P [ 12 ] [ 13 ] * SPP [ 5 ] - ( P [ 11 ] [ 13 ] * q0 ) / 2 ;
nextP [ 2 ] [ 14 ] = P [ 2 ] [ 14 ] + P [ 0 ] [ 14 ] * SF [ 3 ] + P [ 3 ] [ 14 ] * SF [ 5 ] + P [ 1 ] [ 14 ] * SPP [ 6 ] - P [ 10 ] [ 14 ] * SPP [ 3 ] + P [ 12 ] [ 14 ] * SPP [ 5 ] - ( P [ 11 ] [ 14 ] * q0 ) / 2 ;
nextP [ 2 ] [ 15 ] = P [ 2 ] [ 15 ] + P [ 0 ] [ 15 ] * SF [ 3 ] + P [ 3 ] [ 15 ] * SF [ 5 ] + P [ 1 ] [ 15 ] * SPP [ 6 ] - P [ 10 ] [ 15 ] * SPP [ 3 ] + P [ 12 ] [ 15 ] * SPP [ 5 ] - ( P [ 11 ] [ 15 ] * q0 ) / 2 ;
nextP [ 2 ] [ 16 ] = P [ 2 ] [ 16 ] + P [ 0 ] [ 16 ] * SF [ 3 ] + P [ 3 ] [ 16 ] * SF [ 5 ] + P [ 1 ] [ 16 ] * SPP [ 6 ] - P [ 10 ] [ 16 ] * SPP [ 3 ] + P [ 12 ] [ 16 ] * SPP [ 5 ] - ( P [ 11 ] [ 16 ] * q0 ) / 2 ;
nextP [ 2 ] [ 17 ] = P [ 2 ] [ 17 ] + P [ 0 ] [ 17 ] * SF [ 3 ] + P [ 3 ] [ 17 ] * SF [ 5 ] + P [ 1 ] [ 17 ] * SPP [ 6 ] - P [ 10 ] [ 17 ] * SPP [ 3 ] + P [ 12 ] [ 17 ] * SPP [ 5 ] - ( P [ 11 ] [ 17 ] * q0 ) / 2 ;
nextP [ 2 ] [ 18 ] = P [ 2 ] [ 18 ] + P [ 0 ] [ 18 ] * SF [ 3 ] + P [ 3 ] [ 18 ] * SF [ 5 ] + P [ 1 ] [ 18 ] * SPP [ 6 ] - P [ 10 ] [ 18 ] * SPP [ 3 ] + P [ 12 ] [ 18 ] * SPP [ 5 ] - ( P [ 11 ] [ 18 ] * q0 ) / 2 ;
nextP [ 2 ] [ 19 ] = P [ 2 ] [ 19 ] + P [ 0 ] [ 19 ] * SF [ 3 ] + P [ 3 ] [ 19 ] * SF [ 5 ] + P [ 1 ] [ 19 ] * SPP [ 6 ] - P [ 10 ] [ 19 ] * SPP [ 3 ] + P [ 12 ] [ 19 ] * SPP [ 5 ] - ( P [ 11 ] [ 19 ] * q0 ) / 2 ;
nextP [ 2 ] [ 20 ] = P [ 2 ] [ 20 ] + P [ 0 ] [ 20 ] * SF [ 3 ] + P [ 3 ] [ 20 ] * SF [ 5 ] + P [ 1 ] [ 20 ] * SPP [ 6 ] - P [ 10 ] [ 20 ] * SPP [ 3 ] + P [ 12 ] [ 20 ] * SPP [ 5 ] - ( P [ 11 ] [ 20 ] * q0 ) / 2 ;
nextP [ 3 ] [ 0 ] = P [ 3 ] [ 0 ] + SQ [ 6 ] + P [ 0 ] [ 0 ] * SF [ 4 ] + P [ 1 ] [ 0 ] * SF [ 3 ] + P [ 2 ] [ 0 ] * SF [ 6 ] + P [ 10 ] [ 0 ] * SPP [ 4 ] - P [ 11 ] [ 0 ] * SPP [ 5 ] - ( P [ 12 ] [ 0 ] * q0 ) / 2 + SF [ 6 ] * ( P [ 3 ] [ 1 ] + P [ 0 ] [ 1 ] * SF [ 4 ] + P [ 1 ] [ 1 ] * SF [ 3 ] + P [ 2 ] [ 1 ] * SF [ 6 ] + P [ 10 ] [ 1 ] * SPP [ 4 ] - P [ 11 ] [ 1 ] * SPP [ 5 ] - ( P [ 12 ] [ 1 ] * q0 ) / 2 ) + SPP [ 7 ] * ( P [ 3 ] [ 2 ] + P [ 0 ] [ 2 ] * SF [ 4 ] + P [ 1 ] [ 2 ] * SF [ 3 ] + P [ 2 ] [ 2 ] * SF [ 6 ] + P [ 10 ] [ 2 ] * SPP [ 4 ] - P [ 11 ] [ 2 ] * SPP [ 5 ] - ( P [ 12 ] [ 2 ] * q0 ) / 2 ) + SPP [ 6 ] * ( P [ 3 ] [ 3 ] + P [ 0 ] [ 3 ] * SF [ 4 ] + P [ 1 ] [ 3 ] * SF [ 3 ] + P [ 2 ] [ 3 ] * SF [ 6 ] + P [ 10 ] [ 3 ] * SPP [ 4 ] - P [ 11 ] [ 3 ] * SPP [ 5 ] - ( P [ 12 ] [ 3 ] * q0 ) / 2 ) + SPP [ 5 ] * ( P [ 3 ] [ 10 ] + P [ 0 ] [ 10 ] * SF [ 4 ] + P [ 1 ] [ 10 ] * SF [ 3 ] + P [ 2 ] [ 10 ] * SF [ 6 ] + P [ 10 ] [ 10 ] * SPP [ 4 ] - P [ 11 ] [ 10 ] * SPP [ 5 ] - ( P [ 12 ] [ 10 ] * q0 ) / 2 ) + SPP [ 4 ] * ( P [ 3 ] [ 11 ] + P [ 0 ] [ 11 ] * SF [ 4 ] + P [ 1 ] [ 11 ] * SF [ 3 ] + P [ 2 ] [ 11 ] * SF [ 6 ] + P [ 10 ] [ 11 ] * SPP [ 4 ] - P [ 11 ] [ 11 ] * SPP [ 5 ] - ( P [ 12 ] [ 11 ] * q0 ) / 2 ) + SPP [ 3 ] * ( P [ 3 ] [ 12 ] + P [ 0 ] [ 12 ] * SF [ 4 ] + P [ 1 ] [ 12 ] * SF [ 3 ] + P [ 2 ] [ 12 ] * SF [ 6 ] + P [ 10 ] [ 12 ] * SPP [ 4 ] - P [ 11 ] [ 12 ] * SPP [ 5 ] - ( P [ 12 ] [ 12 ] * q0 ) / 2 ) ;
nextP [ 3 ] [ 1 ] = P [ 3 ] [ 1 ] + SQ [ 4 ] + P [ 0 ] [ 1 ] * SF [ 4 ] + P [ 1 ] [ 1 ] * SF [ 3 ] + P [ 2 ] [ 1 ] * SF [ 6 ] + P [ 10 ] [ 1 ] * SPP [ 4 ] - P [ 11 ] [ 1 ] * SPP [ 5 ] - ( P [ 12 ] [ 1 ] * q0 ) / 2 + SF [ 5 ] * ( P [ 3 ] [ 0 ] + P [ 0 ] [ 0 ] * SF [ 4 ] + P [ 1 ] [ 0 ] * SF [ 3 ] + P [ 2 ] [ 0 ] * SF [ 6 ] + P [ 10 ] [ 0 ] * SPP [ 4 ] - P [ 11 ] [ 0 ] * SPP [ 5 ] - ( P [ 12 ] [ 0 ] * q0 ) / 2 ) + SF [ 4 ] * ( P [ 3 ] [ 2 ] + P [ 0 ] [ 2 ] * SF [ 4 ] + P [ 1 ] [ 2 ] * SF [ 3 ] + P [ 2 ] [ 2 ] * SF [ 6 ] + P [ 10 ] [ 2 ] * SPP [ 4 ] - P [ 11 ] [ 2 ] * SPP [ 5 ] - ( P [ 12 ] [ 2 ] * q0 ) / 2 ) + SPP [ 7 ] * ( P [ 3 ] [ 3 ] + P [ 0 ] [ 3 ] * SF [ 4 ] + P [ 1 ] [ 3 ] * SF [ 3 ] + P [ 2 ] [ 3 ] * SF [ 6 ] + P [ 10 ] [ 3 ] * SPP [ 4 ] - P [ 11 ] [ 3 ] * SPP [ 5 ] - ( P [ 12 ] [ 3 ] * q0 ) / 2 ) + SPP [ 3 ] * ( P [ 3 ] [ 11 ] + P [ 0 ] [ 11 ] * SF [ 4 ] + P [ 1 ] [ 11 ] * SF [ 3 ] + P [ 2 ] [ 11 ] * SF [ 6 ] + P [ 10 ] [ 11 ] * SPP [ 4 ] - P [ 11 ] [ 11 ] * SPP [ 5 ] - ( P [ 12 ] [ 11 ] * q0 ) / 2 ) - SPP [ 4 ] * ( P [ 3 ] [ 12 ] + P [ 0 ] [ 12 ] * SF [ 4 ] + P [ 1 ] [ 12 ] * SF [ 3 ] + P [ 2 ] [ 12 ] * SF [ 6 ] + P [ 10 ] [ 12 ] * SPP [ 4 ] - P [ 11 ] [ 12 ] * SPP [ 5 ] - ( P [ 12 ] [ 12 ] * q0 ) / 2 ) - ( q0 * ( P [ 3 ] [ 10 ] + P [ 0 ] [ 10 ] * SF [ 4 ] + P [ 1 ] [ 10 ] * SF [ 3 ] + P [ 2 ] [ 10 ] * SF [ 6 ] + P [ 10 ] [ 10 ] * SPP [ 4 ] - P [ 11 ] [ 10 ] * SPP [ 5 ] - ( P [ 12 ] [ 10 ] * q0 ) / 2 ) ) / 2 ;
nextP [ 3 ] [ 2 ] = P [ 3 ] [ 2 ] + SQ [ 3 ] + P [ 0 ] [ 2 ] * SF [ 4 ] + P [ 1 ] [ 2 ] * SF [ 3 ] + P [ 2 ] [ 2 ] * SF [ 6 ] + P [ 10 ] [ 2 ] * SPP [ 4 ] - P [ 11 ] [ 2 ] * SPP [ 5 ] - ( P [ 12 ] [ 2 ] * q0 ) / 2 + SF [ 3 ] * ( P [ 3 ] [ 0 ] + P [ 0 ] [ 0 ] * SF [ 4 ] + P [ 1 ] [ 0 ] * SF [ 3 ] + P [ 2 ] [ 0 ] * SF [ 6 ] + P [ 10 ] [ 0 ] * SPP [ 4 ] - P [ 11 ] [ 0 ] * SPP [ 5 ] - ( P [ 12 ] [ 0 ] * q0 ) / 2 ) + SF [ 5 ] * ( P [ 3 ] [ 3 ] + P [ 0 ] [ 3 ] * SF [ 4 ] + P [ 1 ] [ 3 ] * SF [ 3 ] + P [ 2 ] [ 3 ] * SF [ 6 ] + P [ 10 ] [ 3 ] * SPP [ 4 ] - P [ 11 ] [ 3 ] * SPP [ 5 ] - ( P [ 12 ] [ 3 ] * q0 ) / 2 ) + SPP [ 6 ] * ( P [ 3 ] [ 1 ] + P [ 0 ] [ 1 ] * SF [ 4 ] + P [ 1 ] [ 1 ] * SF [ 3 ] + P [ 2 ] [ 1 ] * SF [ 6 ] + P [ 10 ] [ 1 ] * SPP [ 4 ] - P [ 11 ] [ 1 ] * SPP [ 5 ] - ( P [ 12 ] [ 1 ] * q0 ) / 2 ) - SPP [ 3 ] * ( P [ 3 ] [ 10 ] + P [ 0 ] [ 10 ] * SF [ 4 ] + P [ 1 ] [ 10 ] * SF [ 3 ] + P [ 2 ] [ 10 ] * SF [ 6 ] + P [ 10 ] [ 10 ] * SPP [ 4 ] - P [ 11 ] [ 10 ] * SPP [ 5 ] - ( P [ 12 ] [ 10 ] * q0 ) / 2 ) + SPP [ 5 ] * ( P [ 3 ] [ 12 ] + P [ 0 ] [ 12 ] * SF [ 4 ] + P [ 1 ] [ 12 ] * SF [ 3 ] + P [ 2 ] [ 12 ] * SF [ 6 ] + P [ 10 ] [ 12 ] * SPP [ 4 ] - P [ 11 ] [ 12 ] * SPP [ 5 ] - ( P [ 12 ] [ 12 ] * q0 ) / 2 ) - ( q0 * ( P [ 3 ] [ 11 ] + P [ 0 ] [ 11 ] * SF [ 4 ] + P [ 1 ] [ 11 ] * SF [ 3 ] + P [ 2 ] [ 11 ] * SF [ 6 ] + P [ 10 ] [ 11 ] * SPP [ 4 ] - P [ 11 ] [ 11 ] * SPP [ 5 ] - ( P [ 12 ] [ 11 ] * q0 ) / 2 ) ) / 2 ;
nextP [ 3 ] [ 3 ] = P [ 3 ] [ 3 ] + P [ 0 ] [ 3 ] * SF [ 4 ] + P [ 1 ] [ 3 ] * SF [ 3 ] + P [ 2 ] [ 3 ] * SF [ 6 ] + P [ 10 ] [ 3 ] * SPP [ 4 ] - P [ 11 ] [ 3 ] * SPP [ 5 ] + ( dayCov * SQ [ 10 ] ) / 4 + dazCov * SQ [ 9 ] - ( P [ 12 ] [ 3 ] * q0 ) / 2 + SF [ 4 ] * ( P [ 3 ] [ 0 ] + P [ 0 ] [ 0 ] * SF [ 4 ] + P [ 1 ] [ 0 ] * SF [ 3 ] + P [ 2 ] [ 0 ] * SF [ 6 ] + P [ 10 ] [ 0 ] * SPP [ 4 ] - P [ 11 ] [ 0 ] * SPP [ 5 ] - ( P [ 12 ] [ 0 ] * q0 ) / 2 ) + SF [ 3 ] * ( P [ 3 ] [ 1 ] + P [ 0 ] [ 1 ] * SF [ 4 ] + P [ 1 ] [ 1 ] * SF [ 3 ] + P [ 2 ] [ 1 ] * SF [ 6 ] + P [ 10 ] [ 1 ] * SPP [ 4 ] - P [ 11 ] [ 1 ] * SPP [ 5 ] - ( P [ 12 ] [ 1 ] * q0 ) / 2 ) + SF [ 6 ] * ( P [ 3 ] [ 2 ] + P [ 0 ] [ 2 ] * SF [ 4 ] + P [ 1 ] [ 2 ] * SF [ 3 ] + P [ 2 ] [ 2 ] * SF [ 6 ] + P [ 10 ] [ 2 ] * SPP [ 4 ] - P [ 11 ] [ 2 ] * SPP [ 5 ] - ( P [ 12 ] [ 2 ] * q0 ) / 2 ) + SPP [ 4 ] * ( P [ 3 ] [ 10 ] + P [ 0 ] [ 10 ] * SF [ 4 ] + P [ 1 ] [ 10 ] * SF [ 3 ] + P [ 2 ] [ 10 ] * SF [ 6 ] + P [ 10 ] [ 10 ] * SPP [ 4 ] - P [ 11 ] [ 10 ] * SPP [ 5 ] - ( P [ 12 ] [ 10 ] * q0 ) / 2 ) - SPP [ 5 ] * ( P [ 3 ] [ 11 ] + P [ 0 ] [ 11 ] * SF [ 4 ] + P [ 1 ] [ 11 ] * SF [ 3 ] + P [ 2 ] [ 11 ] * SF [ 6 ] + P [ 10 ] [ 11 ] * SPP [ 4 ] - P [ 11 ] [ 11 ] * SPP [ 5 ] - ( P [ 12 ] [ 11 ] * q0 ) / 2 ) + ( daxCov * sq ( q2 ) ) / 4 - ( q0 * ( P [ 3 ] [ 12 ] + P [ 0 ] [ 12 ] * SF [ 4 ] + P [ 1 ] [ 12 ] * SF [ 3 ] + P [ 2 ] [ 12 ] * SF [ 6 ] + P [ 10 ] [ 12 ] * SPP [ 4 ] - P [ 11 ] [ 12 ] * SPP [ 5 ] - ( P [ 12 ] [ 12 ] * q0 ) / 2 ) ) / 2 ;
nextP [ 3 ] [ 4 ] = P [ 3 ] [ 4 ] + P [ 0 ] [ 4 ] * SF [ 4 ] + P [ 1 ] [ 4 ] * SF [ 3 ] + P [ 2 ] [ 4 ] * SF [ 6 ] + P [ 10 ] [ 4 ] * SPP [ 4 ] - P [ 11 ] [ 4 ] * SPP [ 5 ] - ( P [ 12 ] [ 4 ] * q0 ) / 2 + SF [ 2 ] * ( P [ 3 ] [ 0 ] + P [ 0 ] [ 0 ] * SF [ 4 ] + P [ 1 ] [ 0 ] * SF [ 3 ] + P [ 2 ] [ 0 ] * SF [ 6 ] + P [ 10 ] [ 0 ] * SPP [ 4 ] - P [ 11 ] [ 0 ] * SPP [ 5 ] - ( P [ 12 ] [ 0 ] * q0 ) / 2 ) + SF [ 0 ] * ( P [ 3 ] [ 1 ] + P [ 0 ] [ 1 ] * SF [ 4 ] + P [ 1 ] [ 1 ] * SF [ 3 ] + P [ 2 ] [ 1 ] * SF [ 6 ] + P [ 10 ] [ 1 ] * SPP [ 4 ] - P [ 11 ] [ 1 ] * SPP [ 5 ] - ( P [ 12 ] [ 1 ] * q0 ) / 2 ) + SPP [ 0 ] * ( P [ 3 ] [ 2 ] + P [ 0 ] [ 2 ] * SF [ 4 ] + P [ 1 ] [ 2 ] * SF [ 3 ] + P [ 2 ] [ 2 ] * SF [ 6 ] + P [ 10 ] [ 2 ] * SPP [ 4 ] - P [ 11 ] [ 2 ] * SPP [ 5 ] - ( P [ 12 ] [ 2 ] * q0 ) / 2 ) - SPP [ 2 ] * ( P [ 3 ] [ 3 ] + P [ 0 ] [ 3 ] * SF [ 4 ] + P [ 1 ] [ 3 ] * SF [ 3 ] + P [ 2 ] [ 3 ] * SF [ 6 ] + P [ 10 ] [ 3 ] * SPP [ 4 ] - P [ 11 ] [ 3 ] * SPP [ 5 ] - ( P [ 12 ] [ 3 ] * q0 ) / 2 ) ;
nextP [ 3 ] [ 5 ] = P [ 3 ] [ 5 ] + P [ 0 ] [ 5 ] * SF [ 4 ] + P [ 1 ] [ 5 ] * SF [ 3 ] + P [ 2 ] [ 5 ] * SF [ 6 ] + P [ 10 ] [ 5 ] * SPP [ 4 ] - P [ 11 ] [ 5 ] * SPP [ 5 ] - ( P [ 12 ] [ 5 ] * q0 ) / 2 + SF [ 1 ] * ( P [ 3 ] [ 0 ] + P [ 0 ] [ 0 ] * SF [ 4 ] + P [ 1 ] [ 0 ] * SF [ 3 ] + P [ 2 ] [ 0 ] * SF [ 6 ] + P [ 10 ] [ 0 ] * SPP [ 4 ] - P [ 11 ] [ 0 ] * SPP [ 5 ] - ( P [ 12 ] [ 0 ] * q0 ) / 2 ) + SF [ 0 ] * ( P [ 3 ] [ 2 ] + P [ 0 ] [ 2 ] * SF [ 4 ] + P [ 1 ] [ 2 ] * SF [ 3 ] + P [ 2 ] [ 2 ] * SF [ 6 ] + P [ 10 ] [ 2 ] * SPP [ 4 ] - P [ 11 ] [ 2 ] * SPP [ 5 ] - ( P [ 12 ] [ 2 ] * q0 ) / 2 ) + SF [ 2 ] * ( P [ 3 ] [ 3 ] + P [ 0 ] [ 3 ] * SF [ 4 ] + P [ 1 ] [ 3 ] * SF [ 3 ] + P [ 2 ] [ 3 ] * SF [ 6 ] + P [ 10 ] [ 3 ] * SPP [ 4 ] - P [ 11 ] [ 3 ] * SPP [ 5 ] - ( P [ 12 ] [ 3 ] * q0 ) / 2 ) - SPP [ 0 ] * ( P [ 3 ] [ 1 ] + P [ 0 ] [ 1 ] * SF [ 4 ] + P [ 1 ] [ 1 ] * SF [ 3 ] + P [ 2 ] [ 1 ] * SF [ 6 ] + P [ 10 ] [ 1 ] * SPP [ 4 ] - P [ 11 ] [ 1 ] * SPP [ 5 ] - ( P [ 12 ] [ 1 ] * q0 ) / 2 ) ;
nextP [ 3 ] [ 6 ] = P [ 3 ] [ 6 ] + P [ 0 ] [ 6 ] * SF [ 4 ] + P [ 1 ] [ 6 ] * SF [ 3 ] + P [ 2 ] [ 6 ] * SF [ 6 ] + P [ 10 ] [ 6 ] * SPP [ 4 ] - P [ 11 ] [ 6 ] * SPP [ 5 ] - ( P [ 12 ] [ 6 ] * q0 ) / 2 + SF [ 1 ] * ( P [ 3 ] [ 1 ] + P [ 0 ] [ 1 ] * SF [ 4 ] + P [ 1 ] [ 1 ] * SF [ 3 ] + P [ 2 ] [ 1 ] * SF [ 6 ] + P [ 10 ] [ 1 ] * SPP [ 4 ] - P [ 11 ] [ 1 ] * SPP [ 5 ] - ( P [ 12 ] [ 1 ] * q0 ) / 2 ) + SF [ 0 ] * ( P [ 3 ] [ 3 ] + P [ 0 ] [ 3 ] * SF [ 4 ] + P [ 1 ] [ 3 ] * SF [ 3 ] + P [ 2 ] [ 3 ] * SF [ 6 ] + P [ 10 ] [ 3 ] * SPP [ 4 ] - P [ 11 ] [ 3 ] * SPP [ 5 ] - ( P [ 12 ] [ 3 ] * q0 ) / 2 ) + SPP [ 0 ] * ( P [ 3 ] [ 0 ] + P [ 0 ] [ 0 ] * SF [ 4 ] + P [ 1 ] [ 0 ] * SF [ 3 ] + P [ 2 ] [ 0 ] * SF [ 6 ] + P [ 10 ] [ 0 ] * SPP [ 4 ] - P [ 11 ] [ 0 ] * SPP [ 5 ] - ( P [ 12 ] [ 0 ] * q0 ) / 2 ) - SPP [ 1 ] * ( P [ 3 ] [ 2 ] + P [ 0 ] [ 2 ] * SF [ 4 ] + P [ 1 ] [ 2 ] * SF [ 3 ] + P [ 2 ] [ 2 ] * SF [ 6 ] + P [ 10 ] [ 2 ] * SPP [ 4 ] - P [ 11 ] [ 2 ] * SPP [ 5 ] - ( P [ 12 ] [ 2 ] * q0 ) / 2 ) ;
nextP [ 3 ] [ 7 ] = P [ 3 ] [ 7 ] + P [ 0 ] [ 7 ] * SF [ 4 ] + P [ 1 ] [ 7 ] * SF [ 3 ] + P [ 2 ] [ 7 ] * SF [ 6 ] + P [ 10 ] [ 7 ] * SPP [ 4 ] - P [ 11 ] [ 7 ] * SPP [ 5 ] - ( P [ 12 ] [ 7 ] * q0 ) / 2 + dt * ( P [ 3 ] [ 4 ] + P [ 0 ] [ 4 ] * SF [ 4 ] + P [ 1 ] [ 4 ] * SF [ 3 ] + P [ 2 ] [ 4 ] * SF [ 6 ] + P [ 10 ] [ 4 ] * SPP [ 4 ] - P [ 11 ] [ 4 ] * SPP [ 5 ] - ( P [ 12 ] [ 4 ] * q0 ) / 2 ) ;
nextP [ 3 ] [ 8 ] = P [ 3 ] [ 8 ] + P [ 0 ] [ 8 ] * SF [ 4 ] + P [ 1 ] [ 8 ] * SF [ 3 ] + P [ 2 ] [ 8 ] * SF [ 6 ] + P [ 10 ] [ 8 ] * SPP [ 4 ] - P [ 11 ] [ 8 ] * SPP [ 5 ] - ( P [ 12 ] [ 8 ] * q0 ) / 2 + dt * ( P [ 3 ] [ 5 ] + P [ 0 ] [ 5 ] * SF [ 4 ] + P [ 1 ] [ 5 ] * SF [ 3 ] + P [ 2 ] [ 5 ] * SF [ 6 ] + P [ 10 ] [ 5 ] * SPP [ 4 ] - P [ 11 ] [ 5 ] * SPP [ 5 ] - ( P [ 12 ] [ 5 ] * q0 ) / 2 ) ;
nextP [ 3 ] [ 9 ] = P [ 3 ] [ 9 ] + P [ 0 ] [ 9 ] * SF [ 4 ] + P [ 1 ] [ 9 ] * SF [ 3 ] + P [ 2 ] [ 9 ] * SF [ 6 ] + P [ 10 ] [ 9 ] * SPP [ 4 ] - P [ 11 ] [ 9 ] * SPP [ 5 ] - ( P [ 12 ] [ 9 ] * q0 ) / 2 + dt * ( P [ 3 ] [ 6 ] + P [ 0 ] [ 6 ] * SF [ 4 ] + P [ 1 ] [ 6 ] * SF [ 3 ] + P [ 2 ] [ 6 ] * SF [ 6 ] + P [ 10 ] [ 6 ] * SPP [ 4 ] - P [ 11 ] [ 6 ] * SPP [ 5 ] - ( P [ 12 ] [ 6 ] * q0 ) / 2 ) ;
nextP [ 3 ] [ 10 ] = P [ 3 ] [ 10 ] + P [ 0 ] [ 10 ] * SF [ 4 ] + P [ 1 ] [ 10 ] * SF [ 3 ] + P [ 2 ] [ 10 ] * SF [ 6 ] + P [ 10 ] [ 10 ] * SPP [ 4 ] - P [ 11 ] [ 10 ] * SPP [ 5 ] - ( P [ 12 ] [ 10 ] * q0 ) / 2 ;
nextP [ 3 ] [ 11 ] = P [ 3 ] [ 11 ] + P [ 0 ] [ 11 ] * SF [ 4 ] + P [ 1 ] [ 11 ] * SF [ 3 ] + P [ 2 ] [ 11 ] * SF [ 6 ] + P [ 10 ] [ 11 ] * SPP [ 4 ] - P [ 11 ] [ 11 ] * SPP [ 5 ] - ( P [ 12 ] [ 11 ] * q0 ) / 2 ;
nextP [ 3 ] [ 12 ] = P [ 3 ] [ 12 ] + P [ 0 ] [ 12 ] * SF [ 4 ] + P [ 1 ] [ 12 ] * SF [ 3 ] + P [ 2 ] [ 12 ] * SF [ 6 ] + P [ 10 ] [ 12 ] * SPP [ 4 ] - P [ 11 ] [ 12 ] * SPP [ 5 ] - ( P [ 12 ] [ 12 ] * q0 ) / 2 ;
nextP [ 3 ] [ 13 ] = P [ 3 ] [ 13 ] + P [ 0 ] [ 13 ] * SF [ 4 ] + P [ 1 ] [ 13 ] * SF [ 3 ] + P [ 2 ] [ 13 ] * SF [ 6 ] + P [ 10 ] [ 13 ] * SPP [ 4 ] - P [ 11 ] [ 13 ] * SPP [ 5 ] - ( P [ 12 ] [ 13 ] * q0 ) / 2 ;
nextP [ 3 ] [ 14 ] = P [ 3 ] [ 14 ] + P [ 0 ] [ 14 ] * SF [ 4 ] + P [ 1 ] [ 14 ] * SF [ 3 ] + P [ 2 ] [ 14 ] * SF [ 6 ] + P [ 10 ] [ 14 ] * SPP [ 4 ] - P [ 11 ] [ 14 ] * SPP [ 5 ] - ( P [ 12 ] [ 14 ] * q0 ) / 2 ;
nextP [ 3 ] [ 15 ] = P [ 3 ] [ 15 ] + P [ 0 ] [ 15 ] * SF [ 4 ] + P [ 1 ] [ 15 ] * SF [ 3 ] + P [ 2 ] [ 15 ] * SF [ 6 ] + P [ 10 ] [ 15 ] * SPP [ 4 ] - P [ 11 ] [ 15 ] * SPP [ 5 ] - ( P [ 12 ] [ 15 ] * q0 ) / 2 ;
nextP [ 3 ] [ 16 ] = P [ 3 ] [ 16 ] + P [ 0 ] [ 16 ] * SF [ 4 ] + P [ 1 ] [ 16 ] * SF [ 3 ] + P [ 2 ] [ 16 ] * SF [ 6 ] + P [ 10 ] [ 16 ] * SPP [ 4 ] - P [ 11 ] [ 16 ] * SPP [ 5 ] - ( P [ 12 ] [ 16 ] * q0 ) / 2 ;
nextP [ 3 ] [ 17 ] = P [ 3 ] [ 17 ] + P [ 0 ] [ 17 ] * SF [ 4 ] + P [ 1 ] [ 17 ] * SF [ 3 ] + P [ 2 ] [ 17 ] * SF [ 6 ] + P [ 10 ] [ 17 ] * SPP [ 4 ] - P [ 11 ] [ 17 ] * SPP [ 5 ] - ( P [ 12 ] [ 17 ] * q0 ) / 2 ;
nextP [ 3 ] [ 18 ] = P [ 3 ] [ 18 ] + P [ 0 ] [ 18 ] * SF [ 4 ] + P [ 1 ] [ 18 ] * SF [ 3 ] + P [ 2 ] [ 18 ] * SF [ 6 ] + P [ 10 ] [ 18 ] * SPP [ 4 ] - P [ 11 ] [ 18 ] * SPP [ 5 ] - ( P [ 12 ] [ 18 ] * q0 ) / 2 ;
nextP [ 3 ] [ 19 ] = P [ 3 ] [ 19 ] + P [ 0 ] [ 19 ] * SF [ 4 ] + P [ 1 ] [ 19 ] * SF [ 3 ] + P [ 2 ] [ 19 ] * SF [ 6 ] + P [ 10 ] [ 19 ] * SPP [ 4 ] - P [ 11 ] [ 19 ] * SPP [ 5 ] - ( P [ 12 ] [ 19 ] * q0 ) / 2 ;
nextP [ 3 ] [ 20 ] = P [ 3 ] [ 20 ] + P [ 0 ] [ 20 ] * SF [ 4 ] + P [ 1 ] [ 20 ] * SF [ 3 ] + P [ 2 ] [ 20 ] * SF [ 6 ] + P [ 10 ] [ 20 ] * SPP [ 4 ] - P [ 11 ] [ 20 ] * SPP [ 5 ] - ( P [ 12 ] [ 20 ] * q0 ) / 2 ;
nextP [ 4 ] [ 0 ] = P [ 4 ] [ 0 ] + P [ 0 ] [ 0 ] * SF [ 2 ] + P [ 1 ] [ 0 ] * SF [ 0 ] + P [ 2 ] [ 0 ] * SPP [ 0 ] - P [ 3 ] [ 0 ] * SPP [ 2 ] + SF [ 6 ] * ( P [ 4 ] [ 1 ] + P [ 0 ] [ 1 ] * SF [ 2 ] + P [ 1 ] [ 1 ] * SF [ 0 ] + P [ 2 ] [ 1 ] * SPP [ 0 ] - P [ 3 ] [ 1 ] * SPP [ 2 ] ) + SPP [ 7 ] * ( P [ 4 ] [ 2 ] + P [ 0 ] [ 2 ] * SF [ 2 ] + P [ 1 ] [ 2 ] * SF [ 0 ] + P [ 2 ] [ 2 ] * SPP [ 0 ] - P [ 3 ] [ 2 ] * SPP [ 2 ] ) + SPP [ 6 ] * ( P [ 4 ] [ 3 ] + P [ 0 ] [ 3 ] * SF [ 2 ] + P [ 1 ] [ 3 ] * SF [ 0 ] + P [ 2 ] [ 3 ] * SPP [ 0 ] - P [ 3 ] [ 3 ] * SPP [ 2 ] ) + SPP [ 5 ] * ( P [ 4 ] [ 10 ] + P [ 0 ] [ 10 ] * SF [ 2 ] + P [ 1 ] [ 10 ] * SF [ 0 ] + P [ 2 ] [ 10 ] * SPP [ 0 ] - P [ 3 ] [ 10 ] * SPP [ 2 ] ) + SPP [ 4 ] * ( P [ 4 ] [ 11 ] + P [ 0 ] [ 11 ] * SF [ 2 ] + P [ 1 ] [ 11 ] * SF [ 0 ] + P [ 2 ] [ 11 ] * SPP [ 0 ] - P [ 3 ] [ 11 ] * SPP [ 2 ] ) + SPP [ 3 ] * ( P [ 4 ] [ 12 ] + P [ 0 ] [ 12 ] * SF [ 2 ] + P [ 1 ] [ 12 ] * SF [ 0 ] + P [ 2 ] [ 12 ] * SPP [ 0 ] - P [ 3 ] [ 12 ] * SPP [ 2 ] ) ;
nextP [ 4 ] [ 1 ] = P [ 4 ] [ 1 ] + P [ 0 ] [ 1 ] * SF [ 2 ] + P [ 1 ] [ 1 ] * SF [ 0 ] + P [ 2 ] [ 1 ] * SPP [ 0 ] - P [ 3 ] [ 1 ] * SPP [ 2 ] + SF [ 5 ] * ( P [ 4 ] [ 0 ] + P [ 0 ] [ 0 ] * SF [ 2 ] + P [ 1 ] [ 0 ] * SF [ 0 ] + P [ 2 ] [ 0 ] * SPP [ 0 ] - P [ 3 ] [ 0 ] * SPP [ 2 ] ) + SF [ 4 ] * ( P [ 4 ] [ 2 ] + P [ 0 ] [ 2 ] * SF [ 2 ] + P [ 1 ] [ 2 ] * SF [ 0 ] + P [ 2 ] [ 2 ] * SPP [ 0 ] - P [ 3 ] [ 2 ] * SPP [ 2 ] ) + SPP [ 7 ] * ( P [ 4 ] [ 3 ] + P [ 0 ] [ 3 ] * SF [ 2 ] + P [ 1 ] [ 3 ] * SF [ 0 ] + P [ 2 ] [ 3 ] * SPP [ 0 ] - P [ 3 ] [ 3 ] * SPP [ 2 ] ) + SPP [ 3 ] * ( P [ 4 ] [ 11 ] + P [ 0 ] [ 11 ] * SF [ 2 ] + P [ 1 ] [ 11 ] * SF [ 0 ] + P [ 2 ] [ 11 ] * SPP [ 0 ] - P [ 3 ] [ 11 ] * SPP [ 2 ] ) - SPP [ 4 ] * ( P [ 4 ] [ 12 ] + P [ 0 ] [ 12 ] * SF [ 2 ] + P [ 1 ] [ 12 ] * SF [ 0 ] + P [ 2 ] [ 12 ] * SPP [ 0 ] - P [ 3 ] [ 12 ] * SPP [ 2 ] ) - ( q0 * ( P [ 4 ] [ 10 ] + P [ 0 ] [ 10 ] * SF [ 2 ] + P [ 1 ] [ 10 ] * SF [ 0 ] + P [ 2 ] [ 10 ] * SPP [ 0 ] - P [ 3 ] [ 10 ] * SPP [ 2 ] ) ) / 2 ;
nextP [ 4 ] [ 2 ] = P [ 4 ] [ 2 ] + P [ 0 ] [ 2 ] * SF [ 2 ] + P [ 1 ] [ 2 ] * SF [ 0 ] + P [ 2 ] [ 2 ] * SPP [ 0 ] - P [ 3 ] [ 2 ] * SPP [ 2 ] + SF [ 3 ] * ( P [ 4 ] [ 0 ] + P [ 0 ] [ 0 ] * SF [ 2 ] + P [ 1 ] [ 0 ] * SF [ 0 ] + P [ 2 ] [ 0 ] * SPP [ 0 ] - P [ 3 ] [ 0 ] * SPP [ 2 ] ) + SF [ 5 ] * ( P [ 4 ] [ 3 ] + P [ 0 ] [ 3 ] * SF [ 2 ] + P [ 1 ] [ 3 ] * SF [ 0 ] + P [ 2 ] [ 3 ] * SPP [ 0 ] - P [ 3 ] [ 3 ] * SPP [ 2 ] ) + SPP [ 6 ] * ( P [ 4 ] [ 1 ] + P [ 0 ] [ 1 ] * SF [ 2 ] + P [ 1 ] [ 1 ] * SF [ 0 ] + P [ 2 ] [ 1 ] * SPP [ 0 ] - P [ 3 ] [ 1 ] * SPP [ 2 ] ) - SPP [ 3 ] * ( P [ 4 ] [ 10 ] + P [ 0 ] [ 10 ] * SF [ 2 ] + P [ 1 ] [ 10 ] * SF [ 0 ] + P [ 2 ] [ 10 ] * SPP [ 0 ] - P [ 3 ] [ 10 ] * SPP [ 2 ] ) + SPP [ 5 ] * ( P [ 4 ] [ 12 ] + P [ 0 ] [ 12 ] * SF [ 2 ] + P [ 1 ] [ 12 ] * SF [ 0 ] + P [ 2 ] [ 12 ] * SPP [ 0 ] - P [ 3 ] [ 12 ] * SPP [ 2 ] ) - ( q0 * ( P [ 4 ] [ 11 ] + P [ 0 ] [ 11 ] * SF [ 2 ] + P [ 1 ] [ 11 ] * SF [ 0 ] + P [ 2 ] [ 11 ] * SPP [ 0 ] - P [ 3 ] [ 11 ] * SPP [ 2 ] ) ) / 2 ;
nextP [ 4 ] [ 3 ] = P [ 4 ] [ 3 ] + P [ 0 ] [ 3 ] * SF [ 2 ] + P [ 1 ] [ 3 ] * SF [ 0 ] + P [ 2 ] [ 3 ] * SPP [ 0 ] - P [ 3 ] [ 3 ] * SPP [ 2 ] + SF [ 4 ] * ( P [ 4 ] [ 0 ] + P [ 0 ] [ 0 ] * SF [ 2 ] + P [ 1 ] [ 0 ] * SF [ 0 ] + P [ 2 ] [ 0 ] * SPP [ 0 ] - P [ 3 ] [ 0 ] * SPP [ 2 ] ) + SF [ 3 ] * ( P [ 4 ] [ 1 ] + P [ 0 ] [ 1 ] * SF [ 2 ] + P [ 1 ] [ 1 ] * SF [ 0 ] + P [ 2 ] [ 1 ] * SPP [ 0 ] - P [ 3 ] [ 1 ] * SPP [ 2 ] ) + SF [ 6 ] * ( P [ 4 ] [ 2 ] + P [ 0 ] [ 2 ] * SF [ 2 ] + P [ 1 ] [ 2 ] * SF [ 0 ] + P [ 2 ] [ 2 ] * SPP [ 0 ] - P [ 3 ] [ 2 ] * SPP [ 2 ] ) + SPP [ 4 ] * ( P [ 4 ] [ 10 ] + P [ 0 ] [ 10 ] * SF [ 2 ] + P [ 1 ] [ 10 ] * SF [ 0 ] + P [ 2 ] [ 10 ] * SPP [ 0 ] - P [ 3 ] [ 10 ] * SPP [ 2 ] ) - SPP [ 5 ] * ( P [ 4 ] [ 11 ] + P [ 0 ] [ 11 ] * SF [ 2 ] + P [ 1 ] [ 11 ] * SF [ 0 ] + P [ 2 ] [ 11 ] * SPP [ 0 ] - P [ 3 ] [ 11 ] * SPP [ 2 ] ) - ( q0 * ( P [ 4 ] [ 12 ] + P [ 0 ] [ 12 ] * SF [ 2 ] + P [ 1 ] [ 12 ] * SF [ 0 ] + P [ 2 ] [ 12 ] * SPP [ 0 ] - P [ 3 ] [ 12 ] * SPP [ 2 ] ) ) / 2 ;
nextP [ 4 ] [ 4 ] = P [ 4 ] [ 4 ] + P [ 0 ] [ 4 ] * SF [ 2 ] + P [ 1 ] [ 4 ] * SF [ 0 ] + P [ 2 ] [ 4 ] * SPP [ 0 ] - P [ 3 ] [ 4 ] * SPP [ 2 ] + dvyCov * sq ( SG [ 7 ] - 2 * q0 * q3 ) + dvzCov * sq ( SG [ 6 ] + 2 * q0 * q2 ) + SF [ 2 ] * ( P [ 4 ] [ 0 ] + P [ 0 ] [ 0 ] * SF [ 2 ] + P [ 1 ] [ 0 ] * SF [ 0 ] + P [ 2 ] [ 0 ] * SPP [ 0 ] - P [ 3 ] [ 0 ] * SPP [ 2 ] ) + SF [ 0 ] * ( P [ 4 ] [ 1 ] + P [ 0 ] [ 1 ] * SF [ 2 ] + P [ 1 ] [ 1 ] * SF [ 0 ] + P [ 2 ] [ 1 ] * SPP [ 0 ] - P [ 3 ] [ 1 ] * SPP [ 2 ] ) + SPP [ 0 ] * ( P [ 4 ] [ 2 ] + P [ 0 ] [ 2 ] * SF [ 2 ] + P [ 1 ] [ 2 ] * SF [ 0 ] + P [ 2 ] [ 2 ] * SPP [ 0 ] - P [ 3 ] [ 2 ] * SPP [ 2 ] ) - SPP [ 2 ] * ( P [ 4 ] [ 3 ] + P [ 0 ] [ 3 ] * SF [ 2 ] + P [ 1 ] [ 3 ] * SF [ 0 ] + P [ 2 ] [ 3 ] * SPP [ 0 ] - P [ 3 ] [ 3 ] * SPP [ 2 ] ) + dvxCov * sq ( SG [ 1 ] + SG [ 2 ] - SG [ 3 ] - SG [ 4 ] ) ;
nextP [ 4 ] [ 5 ] = P [ 4 ] [ 5 ] + SQ [ 2 ] + P [ 0 ] [ 5 ] * SF [ 2 ] + P [ 1 ] [ 5 ] * SF [ 0 ] + P [ 2 ] [ 5 ] * SPP [ 0 ] - P [ 3 ] [ 5 ] * SPP [ 2 ] + SF [ 1 ] * ( P [ 4 ] [ 0 ] + P [ 0 ] [ 0 ] * SF [ 2 ] + P [ 1 ] [ 0 ] * SF [ 0 ] + P [ 2 ] [ 0 ] * SPP [ 0 ] - P [ 3 ] [ 0 ] * SPP [ 2 ] ) + SF [ 0 ] * ( P [ 4 ] [ 2 ] + P [ 0 ] [ 2 ] * SF [ 2 ] + P [ 1 ] [ 2 ] * SF [ 0 ] + P [ 2 ] [ 2 ] * SPP [ 0 ] - P [ 3 ] [ 2 ] * SPP [ 2 ] ) + SF [ 2 ] * ( P [ 4 ] [ 3 ] + P [ 0 ] [ 3 ] * SF [ 2 ] + P [ 1 ] [ 3 ] * SF [ 0 ] + P [ 2 ] [ 3 ] * SPP [ 0 ] - P [ 3 ] [ 3 ] * SPP [ 2 ] ) - SPP [ 0 ] * ( P [ 4 ] [ 1 ] + P [ 0 ] [ 1 ] * SF [ 2 ] + P [ 1 ] [ 1 ] * SF [ 0 ] + P [ 2 ] [ 1 ] * SPP [ 0 ] - P [ 3 ] [ 1 ] * SPP [ 2 ] ) ;
nextP [ 4 ] [ 6 ] = P [ 4 ] [ 6 ] + SQ [ 1 ] + P [ 0 ] [ 6 ] * SF [ 2 ] + P [ 1 ] [ 6 ] * SF [ 0 ] + P [ 2 ] [ 6 ] * SPP [ 0 ] - P [ 3 ] [ 6 ] * SPP [ 2 ] + SF [ 1 ] * ( P [ 4 ] [ 1 ] + P [ 0 ] [ 1 ] * SF [ 2 ] + P [ 1 ] [ 1 ] * SF [ 0 ] + P [ 2 ] [ 1 ] * SPP [ 0 ] - P [ 3 ] [ 1 ] * SPP [ 2 ] ) + SF [ 0 ] * ( P [ 4 ] [ 3 ] + P [ 0 ] [ 3 ] * SF [ 2 ] + P [ 1 ] [ 3 ] * SF [ 0 ] + P [ 2 ] [ 3 ] * SPP [ 0 ] - P [ 3 ] [ 3 ] * SPP [ 2 ] ) + SPP [ 0 ] * ( P [ 4 ] [ 0 ] + P [ 0 ] [ 0 ] * SF [ 2 ] + P [ 1 ] [ 0 ] * SF [ 0 ] + P [ 2 ] [ 0 ] * SPP [ 0 ] - P [ 3 ] [ 0 ] * SPP [ 2 ] ) - SPP [ 1 ] * ( P [ 4 ] [ 2 ] + P [ 0 ] [ 2 ] * SF [ 2 ] + P [ 1 ] [ 2 ] * SF [ 0 ] + P [ 2 ] [ 2 ] * SPP [ 0 ] - P [ 3 ] [ 2 ] * SPP [ 2 ] ) ;
nextP [ 4 ] [ 7 ] = P [ 4 ] [ 7 ] + P [ 0 ] [ 7 ] * SF [ 2 ] + P [ 1 ] [ 7 ] * SF [ 0 ] + P [ 2 ] [ 7 ] * SPP [ 0 ] - P [ 3 ] [ 7 ] * SPP [ 2 ] + dt * ( P [ 4 ] [ 4 ] + P [ 0 ] [ 4 ] * SF [ 2 ] + P [ 1 ] [ 4 ] * SF [ 0 ] + P [ 2 ] [ 4 ] * SPP [ 0 ] - P [ 3 ] [ 4 ] * SPP [ 2 ] ) ;
nextP [ 4 ] [ 8 ] = P [ 4 ] [ 8 ] + P [ 0 ] [ 8 ] * SF [ 2 ] + P [ 1 ] [ 8 ] * SF [ 0 ] + P [ 2 ] [ 8 ] * SPP [ 0 ] - P [ 3 ] [ 8 ] * SPP [ 2 ] + dt * ( P [ 4 ] [ 5 ] + P [ 0 ] [ 5 ] * SF [ 2 ] + P [ 1 ] [ 5 ] * SF [ 0 ] + P [ 2 ] [ 5 ] * SPP [ 0 ] - P [ 3 ] [ 5 ] * SPP [ 2 ] ) ;
nextP [ 4 ] [ 9 ] = P [ 4 ] [ 9 ] + P [ 0 ] [ 9 ] * SF [ 2 ] + P [ 1 ] [ 9 ] * SF [ 0 ] + P [ 2 ] [ 9 ] * SPP [ 0 ] - P [ 3 ] [ 9 ] * SPP [ 2 ] + dt * ( P [ 4 ] [ 6 ] + P [ 0 ] [ 6 ] * SF [ 2 ] + P [ 1 ] [ 6 ] * SF [ 0 ] + P [ 2 ] [ 6 ] * SPP [ 0 ] - P [ 3 ] [ 6 ] * SPP [ 2 ] ) ;
nextP [ 4 ] [ 10 ] = P [ 4 ] [ 10 ] + P [ 0 ] [ 10 ] * SF [ 2 ] + P [ 1 ] [ 10 ] * SF [ 0 ] + P [ 2 ] [ 10 ] * SPP [ 0 ] - P [ 3 ] [ 10 ] * SPP [ 2 ] ;
nextP [ 4 ] [ 11 ] = P [ 4 ] [ 11 ] + P [ 0 ] [ 11 ] * SF [ 2 ] + P [ 1 ] [ 11 ] * SF [ 0 ] + P [ 2 ] [ 11 ] * SPP [ 0 ] - P [ 3 ] [ 11 ] * SPP [ 2 ] ;
nextP [ 4 ] [ 12 ] = P [ 4 ] [ 12 ] + P [ 0 ] [ 12 ] * SF [ 2 ] + P [ 1 ] [ 12 ] * SF [ 0 ] + P [ 2 ] [ 12 ] * SPP [ 0 ] - P [ 3 ] [ 12 ] * SPP [ 2 ] ;
nextP [ 4 ] [ 13 ] = P [ 4 ] [ 13 ] + P [ 0 ] [ 13 ] * SF [ 2 ] + P [ 1 ] [ 13 ] * SF [ 0 ] + P [ 2 ] [ 13 ] * SPP [ 0 ] - P [ 3 ] [ 13 ] * SPP [ 2 ] ;
nextP [ 4 ] [ 14 ] = P [ 4 ] [ 14 ] + P [ 0 ] [ 14 ] * SF [ 2 ] + P [ 1 ] [ 14 ] * SF [ 0 ] + P [ 2 ] [ 14 ] * SPP [ 0 ] - P [ 3 ] [ 14 ] * SPP [ 2 ] ;
nextP [ 4 ] [ 15 ] = P [ 4 ] [ 15 ] + P [ 0 ] [ 15 ] * SF [ 2 ] + P [ 1 ] [ 15 ] * SF [ 0 ] + P [ 2 ] [ 15 ] * SPP [ 0 ] - P [ 3 ] [ 15 ] * SPP [ 2 ] ;
nextP [ 4 ] [ 16 ] = P [ 4 ] [ 16 ] + P [ 0 ] [ 16 ] * SF [ 2 ] + P [ 1 ] [ 16 ] * SF [ 0 ] + P [ 2 ] [ 16 ] * SPP [ 0 ] - P [ 3 ] [ 16 ] * SPP [ 2 ] ;
nextP [ 4 ] [ 17 ] = P [ 4 ] [ 17 ] + P [ 0 ] [ 17 ] * SF [ 2 ] + P [ 1 ] [ 17 ] * SF [ 0 ] + P [ 2 ] [ 17 ] * SPP [ 0 ] - P [ 3 ] [ 17 ] * SPP [ 2 ] ;
nextP [ 4 ] [ 18 ] = P [ 4 ] [ 18 ] + P [ 0 ] [ 18 ] * SF [ 2 ] + P [ 1 ] [ 18 ] * SF [ 0 ] + P [ 2 ] [ 18 ] * SPP [ 0 ] - P [ 3 ] [ 18 ] * SPP [ 2 ] ;
nextP [ 4 ] [ 19 ] = P [ 4 ] [ 19 ] + P [ 0 ] [ 19 ] * SF [ 2 ] + P [ 1 ] [ 19 ] * SF [ 0 ] + P [ 2 ] [ 19 ] * SPP [ 0 ] - P [ 3 ] [ 19 ] * SPP [ 2 ] ;
nextP [ 4 ] [ 20 ] = P [ 4 ] [ 20 ] + P [ 0 ] [ 20 ] * SF [ 2 ] + P [ 1 ] [ 20 ] * SF [ 0 ] + P [ 2 ] [ 20 ] * SPP [ 0 ] - P [ 3 ] [ 20 ] * SPP [ 2 ] ;
nextP [ 5 ] [ 0 ] = P [ 5 ] [ 0 ] + P [ 0 ] [ 0 ] * SF [ 1 ] + P [ 2 ] [ 0 ] * SF [ 0 ] + P [ 3 ] [ 0 ] * SF [ 2 ] - P [ 1 ] [ 0 ] * SPP [ 0 ] + SF [ 6 ] * ( P [ 5 ] [ 1 ] + P [ 0 ] [ 1 ] * SF [ 1 ] + P [ 2 ] [ 1 ] * SF [ 0 ] + P [ 3 ] [ 1 ] * SF [ 2 ] - P [ 1 ] [ 1 ] * SPP [ 0 ] ) + SPP [ 7 ] * ( P [ 5 ] [ 2 ] + P [ 0 ] [ 2 ] * SF [ 1 ] + P [ 2 ] [ 2 ] * SF [ 0 ] + P [ 3 ] [ 2 ] * SF [ 2 ] - P [ 1 ] [ 2 ] * SPP [ 0 ] ) + SPP [ 6 ] * ( P [ 5 ] [ 3 ] + P [ 0 ] [ 3 ] * SF [ 1 ] + P [ 2 ] [ 3 ] * SF [ 0 ] + P [ 3 ] [ 3 ] * SF [ 2 ] - P [ 1 ] [ 3 ] * SPP [ 0 ] ) + SPP [ 5 ] * ( P [ 5 ] [ 10 ] + P [ 0 ] [ 10 ] * SF [ 1 ] + P [ 2 ] [ 10 ] * SF [ 0 ] + P [ 3 ] [ 10 ] * SF [ 2 ] - P [ 1 ] [ 10 ] * SPP [ 0 ] ) + SPP [ 4 ] * ( P [ 5 ] [ 11 ] + P [ 0 ] [ 11 ] * SF [ 1 ] + P [ 2 ] [ 11 ] * SF [ 0 ] + P [ 3 ] [ 11 ] * SF [ 2 ] - P [ 1 ] [ 11 ] * SPP [ 0 ] ) + SPP [ 3 ] * ( P [ 5 ] [ 12 ] + P [ 0 ] [ 12 ] * SF [ 1 ] + P [ 2 ] [ 12 ] * SF [ 0 ] + P [ 3 ] [ 12 ] * SF [ 2 ] - P [ 1 ] [ 12 ] * SPP [ 0 ] ) ;
nextP [ 5 ] [ 1 ] = P [ 5 ] [ 1 ] + P [ 0 ] [ 1 ] * SF [ 1 ] + P [ 2 ] [ 1 ] * SF [ 0 ] + P [ 3 ] [ 1 ] * SF [ 2 ] - P [ 1 ] [ 1 ] * SPP [ 0 ] + SF [ 5 ] * ( P [ 5 ] [ 0 ] + P [ 0 ] [ 0 ] * SF [ 1 ] + P [ 2 ] [ 0 ] * SF [ 0 ] + P [ 3 ] [ 0 ] * SF [ 2 ] - P [ 1 ] [ 0 ] * SPP [ 0 ] ) + SF [ 4 ] * ( P [ 5 ] [ 2 ] + P [ 0 ] [ 2 ] * SF [ 1 ] + P [ 2 ] [ 2 ] * SF [ 0 ] + P [ 3 ] [ 2 ] * SF [ 2 ] - P [ 1 ] [ 2 ] * SPP [ 0 ] ) + SPP [ 7 ] * ( P [ 5 ] [ 3 ] + P [ 0 ] [ 3 ] * SF [ 1 ] + P [ 2 ] [ 3 ] * SF [ 0 ] + P [ 3 ] [ 3 ] * SF [ 2 ] - P [ 1 ] [ 3 ] * SPP [ 0 ] ) + SPP [ 3 ] * ( P [ 5 ] [ 11 ] + P [ 0 ] [ 11 ] * SF [ 1 ] + P [ 2 ] [ 11 ] * SF [ 0 ] + P [ 3 ] [ 11 ] * SF [ 2 ] - P [ 1 ] [ 11 ] * SPP [ 0 ] ) - SPP [ 4 ] * ( P [ 5 ] [ 12 ] + P [ 0 ] [ 12 ] * SF [ 1 ] + P [ 2 ] [ 12 ] * SF [ 0 ] + P [ 3 ] [ 12 ] * SF [ 2 ] - P [ 1 ] [ 12 ] * SPP [ 0 ] ) - ( q0 * ( P [ 5 ] [ 10 ] + P [ 0 ] [ 10 ] * SF [ 1 ] + P [ 2 ] [ 10 ] * SF [ 0 ] + P [ 3 ] [ 10 ] * SF [ 2 ] - P [ 1 ] [ 10 ] * SPP [ 0 ] ) ) / 2 ;
nextP [ 5 ] [ 2 ] = P [ 5 ] [ 2 ] + P [ 0 ] [ 2 ] * SF [ 1 ] + P [ 2 ] [ 2 ] * SF [ 0 ] + P [ 3 ] [ 2 ] * SF [ 2 ] - P [ 1 ] [ 2 ] * SPP [ 0 ] + SF [ 3 ] * ( P [ 5 ] [ 0 ] + P [ 0 ] [ 0 ] * SF [ 1 ] + P [ 2 ] [ 0 ] * SF [ 0 ] + P [ 3 ] [ 0 ] * SF [ 2 ] - P [ 1 ] [ 0 ] * SPP [ 0 ] ) + SF [ 5 ] * ( P [ 5 ] [ 3 ] + P [ 0 ] [ 3 ] * SF [ 1 ] + P [ 2 ] [ 3 ] * SF [ 0 ] + P [ 3 ] [ 3 ] * SF [ 2 ] - P [ 1 ] [ 3 ] * SPP [ 0 ] ) + SPP [ 6 ] * ( P [ 5 ] [ 1 ] + P [ 0 ] [ 1 ] * SF [ 1 ] + P [ 2 ] [ 1 ] * SF [ 0 ] + P [ 3 ] [ 1 ] * SF [ 2 ] - P [ 1 ] [ 1 ] * SPP [ 0 ] ) - SPP [ 3 ] * ( P [ 5 ] [ 10 ] + P [ 0 ] [ 10 ] * SF [ 1 ] + P [ 2 ] [ 10 ] * SF [ 0 ] + P [ 3 ] [ 10 ] * SF [ 2 ] - P [ 1 ] [ 10 ] * SPP [ 0 ] ) + SPP [ 5 ] * ( P [ 5 ] [ 12 ] + P [ 0 ] [ 12 ] * SF [ 1 ] + P [ 2 ] [ 12 ] * SF [ 0 ] + P [ 3 ] [ 12 ] * SF [ 2 ] - P [ 1 ] [ 12 ] * SPP [ 0 ] ) - ( q0 * ( P [ 5 ] [ 11 ] + P [ 0 ] [ 11 ] * SF [ 1 ] + P [ 2 ] [ 11 ] * SF [ 0 ] + P [ 3 ] [ 11 ] * SF [ 2 ] - P [ 1 ] [ 11 ] * SPP [ 0 ] ) ) / 2 ;
nextP [ 5 ] [ 3 ] = P [ 5 ] [ 3 ] + P [ 0 ] [ 3 ] * SF [ 1 ] + P [ 2 ] [ 3 ] * SF [ 0 ] + P [ 3 ] [ 3 ] * SF [ 2 ] - P [ 1 ] [ 3 ] * SPP [ 0 ] + SF [ 4 ] * ( P [ 5 ] [ 0 ] + P [ 0 ] [ 0 ] * SF [ 1 ] + P [ 2 ] [ 0 ] * SF [ 0 ] + P [ 3 ] [ 0 ] * SF [ 2 ] - P [ 1 ] [ 0 ] * SPP [ 0 ] ) + SF [ 3 ] * ( P [ 5 ] [ 1 ] + P [ 0 ] [ 1 ] * SF [ 1 ] + P [ 2 ] [ 1 ] * SF [ 0 ] + P [ 3 ] [ 1 ] * SF [ 2 ] - P [ 1 ] [ 1 ] * SPP [ 0 ] ) + SF [ 6 ] * ( P [ 5 ] [ 2 ] + P [ 0 ] [ 2 ] * SF [ 1 ] + P [ 2 ] [ 2 ] * SF [ 0 ] + P [ 3 ] [ 2 ] * SF [ 2 ] - P [ 1 ] [ 2 ] * SPP [ 0 ] ) + SPP [ 4 ] * ( P [ 5 ] [ 10 ] + P [ 0 ] [ 10 ] * SF [ 1 ] + P [ 2 ] [ 10 ] * SF [ 0 ] + P [ 3 ] [ 10 ] * SF [ 2 ] - P [ 1 ] [ 10 ] * SPP [ 0 ] ) - SPP [ 5 ] * ( P [ 5 ] [ 11 ] + P [ 0 ] [ 11 ] * SF [ 1 ] + P [ 2 ] [ 11 ] * SF [ 0 ] + P [ 3 ] [ 11 ] * SF [ 2 ] - P [ 1 ] [ 11 ] * SPP [ 0 ] ) - ( q0 * ( P [ 5 ] [ 12 ] + P [ 0 ] [ 12 ] * SF [ 1 ] + P [ 2 ] [ 12 ] * SF [ 0 ] + P [ 3 ] [ 12 ] * SF [ 2 ] - P [ 1 ] [ 12 ] * SPP [ 0 ] ) ) / 2 ;
nextP [ 5 ] [ 4 ] = P [ 5 ] [ 4 ] + SQ [ 2 ] + P [ 0 ] [ 4 ] * SF [ 1 ] + P [ 2 ] [ 4 ] * SF [ 0 ] + P [ 3 ] [ 4 ] * SF [ 2 ] - P [ 1 ] [ 4 ] * SPP [ 0 ] + SF [ 2 ] * ( P [ 5 ] [ 0 ] + P [ 0 ] [ 0 ] * SF [ 1 ] + P [ 2 ] [ 0 ] * SF [ 0 ] + P [ 3 ] [ 0 ] * SF [ 2 ] - P [ 1 ] [ 0 ] * SPP [ 0 ] ) + SF [ 0 ] * ( P [ 5 ] [ 1 ] + P [ 0 ] [ 1 ] * SF [ 1 ] + P [ 2 ] [ 1 ] * SF [ 0 ] + P [ 3 ] [ 1 ] * SF [ 2 ] - P [ 1 ] [ 1 ] * SPP [ 0 ] ) + SPP [ 0 ] * ( P [ 5 ] [ 2 ] + P [ 0 ] [ 2 ] * SF [ 1 ] + P [ 2 ] [ 2 ] * SF [ 0 ] + P [ 3 ] [ 2 ] * SF [ 2 ] - P [ 1 ] [ 2 ] * SPP [ 0 ] ) - SPP [ 2 ] * ( P [ 5 ] [ 3 ] + P [ 0 ] [ 3 ] * SF [ 1 ] + P [ 2 ] [ 3 ] * SF [ 0 ] + P [ 3 ] [ 3 ] * SF [ 2 ] - P [ 1 ] [ 3 ] * SPP [ 0 ] ) ;
nextP [ 5 ] [ 5 ] = P [ 5 ] [ 5 ] + P [ 0 ] [ 5 ] * SF [ 1 ] + P [ 2 ] [ 5 ] * SF [ 0 ] + P [ 3 ] [ 5 ] * SF [ 2 ] - P [ 1 ] [ 5 ] * SPP [ 0 ] + dvxCov * sq ( SG [ 7 ] + 2 * q0 * q3 ) + dvzCov * sq ( SG [ 5 ] - 2 * q0 * q1 ) + SF [ 1 ] * ( P [ 5 ] [ 0 ] + P [ 0 ] [ 0 ] * SF [ 1 ] + P [ 2 ] [ 0 ] * SF [ 0 ] + P [ 3 ] [ 0 ] * SF [ 2 ] - P [ 1 ] [ 0 ] * SPP [ 0 ] ) + SF [ 0 ] * ( P [ 5 ] [ 2 ] + P [ 0 ] [ 2 ] * SF [ 1 ] + P [ 2 ] [ 2 ] * SF [ 0 ] + P [ 3 ] [ 2 ] * SF [ 2 ] - P [ 1 ] [ 2 ] * SPP [ 0 ] ) + SF [ 2 ] * ( P [ 5 ] [ 3 ] + P [ 0 ] [ 3 ] * SF [ 1 ] + P [ 2 ] [ 3 ] * SF [ 0 ] + P [ 3 ] [ 3 ] * SF [ 2 ] - P [ 1 ] [ 3 ] * SPP [ 0 ] ) - SPP [ 0 ] * ( P [ 5 ] [ 1 ] + P [ 0 ] [ 1 ] * SF [ 1 ] + P [ 2 ] [ 1 ] * SF [ 0 ] + P [ 3 ] [ 1 ] * SF [ 2 ] - P [ 1 ] [ 1 ] * SPP [ 0 ] ) + dvyCov * sq ( SG [ 1 ] - SG [ 2 ] + SG [ 3 ] - SG [ 4 ] ) ;
nextP [ 5 ] [ 6 ] = P [ 5 ] [ 6 ] + SQ [ 0 ] + P [ 0 ] [ 6 ] * SF [ 1 ] + P [ 2 ] [ 6 ] * SF [ 0 ] + P [ 3 ] [ 6 ] * SF [ 2 ] - P [ 1 ] [ 6 ] * SPP [ 0 ] + SF [ 1 ] * ( P [ 5 ] [ 1 ] + P [ 0 ] [ 1 ] * SF [ 1 ] + P [ 2 ] [ 1 ] * SF [ 0 ] + P [ 3 ] [ 1 ] * SF [ 2 ] - P [ 1 ] [ 1 ] * SPP [ 0 ] ) + SF [ 0 ] * ( P [ 5 ] [ 3 ] + P [ 0 ] [ 3 ] * SF [ 1 ] + P [ 2 ] [ 3 ] * SF [ 0 ] + P [ 3 ] [ 3 ] * SF [ 2 ] - P [ 1 ] [ 3 ] * SPP [ 0 ] ) + SPP [ 0 ] * ( P [ 5 ] [ 0 ] + P [ 0 ] [ 0 ] * SF [ 1 ] + P [ 2 ] [ 0 ] * SF [ 0 ] + P [ 3 ] [ 0 ] * SF [ 2 ] - P [ 1 ] [ 0 ] * SPP [ 0 ] ) - SPP [ 1 ] * ( P [ 5 ] [ 2 ] + P [ 0 ] [ 2 ] * SF [ 1 ] + P [ 2 ] [ 2 ] * SF [ 0 ] + P [ 3 ] [ 2 ] * SF [ 2 ] - P [ 1 ] [ 2 ] * SPP [ 0 ] ) ;
nextP [ 5 ] [ 7 ] = P [ 5 ] [ 7 ] + P [ 0 ] [ 7 ] * SF [ 1 ] + P [ 2 ] [ 7 ] * SF [ 0 ] + P [ 3 ] [ 7 ] * SF [ 2 ] - P [ 1 ] [ 7 ] * SPP [ 0 ] + dt * ( P [ 5 ] [ 4 ] + P [ 0 ] [ 4 ] * SF [ 1 ] + P [ 2 ] [ 4 ] * SF [ 0 ] + P [ 3 ] [ 4 ] * SF [ 2 ] - P [ 1 ] [ 4 ] * SPP [ 0 ] ) ;
nextP [ 5 ] [ 8 ] = P [ 5 ] [ 8 ] + P [ 0 ] [ 8 ] * SF [ 1 ] + P [ 2 ] [ 8 ] * SF [ 0 ] + P [ 3 ] [ 8 ] * SF [ 2 ] - P [ 1 ] [ 8 ] * SPP [ 0 ] + dt * ( P [ 5 ] [ 5 ] + P [ 0 ] [ 5 ] * SF [ 1 ] + P [ 2 ] [ 5 ] * SF [ 0 ] + P [ 3 ] [ 5 ] * SF [ 2 ] - P [ 1 ] [ 5 ] * SPP [ 0 ] ) ;
nextP [ 5 ] [ 9 ] = P [ 5 ] [ 9 ] + P [ 0 ] [ 9 ] * SF [ 1 ] + P [ 2 ] [ 9 ] * SF [ 0 ] + P [ 3 ] [ 9 ] * SF [ 2 ] - P [ 1 ] [ 9 ] * SPP [ 0 ] + dt * ( P [ 5 ] [ 6 ] + P [ 0 ] [ 6 ] * SF [ 1 ] + P [ 2 ] [ 6 ] * SF [ 0 ] + P [ 3 ] [ 6 ] * SF [ 2 ] - P [ 1 ] [ 6 ] * SPP [ 0 ] ) ;
nextP [ 5 ] [ 10 ] = P [ 5 ] [ 10 ] + P [ 0 ] [ 10 ] * SF [ 1 ] + P [ 2 ] [ 10 ] * SF [ 0 ] + P [ 3 ] [ 10 ] * SF [ 2 ] - P [ 1 ] [ 10 ] * SPP [ 0 ] ;
nextP [ 5 ] [ 11 ] = P [ 5 ] [ 11 ] + P [ 0 ] [ 11 ] * SF [ 1 ] + P [ 2 ] [ 11 ] * SF [ 0 ] + P [ 3 ] [ 11 ] * SF [ 2 ] - P [ 1 ] [ 11 ] * SPP [ 0 ] ;
nextP [ 5 ] [ 12 ] = P [ 5 ] [ 12 ] + P [ 0 ] [ 12 ] * SF [ 1 ] + P [ 2 ] [ 12 ] * SF [ 0 ] + P [ 3 ] [ 12 ] * SF [ 2 ] - P [ 1 ] [ 12 ] * SPP [ 0 ] ;
nextP [ 5 ] [ 13 ] = P [ 5 ] [ 13 ] + P [ 0 ] [ 13 ] * SF [ 1 ] + P [ 2 ] [ 13 ] * SF [ 0 ] + P [ 3 ] [ 13 ] * SF [ 2 ] - P [ 1 ] [ 13 ] * SPP [ 0 ] ;
nextP [ 5 ] [ 14 ] = P [ 5 ] [ 14 ] + P [ 0 ] [ 14 ] * SF [ 1 ] + P [ 2 ] [ 14 ] * SF [ 0 ] + P [ 3 ] [ 14 ] * SF [ 2 ] - P [ 1 ] [ 14 ] * SPP [ 0 ] ;
nextP [ 5 ] [ 15 ] = P [ 5 ] [ 15 ] + P [ 0 ] [ 15 ] * SF [ 1 ] + P [ 2 ] [ 15 ] * SF [ 0 ] + P [ 3 ] [ 15 ] * SF [ 2 ] - P [ 1 ] [ 15 ] * SPP [ 0 ] ;
nextP [ 5 ] [ 16 ] = P [ 5 ] [ 16 ] + P [ 0 ] [ 16 ] * SF [ 1 ] + P [ 2 ] [ 16 ] * SF [ 0 ] + P [ 3 ] [ 16 ] * SF [ 2 ] - P [ 1 ] [ 16 ] * SPP [ 0 ] ;
nextP [ 5 ] [ 17 ] = P [ 5 ] [ 17 ] + P [ 0 ] [ 17 ] * SF [ 1 ] + P [ 2 ] [ 17 ] * SF [ 0 ] + P [ 3 ] [ 17 ] * SF [ 2 ] - P [ 1 ] [ 17 ] * SPP [ 0 ] ;
nextP [ 5 ] [ 18 ] = P [ 5 ] [ 18 ] + P [ 0 ] [ 18 ] * SF [ 1 ] + P [ 2 ] [ 18 ] * SF [ 0 ] + P [ 3 ] [ 18 ] * SF [ 2 ] - P [ 1 ] [ 18 ] * SPP [ 0 ] ;
nextP [ 5 ] [ 19 ] = P [ 5 ] [ 19 ] + P [ 0 ] [ 19 ] * SF [ 1 ] + P [ 2 ] [ 19 ] * SF [ 0 ] + P [ 3 ] [ 19 ] * SF [ 2 ] - P [ 1 ] [ 19 ] * SPP [ 0 ] ;
nextP [ 5 ] [ 20 ] = P [ 5 ] [ 20 ] + P [ 0 ] [ 20 ] * SF [ 1 ] + P [ 2 ] [ 20 ] * SF [ 0 ] + P [ 3 ] [ 20 ] * SF [ 2 ] - P [ 1 ] [ 20 ] * SPP [ 0 ] ;
nextP [ 6 ] [ 0 ] = P [ 6 ] [ 0 ] + P [ 1 ] [ 0 ] * SF [ 1 ] + P [ 3 ] [ 0 ] * SF [ 0 ] + P [ 0 ] [ 0 ] * SPP [ 0 ] - P [ 2 ] [ 0 ] * SPP [ 1 ] + SF [ 6 ] * ( P [ 6 ] [ 1 ] + P [ 1 ] [ 1 ] * SF [ 1 ] + P [ 3 ] [ 1 ] * SF [ 0 ] + P [ 0 ] [ 1 ] * SPP [ 0 ] - P [ 2 ] [ 1 ] * SPP [ 1 ] ) + SPP [ 7 ] * ( P [ 6 ] [ 2 ] + P [ 1 ] [ 2 ] * SF [ 1 ] + P [ 3 ] [ 2 ] * SF [ 0 ] + P [ 0 ] [ 2 ] * SPP [ 0 ] - P [ 2 ] [ 2 ] * SPP [ 1 ] ) + SPP [ 6 ] * ( P [ 6 ] [ 3 ] + P [ 1 ] [ 3 ] * SF [ 1 ] + P [ 3 ] [ 3 ] * SF [ 0 ] + P [ 0 ] [ 3 ] * SPP [ 0 ] - P [ 2 ] [ 3 ] * SPP [ 1 ] ) + SPP [ 5 ] * ( P [ 6 ] [ 10 ] + P [ 1 ] [ 10 ] * SF [ 1 ] + P [ 3 ] [ 10 ] * SF [ 0 ] + P [ 0 ] [ 10 ] * SPP [ 0 ] - P [ 2 ] [ 10 ] * SPP [ 1 ] ) + SPP [ 4 ] * ( P [ 6 ] [ 11 ] + P [ 1 ] [ 11 ] * SF [ 1 ] + P [ 3 ] [ 11 ] * SF [ 0 ] + P [ 0 ] [ 11 ] * SPP [ 0 ] - P [ 2 ] [ 11 ] * SPP [ 1 ] ) + SPP [ 3 ] * ( P [ 6 ] [ 12 ] + P [ 1 ] [ 12 ] * SF [ 1 ] + P [ 3 ] [ 12 ] * SF [ 0 ] + P [ 0 ] [ 12 ] * SPP [ 0 ] - P [ 2 ] [ 12 ] * SPP [ 1 ] ) ;
nextP [ 6 ] [ 1 ] = P [ 6 ] [ 1 ] + P [ 1 ] [ 1 ] * SF [ 1 ] + P [ 3 ] [ 1 ] * SF [ 0 ] + P [ 0 ] [ 1 ] * SPP [ 0 ] - P [ 2 ] [ 1 ] * SPP [ 1 ] + SF [ 5 ] * ( P [ 6 ] [ 0 ] + P [ 1 ] [ 0 ] * SF [ 1 ] + P [ 3 ] [ 0 ] * SF [ 0 ] + P [ 0 ] [ 0 ] * SPP [ 0 ] - P [ 2 ] [ 0 ] * SPP [ 1 ] ) + SF [ 4 ] * ( P [ 6 ] [ 2 ] + P [ 1 ] [ 2 ] * SF [ 1 ] + P [ 3 ] [ 2 ] * SF [ 0 ] + P [ 0 ] [ 2 ] * SPP [ 0 ] - P [ 2 ] [ 2 ] * SPP [ 1 ] ) + SPP [ 7 ] * ( P [ 6 ] [ 3 ] + P [ 1 ] [ 3 ] * SF [ 1 ] + P [ 3 ] [ 3 ] * SF [ 0 ] + P [ 0 ] [ 3 ] * SPP [ 0 ] - P [ 2 ] [ 3 ] * SPP [ 1 ] ) + SPP [ 3 ] * ( P [ 6 ] [ 11 ] + P [ 1 ] [ 11 ] * SF [ 1 ] + P [ 3 ] [ 11 ] * SF [ 0 ] + P [ 0 ] [ 11 ] * SPP [ 0 ] - P [ 2 ] [ 11 ] * SPP [ 1 ] ) - SPP [ 4 ] * ( P [ 6 ] [ 12 ] + P [ 1 ] [ 12 ] * SF [ 1 ] + P [ 3 ] [ 12 ] * SF [ 0 ] + P [ 0 ] [ 12 ] * SPP [ 0 ] - P [ 2 ] [ 12 ] * SPP [ 1 ] ) - ( q0 * ( P [ 6 ] [ 10 ] + P [ 1 ] [ 10 ] * SF [ 1 ] + P [ 3 ] [ 10 ] * SF [ 0 ] + P [ 0 ] [ 10 ] * SPP [ 0 ] - P [ 2 ] [ 10 ] * SPP [ 1 ] ) ) / 2 ;
nextP [ 6 ] [ 2 ] = P [ 6 ] [ 2 ] + P [ 1 ] [ 2 ] * SF [ 1 ] + P [ 3 ] [ 2 ] * SF [ 0 ] + P [ 0 ] [ 2 ] * SPP [ 0 ] - P [ 2 ] [ 2 ] * SPP [ 1 ] + SF [ 3 ] * ( P [ 6 ] [ 0 ] + P [ 1 ] [ 0 ] * SF [ 1 ] + P [ 3 ] [ 0 ] * SF [ 0 ] + P [ 0 ] [ 0 ] * SPP [ 0 ] - P [ 2 ] [ 0 ] * SPP [ 1 ] ) + SF [ 5 ] * ( P [ 6 ] [ 3 ] + P [ 1 ] [ 3 ] * SF [ 1 ] + P [ 3 ] [ 3 ] * SF [ 0 ] + P [ 0 ] [ 3 ] * SPP [ 0 ] - P [ 2 ] [ 3 ] * SPP [ 1 ] ) + SPP [ 6 ] * ( P [ 6 ] [ 1 ] + P [ 1 ] [ 1 ] * SF [ 1 ] + P [ 3 ] [ 1 ] * SF [ 0 ] + P [ 0 ] [ 1 ] * SPP [ 0 ] - P [ 2 ] [ 1 ] * SPP [ 1 ] ) - SPP [ 3 ] * ( P [ 6 ] [ 10 ] + P [ 1 ] [ 10 ] * SF [ 1 ] + P [ 3 ] [ 10 ] * SF [ 0 ] + P [ 0 ] [ 10 ] * SPP [ 0 ] - P [ 2 ] [ 10 ] * SPP [ 1 ] ) + SPP [ 5 ] * ( P [ 6 ] [ 12 ] + P [ 1 ] [ 12 ] * SF [ 1 ] + P [ 3 ] [ 12 ] * SF [ 0 ] + P [ 0 ] [ 12 ] * SPP [ 0 ] - P [ 2 ] [ 12 ] * SPP [ 1 ] ) - ( q0 * ( P [ 6 ] [ 11 ] + P [ 1 ] [ 11 ] * SF [ 1 ] + P [ 3 ] [ 11 ] * SF [ 0 ] + P [ 0 ] [ 11 ] * SPP [ 0 ] - P [ 2 ] [ 11 ] * SPP [ 1 ] ) ) / 2 ;
nextP [ 6 ] [ 3 ] = P [ 6 ] [ 3 ] + P [ 1 ] [ 3 ] * SF [ 1 ] + P [ 3 ] [ 3 ] * SF [ 0 ] + P [ 0 ] [ 3 ] * SPP [ 0 ] - P [ 2 ] [ 3 ] * SPP [ 1 ] + SF [ 4 ] * ( P [ 6 ] [ 0 ] + P [ 1 ] [ 0 ] * SF [ 1 ] + P [ 3 ] [ 0 ] * SF [ 0 ] + P [ 0 ] [ 0 ] * SPP [ 0 ] - P [ 2 ] [ 0 ] * SPP [ 1 ] ) + SF [ 3 ] * ( P [ 6 ] [ 1 ] + P [ 1 ] [ 1 ] * SF [ 1 ] + P [ 3 ] [ 1 ] * SF [ 0 ] + P [ 0 ] [ 1 ] * SPP [ 0 ] - P [ 2 ] [ 1 ] * SPP [ 1 ] ) + SF [ 6 ] * ( P [ 6 ] [ 2 ] + P [ 1 ] [ 2 ] * SF [ 1 ] + P [ 3 ] [ 2 ] * SF [ 0 ] + P [ 0 ] [ 2 ] * SPP [ 0 ] - P [ 2 ] [ 2 ] * SPP [ 1 ] ) + SPP [ 4 ] * ( P [ 6 ] [ 10 ] + P [ 1 ] [ 10 ] * SF [ 1 ] + P [ 3 ] [ 10 ] * SF [ 0 ] + P [ 0 ] [ 10 ] * SPP [ 0 ] - P [ 2 ] [ 10 ] * SPP [ 1 ] ) - SPP [ 5 ] * ( P [ 6 ] [ 11 ] + P [ 1 ] [ 11 ] * SF [ 1 ] + P [ 3 ] [ 11 ] * SF [ 0 ] + P [ 0 ] [ 11 ] * SPP [ 0 ] - P [ 2 ] [ 11 ] * SPP [ 1 ] ) - ( q0 * ( P [ 6 ] [ 12 ] + P [ 1 ] [ 12 ] * SF [ 1 ] + P [ 3 ] [ 12 ] * SF [ 0 ] + P [ 0 ] [ 12 ] * SPP [ 0 ] - P [ 2 ] [ 12 ] * SPP [ 1 ] ) ) / 2 ;
nextP [ 6 ] [ 4 ] = P [ 6 ] [ 4 ] + SQ [ 1 ] + P [ 1 ] [ 4 ] * SF [ 1 ] + P [ 3 ] [ 4 ] * SF [ 0 ] + P [ 0 ] [ 4 ] * SPP [ 0 ] - P [ 2 ] [ 4 ] * SPP [ 1 ] + SF [ 2 ] * ( P [ 6 ] [ 0 ] + P [ 1 ] [ 0 ] * SF [ 1 ] + P [ 3 ] [ 0 ] * SF [ 0 ] + P [ 0 ] [ 0 ] * SPP [ 0 ] - P [ 2 ] [ 0 ] * SPP [ 1 ] ) + SF [ 0 ] * ( P [ 6 ] [ 1 ] + P [ 1 ] [ 1 ] * SF [ 1 ] + P [ 3 ] [ 1 ] * SF [ 0 ] + P [ 0 ] [ 1 ] * SPP [ 0 ] - P [ 2 ] [ 1 ] * SPP [ 1 ] ) + SPP [ 0 ] * ( P [ 6 ] [ 2 ] + P [ 1 ] [ 2 ] * SF [ 1 ] + P [ 3 ] [ 2 ] * SF [ 0 ] + P [ 0 ] [ 2 ] * SPP [ 0 ] - P [ 2 ] [ 2 ] * SPP [ 1 ] ) - SPP [ 2 ] * ( P [ 6 ] [ 3 ] + P [ 1 ] [ 3 ] * SF [ 1 ] + P [ 3 ] [ 3 ] * SF [ 0 ] + P [ 0 ] [ 3 ] * SPP [ 0 ] - P [ 2 ] [ 3 ] * SPP [ 1 ] ) ;
nextP [ 6 ] [ 5 ] = P [ 6 ] [ 5 ] + SQ [ 0 ] + P [ 1 ] [ 5 ] * SF [ 1 ] + P [ 3 ] [ 5 ] * SF [ 0 ] + P [ 0 ] [ 5 ] * SPP [ 0 ] - P [ 2 ] [ 5 ] * SPP [ 1 ] + SF [ 1 ] * ( P [ 6 ] [ 0 ] + P [ 1 ] [ 0 ] * SF [ 1 ] + P [ 3 ] [ 0 ] * SF [ 0 ] + P [ 0 ] [ 0 ] * SPP [ 0 ] - P [ 2 ] [ 0 ] * SPP [ 1 ] ) + SF [ 0 ] * ( P [ 6 ] [ 2 ] + P [ 1 ] [ 2 ] * SF [ 1 ] + P [ 3 ] [ 2 ] * SF [ 0 ] + P [ 0 ] [ 2 ] * SPP [ 0 ] - P [ 2 ] [ 2 ] * SPP [ 1 ] ) + SF [ 2 ] * ( P [ 6 ] [ 3 ] + P [ 1 ] [ 3 ] * SF [ 1 ] + P [ 3 ] [ 3 ] * SF [ 0 ] + P [ 0 ] [ 3 ] * SPP [ 0 ] - P [ 2 ] [ 3 ] * SPP [ 1 ] ) - SPP [ 0 ] * ( P [ 6 ] [ 1 ] + P [ 1 ] [ 1 ] * SF [ 1 ] + P [ 3 ] [ 1 ] * SF [ 0 ] + P [ 0 ] [ 1 ] * SPP [ 0 ] - P [ 2 ] [ 1 ] * SPP [ 1 ] ) ;
nextP [ 6 ] [ 6 ] = P [ 6 ] [ 6 ] + P [ 1 ] [ 6 ] * SF [ 1 ] + P [ 3 ] [ 6 ] * SF [ 0 ] + P [ 0 ] [ 6 ] * SPP [ 0 ] - P [ 2 ] [ 6 ] * SPP [ 1 ] + dvxCov * sq ( SG [ 6 ] - 2 * q0 * q2 ) + dvyCov * sq ( SG [ 5 ] + 2 * q0 * q1 ) + SF [ 1 ] * ( P [ 6 ] [ 1 ] + P [ 1 ] [ 1 ] * SF [ 1 ] + P [ 3 ] [ 1 ] * SF [ 0 ] + P [ 0 ] [ 1 ] * SPP [ 0 ] - P [ 2 ] [ 1 ] * SPP [ 1 ] ) + SF [ 0 ] * ( P [ 6 ] [ 3 ] + P [ 1 ] [ 3 ] * SF [ 1 ] + P [ 3 ] [ 3 ] * SF [ 0 ] + P [ 0 ] [ 3 ] * SPP [ 0 ] - P [ 2 ] [ 3 ] * SPP [ 1 ] ) + SPP [ 0 ] * ( P [ 6 ] [ 0 ] + P [ 1 ] [ 0 ] * SF [ 1 ] + P [ 3 ] [ 0 ] * SF [ 0 ] + P [ 0 ] [ 0 ] * SPP [ 0 ] - P [ 2 ] [ 0 ] * SPP [ 1 ] ) - SPP [ 1 ] * ( P [ 6 ] [ 2 ] + P [ 1 ] [ 2 ] * SF [ 1 ] + P [ 3 ] [ 2 ] * SF [ 0 ] + P [ 0 ] [ 2 ] * SPP [ 0 ] - P [ 2 ] [ 2 ] * SPP [ 1 ] ) + dvzCov * sq ( SG [ 1 ] - SG [ 2 ] - SG [ 3 ] + SG [ 4 ] ) ;
nextP [ 6 ] [ 7 ] = P [ 6 ] [ 7 ] + P [ 1 ] [ 7 ] * SF [ 1 ] + P [ 3 ] [ 7 ] * SF [ 0 ] + P [ 0 ] [ 7 ] * SPP [ 0 ] - P [ 2 ] [ 7 ] * SPP [ 1 ] + dt * ( P [ 6 ] [ 4 ] + P [ 1 ] [ 4 ] * SF [ 1 ] + P [ 3 ] [ 4 ] * SF [ 0 ] + P [ 0 ] [ 4 ] * SPP [ 0 ] - P [ 2 ] [ 4 ] * SPP [ 1 ] ) ;
nextP [ 6 ] [ 8 ] = P [ 6 ] [ 8 ] + P [ 1 ] [ 8 ] * SF [ 1 ] + P [ 3 ] [ 8 ] * SF [ 0 ] + P [ 0 ] [ 8 ] * SPP [ 0 ] - P [ 2 ] [ 8 ] * SPP [ 1 ] + dt * ( P [ 6 ] [ 5 ] + P [ 1 ] [ 5 ] * SF [ 1 ] + P [ 3 ] [ 5 ] * SF [ 0 ] + P [ 0 ] [ 5 ] * SPP [ 0 ] - P [ 2 ] [ 5 ] * SPP [ 1 ] ) ;
nextP [ 6 ] [ 9 ] = P [ 6 ] [ 9 ] + P [ 1 ] [ 9 ] * SF [ 1 ] + P [ 3 ] [ 9 ] * SF [ 0 ] + P [ 0 ] [ 9 ] * SPP [ 0 ] - P [ 2 ] [ 9 ] * SPP [ 1 ] + dt * ( P [ 6 ] [ 6 ] + P [ 1 ] [ 6 ] * SF [ 1 ] + P [ 3 ] [ 6 ] * SF [ 0 ] + P [ 0 ] [ 6 ] * SPP [ 0 ] - P [ 2 ] [ 6 ] * SPP [ 1 ] ) ;
nextP [ 6 ] [ 10 ] = P [ 6 ] [ 10 ] + P [ 1 ] [ 10 ] * SF [ 1 ] + P [ 3 ] [ 10 ] * SF [ 0 ] + P [ 0 ] [ 10 ] * SPP [ 0 ] - P [ 2 ] [ 10 ] * SPP [ 1 ] ;
nextP [ 6 ] [ 11 ] = P [ 6 ] [ 11 ] + P [ 1 ] [ 11 ] * SF [ 1 ] + P [ 3 ] [ 11 ] * SF [ 0 ] + P [ 0 ] [ 11 ] * SPP [ 0 ] - P [ 2 ] [ 11 ] * SPP [ 1 ] ;
nextP [ 6 ] [ 12 ] = P [ 6 ] [ 12 ] + P [ 1 ] [ 12 ] * SF [ 1 ] + P [ 3 ] [ 12 ] * SF [ 0 ] + P [ 0 ] [ 12 ] * SPP [ 0 ] - P [ 2 ] [ 12 ] * SPP [ 1 ] ;
nextP [ 6 ] [ 13 ] = P [ 6 ] [ 13 ] + P [ 1 ] [ 13 ] * SF [ 1 ] + P [ 3 ] [ 13 ] * SF [ 0 ] + P [ 0 ] [ 13 ] * SPP [ 0 ] - P [ 2 ] [ 13 ] * SPP [ 1 ] ;
nextP [ 6 ] [ 14 ] = P [ 6 ] [ 14 ] + P [ 1 ] [ 14 ] * SF [ 1 ] + P [ 3 ] [ 14 ] * SF [ 0 ] + P [ 0 ] [ 14 ] * SPP [ 0 ] - P [ 2 ] [ 14 ] * SPP [ 1 ] ;
nextP [ 6 ] [ 15 ] = P [ 6 ] [ 15 ] + P [ 1 ] [ 15 ] * SF [ 1 ] + P [ 3 ] [ 15 ] * SF [ 0 ] + P [ 0 ] [ 15 ] * SPP [ 0 ] - P [ 2 ] [ 15 ] * SPP [ 1 ] ;
nextP [ 6 ] [ 16 ] = P [ 6 ] [ 16 ] + P [ 1 ] [ 16 ] * SF [ 1 ] + P [ 3 ] [ 16 ] * SF [ 0 ] + P [ 0 ] [ 16 ] * SPP [ 0 ] - P [ 2 ] [ 16 ] * SPP [ 1 ] ;
nextP [ 6 ] [ 17 ] = P [ 6 ] [ 17 ] + P [ 1 ] [ 17 ] * SF [ 1 ] + P [ 3 ] [ 17 ] * SF [ 0 ] + P [ 0 ] [ 17 ] * SPP [ 0 ] - P [ 2 ] [ 17 ] * SPP [ 1 ] ;
nextP [ 6 ] [ 18 ] = P [ 6 ] [ 18 ] + P [ 1 ] [ 18 ] * SF [ 1 ] + P [ 3 ] [ 18 ] * SF [ 0 ] + P [ 0 ] [ 18 ] * SPP [ 0 ] - P [ 2 ] [ 18 ] * SPP [ 1 ] ;
nextP [ 6 ] [ 19 ] = P [ 6 ] [ 19 ] + P [ 1 ] [ 19 ] * SF [ 1 ] + P [ 3 ] [ 19 ] * SF [ 0 ] + P [ 0 ] [ 19 ] * SPP [ 0 ] - P [ 2 ] [ 19 ] * SPP [ 1 ] ;
nextP [ 6 ] [ 20 ] = P [ 6 ] [ 20 ] + P [ 1 ] [ 20 ] * SF [ 1 ] + P [ 3 ] [ 20 ] * SF [ 0 ] + P [ 0 ] [ 20 ] * SPP [ 0 ] - P [ 2 ] [ 20 ] * SPP [ 1 ] ;
nextP [ 7 ] [ 0 ] = P [ 7 ] [ 0 ] + P [ 4 ] [ 0 ] * dt + SF [ 6 ] * ( P [ 7 ] [ 1 ] + P [ 4 ] [ 1 ] * dt ) + SPP [ 7 ] * ( P [ 7 ] [ 2 ] + P [ 4 ] [ 2 ] * dt ) + SPP [ 6 ] * ( P [ 7 ] [ 3 ] + P [ 4 ] [ 3 ] * dt ) + SPP [ 5 ] * ( P [ 7 ] [ 10 ] + P [ 4 ] [ 10 ] * dt ) + SPP [ 4 ] * ( P [ 7 ] [ 11 ] + P [ 4 ] [ 11 ] * dt ) + SPP [ 3 ] * ( P [ 7 ] [ 12 ] + P [ 4 ] [ 12 ] * dt ) ;
nextP [ 7 ] [ 1 ] = P [ 7 ] [ 1 ] + P [ 4 ] [ 1 ] * dt + SF [ 5 ] * ( P [ 7 ] [ 0 ] + P [ 4 ] [ 0 ] * dt ) + SF [ 4 ] * ( P [ 7 ] [ 2 ] + P [ 4 ] [ 2 ] * dt ) + SPP [ 7 ] * ( P [ 7 ] [ 3 ] + P [ 4 ] [ 3 ] * dt ) + SPP [ 3 ] * ( P [ 7 ] [ 11 ] + P [ 4 ] [ 11 ] * dt ) - SPP [ 4 ] * ( P [ 7 ] [ 12 ] + P [ 4 ] [ 12 ] * dt ) - ( q0 * ( P [ 7 ] [ 10 ] + P [ 4 ] [ 10 ] * dt ) ) / 2 ;
nextP [ 7 ] [ 2 ] = P [ 7 ] [ 2 ] + P [ 4 ] [ 2 ] * dt + SF [ 3 ] * ( P [ 7 ] [ 0 ] + P [ 4 ] [ 0 ] * dt ) + SF [ 5 ] * ( P [ 7 ] [ 3 ] + P [ 4 ] [ 3 ] * dt ) + SPP [ 6 ] * ( P [ 7 ] [ 1 ] + P [ 4 ] [ 1 ] * dt ) - SPP [ 3 ] * ( P [ 7 ] [ 10 ] + P [ 4 ] [ 10 ] * dt ) + SPP [ 5 ] * ( P [ 7 ] [ 12 ] + P [ 4 ] [ 12 ] * dt ) - ( q0 * ( P [ 7 ] [ 11 ] + P [ 4 ] [ 11 ] * dt ) ) / 2 ;
nextP [ 7 ] [ 3 ] = P [ 7 ] [ 3 ] + P [ 4 ] [ 3 ] * dt + SF [ 4 ] * ( P [ 7 ] [ 0 ] + P [ 4 ] [ 0 ] * dt ) + SF [ 3 ] * ( P [ 7 ] [ 1 ] + P [ 4 ] [ 1 ] * dt ) + SF [ 6 ] * ( P [ 7 ] [ 2 ] + P [ 4 ] [ 2 ] * dt ) + SPP [ 4 ] * ( P [ 7 ] [ 10 ] + P [ 4 ] [ 10 ] * dt ) - SPP [ 5 ] * ( P [ 7 ] [ 11 ] + P [ 4 ] [ 11 ] * dt ) - ( q0 * ( P [ 7 ] [ 12 ] + P [ 4 ] [ 12 ] * dt ) ) / 2 ;
nextP [ 7 ] [ 4 ] = P [ 7 ] [ 4 ] + P [ 4 ] [ 4 ] * dt + SF [ 0 ] * ( P [ 7 ] [ 1 ] + P [ 4 ] [ 1 ] * dt ) + SF [ 2 ] * ( P [ 7 ] [ 0 ] + P [ 4 ] [ 0 ] * dt ) + SPP [ 0 ] * ( P [ 7 ] [ 2 ] + P [ 4 ] [ 2 ] * dt ) - SPP [ 2 ] * ( P [ 7 ] [ 3 ] + P [ 4 ] [ 3 ] * dt ) ;
nextP [ 7 ] [ 5 ] = P [ 7 ] [ 5 ] + P [ 4 ] [ 5 ] * dt + SF [ 1 ] * ( P [ 7 ] [ 0 ] + P [ 4 ] [ 0 ] * dt ) + SF [ 0 ] * ( P [ 7 ] [ 2 ] + P [ 4 ] [ 2 ] * dt ) + SF [ 2 ] * ( P [ 7 ] [ 3 ] + P [ 4 ] [ 3 ] * dt ) - SPP [ 0 ] * ( P [ 7 ] [ 1 ] + P [ 4 ] [ 1 ] * dt ) ;
nextP [ 7 ] [ 6 ] = P [ 7 ] [ 6 ] + P [ 4 ] [ 6 ] * dt + SF [ 1 ] * ( P [ 7 ] [ 1 ] + P [ 4 ] [ 1 ] * dt ) + SF [ 0 ] * ( P [ 7 ] [ 3 ] + P [ 4 ] [ 3 ] * dt ) + SPP [ 0 ] * ( P [ 7 ] [ 0 ] + P [ 4 ] [ 0 ] * dt ) - SPP [ 1 ] * ( P [ 7 ] [ 2 ] + P [ 4 ] [ 2 ] * dt ) ;
2013-12-29 05:48:15 -04:00
nextP [ 7 ] [ 7 ] = P [ 7 ] [ 7 ] + P [ 4 ] [ 7 ] * dt + dt * ( P [ 7 ] [ 4 ] + P [ 4 ] [ 4 ] * dt ) ;
nextP [ 7 ] [ 8 ] = P [ 7 ] [ 8 ] + P [ 4 ] [ 8 ] * dt + dt * ( P [ 7 ] [ 5 ] + P [ 4 ] [ 5 ] * dt ) ;
nextP [ 7 ] [ 9 ] = P [ 7 ] [ 9 ] + P [ 4 ] [ 9 ] * dt + dt * ( P [ 7 ] [ 6 ] + P [ 4 ] [ 6 ] * dt ) ;
nextP [ 7 ] [ 10 ] = P [ 7 ] [ 10 ] + P [ 4 ] [ 10 ] * dt ;
nextP [ 7 ] [ 11 ] = P [ 7 ] [ 11 ] + P [ 4 ] [ 11 ] * dt ;
nextP [ 7 ] [ 12 ] = P [ 7 ] [ 12 ] + P [ 4 ] [ 12 ] * dt ;
nextP [ 7 ] [ 13 ] = P [ 7 ] [ 13 ] + P [ 4 ] [ 13 ] * dt ;
nextP [ 7 ] [ 14 ] = P [ 7 ] [ 14 ] + P [ 4 ] [ 14 ] * dt ;
nextP [ 7 ] [ 15 ] = P [ 7 ] [ 15 ] + P [ 4 ] [ 15 ] * dt ;
nextP [ 7 ] [ 16 ] = P [ 7 ] [ 16 ] + P [ 4 ] [ 16 ] * dt ;
nextP [ 7 ] [ 17 ] = P [ 7 ] [ 17 ] + P [ 4 ] [ 17 ] * dt ;
nextP [ 7 ] [ 18 ] = P [ 7 ] [ 18 ] + P [ 4 ] [ 18 ] * dt ;
nextP [ 7 ] [ 19 ] = P [ 7 ] [ 19 ] + P [ 4 ] [ 19 ] * dt ;
nextP [ 7 ] [ 20 ] = P [ 7 ] [ 20 ] + P [ 4 ] [ 20 ] * dt ;
2014-01-03 03:52:37 -04:00
nextP [ 8 ] [ 0 ] = P [ 8 ] [ 0 ] + P [ 5 ] [ 0 ] * dt + SF [ 6 ] * ( P [ 8 ] [ 1 ] + P [ 5 ] [ 1 ] * dt ) + SPP [ 7 ] * ( P [ 8 ] [ 2 ] + P [ 5 ] [ 2 ] * dt ) + SPP [ 6 ] * ( P [ 8 ] [ 3 ] + P [ 5 ] [ 3 ] * dt ) + SPP [ 5 ] * ( P [ 8 ] [ 10 ] + P [ 5 ] [ 10 ] * dt ) + SPP [ 4 ] * ( P [ 8 ] [ 11 ] + P [ 5 ] [ 11 ] * dt ) + SPP [ 3 ] * ( P [ 8 ] [ 12 ] + P [ 5 ] [ 12 ] * dt ) ;
nextP [ 8 ] [ 1 ] = P [ 8 ] [ 1 ] + P [ 5 ] [ 1 ] * dt + SF [ 5 ] * ( P [ 8 ] [ 0 ] + P [ 5 ] [ 0 ] * dt ) + SF [ 4 ] * ( P [ 8 ] [ 2 ] + P [ 5 ] [ 2 ] * dt ) + SPP [ 7 ] * ( P [ 8 ] [ 3 ] + P [ 5 ] [ 3 ] * dt ) + SPP [ 3 ] * ( P [ 8 ] [ 11 ] + P [ 5 ] [ 11 ] * dt ) - SPP [ 4 ] * ( P [ 8 ] [ 12 ] + P [ 5 ] [ 12 ] * dt ) - ( q0 * ( P [ 8 ] [ 10 ] + P [ 5 ] [ 10 ] * dt ) ) / 2 ;
nextP [ 8 ] [ 2 ] = P [ 8 ] [ 2 ] + P [ 5 ] [ 2 ] * dt + SF [ 3 ] * ( P [ 8 ] [ 0 ] + P [ 5 ] [ 0 ] * dt ) + SF [ 5 ] * ( P [ 8 ] [ 3 ] + P [ 5 ] [ 3 ] * dt ) + SPP [ 6 ] * ( P [ 8 ] [ 1 ] + P [ 5 ] [ 1 ] * dt ) - SPP [ 3 ] * ( P [ 8 ] [ 10 ] + P [ 5 ] [ 10 ] * dt ) + SPP [ 5 ] * ( P [ 8 ] [ 12 ] + P [ 5 ] [ 12 ] * dt ) - ( q0 * ( P [ 8 ] [ 11 ] + P [ 5 ] [ 11 ] * dt ) ) / 2 ;
nextP [ 8 ] [ 3 ] = P [ 8 ] [ 3 ] + P [ 5 ] [ 3 ] * dt + SF [ 4 ] * ( P [ 8 ] [ 0 ] + P [ 5 ] [ 0 ] * dt ) + SF [ 3 ] * ( P [ 8 ] [ 1 ] + P [ 5 ] [ 1 ] * dt ) + SF [ 6 ] * ( P [ 8 ] [ 2 ] + P [ 5 ] [ 2 ] * dt ) + SPP [ 4 ] * ( P [ 8 ] [ 10 ] + P [ 5 ] [ 10 ] * dt ) - SPP [ 5 ] * ( P [ 8 ] [ 11 ] + P [ 5 ] [ 11 ] * dt ) - ( q0 * ( P [ 8 ] [ 12 ] + P [ 5 ] [ 12 ] * dt ) ) / 2 ;
nextP [ 8 ] [ 4 ] = P [ 8 ] [ 4 ] + P [ 5 ] [ 4 ] * dt + SF [ 0 ] * ( P [ 8 ] [ 1 ] + P [ 5 ] [ 1 ] * dt ) + SF [ 2 ] * ( P [ 8 ] [ 0 ] + P [ 5 ] [ 0 ] * dt ) + SPP [ 0 ] * ( P [ 8 ] [ 2 ] + P [ 5 ] [ 2 ] * dt ) - SPP [ 2 ] * ( P [ 8 ] [ 3 ] + P [ 5 ] [ 3 ] * dt ) ;
nextP [ 8 ] [ 5 ] = P [ 8 ] [ 5 ] + P [ 5 ] [ 5 ] * dt + SF [ 1 ] * ( P [ 8 ] [ 0 ] + P [ 5 ] [ 0 ] * dt ) + SF [ 0 ] * ( P [ 8 ] [ 2 ] + P [ 5 ] [ 2 ] * dt ) + SF [ 2 ] * ( P [ 8 ] [ 3 ] + P [ 5 ] [ 3 ] * dt ) - SPP [ 0 ] * ( P [ 8 ] [ 1 ] + P [ 5 ] [ 1 ] * dt ) ;
nextP [ 8 ] [ 6 ] = P [ 8 ] [ 6 ] + P [ 5 ] [ 6 ] * dt + SF [ 1 ] * ( P [ 8 ] [ 1 ] + P [ 5 ] [ 1 ] * dt ) + SF [ 0 ] * ( P [ 8 ] [ 3 ] + P [ 5 ] [ 3 ] * dt ) + SPP [ 0 ] * ( P [ 8 ] [ 0 ] + P [ 5 ] [ 0 ] * dt ) - SPP [ 1 ] * ( P [ 8 ] [ 2 ] + P [ 5 ] [ 2 ] * dt ) ;
2013-12-29 05:48:15 -04:00
nextP [ 8 ] [ 7 ] = P [ 8 ] [ 7 ] + P [ 5 ] [ 7 ] * dt + dt * ( P [ 8 ] [ 4 ] + P [ 5 ] [ 4 ] * dt ) ;
nextP [ 8 ] [ 8 ] = P [ 8 ] [ 8 ] + P [ 5 ] [ 8 ] * dt + dt * ( P [ 8 ] [ 5 ] + P [ 5 ] [ 5 ] * dt ) ;
nextP [ 8 ] [ 9 ] = P [ 8 ] [ 9 ] + P [ 5 ] [ 9 ] * dt + dt * ( P [ 8 ] [ 6 ] + P [ 5 ] [ 6 ] * dt ) ;
nextP [ 8 ] [ 10 ] = P [ 8 ] [ 10 ] + P [ 5 ] [ 10 ] * dt ;
nextP [ 8 ] [ 11 ] = P [ 8 ] [ 11 ] + P [ 5 ] [ 11 ] * dt ;
nextP [ 8 ] [ 12 ] = P [ 8 ] [ 12 ] + P [ 5 ] [ 12 ] * dt ;
nextP [ 8 ] [ 13 ] = P [ 8 ] [ 13 ] + P [ 5 ] [ 13 ] * dt ;
nextP [ 8 ] [ 14 ] = P [ 8 ] [ 14 ] + P [ 5 ] [ 14 ] * dt ;
nextP [ 8 ] [ 15 ] = P [ 8 ] [ 15 ] + P [ 5 ] [ 15 ] * dt ;
nextP [ 8 ] [ 16 ] = P [ 8 ] [ 16 ] + P [ 5 ] [ 16 ] * dt ;
nextP [ 8 ] [ 17 ] = P [ 8 ] [ 17 ] + P [ 5 ] [ 17 ] * dt ;
nextP [ 8 ] [ 18 ] = P [ 8 ] [ 18 ] + P [ 5 ] [ 18 ] * dt ;
nextP [ 8 ] [ 19 ] = P [ 8 ] [ 19 ] + P [ 5 ] [ 19 ] * dt ;
nextP [ 8 ] [ 20 ] = P [ 8 ] [ 20 ] + P [ 5 ] [ 20 ] * dt ;
2014-01-03 03:52:37 -04:00
nextP [ 9 ] [ 0 ] = P [ 9 ] [ 0 ] + P [ 6 ] [ 0 ] * dt + SF [ 6 ] * ( P [ 9 ] [ 1 ] + P [ 6 ] [ 1 ] * dt ) + SPP [ 7 ] * ( P [ 9 ] [ 2 ] + P [ 6 ] [ 2 ] * dt ) + SPP [ 6 ] * ( P [ 9 ] [ 3 ] + P [ 6 ] [ 3 ] * dt ) + SPP [ 5 ] * ( P [ 9 ] [ 10 ] + P [ 6 ] [ 10 ] * dt ) + SPP [ 4 ] * ( P [ 9 ] [ 11 ] + P [ 6 ] [ 11 ] * dt ) + SPP [ 3 ] * ( P [ 9 ] [ 12 ] + P [ 6 ] [ 12 ] * dt ) ;
nextP [ 9 ] [ 1 ] = P [ 9 ] [ 1 ] + P [ 6 ] [ 1 ] * dt + SF [ 5 ] * ( P [ 9 ] [ 0 ] + P [ 6 ] [ 0 ] * dt ) + SF [ 4 ] * ( P [ 9 ] [ 2 ] + P [ 6 ] [ 2 ] * dt ) + SPP [ 7 ] * ( P [ 9 ] [ 3 ] + P [ 6 ] [ 3 ] * dt ) + SPP [ 3 ] * ( P [ 9 ] [ 11 ] + P [ 6 ] [ 11 ] * dt ) - SPP [ 4 ] * ( P [ 9 ] [ 12 ] + P [ 6 ] [ 12 ] * dt ) - ( q0 * ( P [ 9 ] [ 10 ] + P [ 6 ] [ 10 ] * dt ) ) / 2 ;
nextP [ 9 ] [ 2 ] = P [ 9 ] [ 2 ] + P [ 6 ] [ 2 ] * dt + SF [ 3 ] * ( P [ 9 ] [ 0 ] + P [ 6 ] [ 0 ] * dt ) + SF [ 5 ] * ( P [ 9 ] [ 3 ] + P [ 6 ] [ 3 ] * dt ) + SPP [ 6 ] * ( P [ 9 ] [ 1 ] + P [ 6 ] [ 1 ] * dt ) - SPP [ 3 ] * ( P [ 9 ] [ 10 ] + P [ 6 ] [ 10 ] * dt ) + SPP [ 5 ] * ( P [ 9 ] [ 12 ] + P [ 6 ] [ 12 ] * dt ) - ( q0 * ( P [ 9 ] [ 11 ] + P [ 6 ] [ 11 ] * dt ) ) / 2 ;
nextP [ 9 ] [ 3 ] = P [ 9 ] [ 3 ] + P [ 6 ] [ 3 ] * dt + SF [ 4 ] * ( P [ 9 ] [ 0 ] + P [ 6 ] [ 0 ] * dt ) + SF [ 3 ] * ( P [ 9 ] [ 1 ] + P [ 6 ] [ 1 ] * dt ) + SF [ 6 ] * ( P [ 9 ] [ 2 ] + P [ 6 ] [ 2 ] * dt ) + SPP [ 4 ] * ( P [ 9 ] [ 10 ] + P [ 6 ] [ 10 ] * dt ) - SPP [ 5 ] * ( P [ 9 ] [ 11 ] + P [ 6 ] [ 11 ] * dt ) - ( q0 * ( P [ 9 ] [ 12 ] + P [ 6 ] [ 12 ] * dt ) ) / 2 ;
nextP [ 9 ] [ 4 ] = P [ 9 ] [ 4 ] + P [ 6 ] [ 4 ] * dt + SF [ 0 ] * ( P [ 9 ] [ 1 ] + P [ 6 ] [ 1 ] * dt ) + SF [ 2 ] * ( P [ 9 ] [ 0 ] + P [ 6 ] [ 0 ] * dt ) + SPP [ 0 ] * ( P [ 9 ] [ 2 ] + P [ 6 ] [ 2 ] * dt ) - SPP [ 2 ] * ( P [ 9 ] [ 3 ] + P [ 6 ] [ 3 ] * dt ) ;
nextP [ 9 ] [ 5 ] = P [ 9 ] [ 5 ] + P [ 6 ] [ 5 ] * dt + SF [ 1 ] * ( P [ 9 ] [ 0 ] + P [ 6 ] [ 0 ] * dt ) + SF [ 0 ] * ( P [ 9 ] [ 2 ] + P [ 6 ] [ 2 ] * dt ) + SF [ 2 ] * ( P [ 9 ] [ 3 ] + P [ 6 ] [ 3 ] * dt ) - SPP [ 0 ] * ( P [ 9 ] [ 1 ] + P [ 6 ] [ 1 ] * dt ) ;
nextP [ 9 ] [ 6 ] = P [ 9 ] [ 6 ] + P [ 6 ] [ 6 ] * dt + SF [ 1 ] * ( P [ 9 ] [ 1 ] + P [ 6 ] [ 1 ] * dt ) + SF [ 0 ] * ( P [ 9 ] [ 3 ] + P [ 6 ] [ 3 ] * dt ) + SPP [ 0 ] * ( P [ 9 ] [ 0 ] + P [ 6 ] [ 0 ] * dt ) - SPP [ 1 ] * ( P [ 9 ] [ 2 ] + P [ 6 ] [ 2 ] * dt ) ;
2013-12-29 05:48:15 -04:00
nextP [ 9 ] [ 7 ] = P [ 9 ] [ 7 ] + P [ 6 ] [ 7 ] * dt + dt * ( P [ 9 ] [ 4 ] + P [ 6 ] [ 4 ] * dt ) ;
nextP [ 9 ] [ 8 ] = P [ 9 ] [ 8 ] + P [ 6 ] [ 8 ] * dt + dt * ( P [ 9 ] [ 5 ] + P [ 6 ] [ 5 ] * dt ) ;
nextP [ 9 ] [ 9 ] = P [ 9 ] [ 9 ] + P [ 6 ] [ 9 ] * dt + dt * ( P [ 9 ] [ 6 ] + P [ 6 ] [ 6 ] * dt ) ;
nextP [ 9 ] [ 10 ] = P [ 9 ] [ 10 ] + P [ 6 ] [ 10 ] * dt ;
nextP [ 9 ] [ 11 ] = P [ 9 ] [ 11 ] + P [ 6 ] [ 11 ] * dt ;
nextP [ 9 ] [ 12 ] = P [ 9 ] [ 12 ] + P [ 6 ] [ 12 ] * dt ;
nextP [ 9 ] [ 13 ] = P [ 9 ] [ 13 ] + P [ 6 ] [ 13 ] * dt ;
nextP [ 9 ] [ 14 ] = P [ 9 ] [ 14 ] + P [ 6 ] [ 14 ] * dt ;
nextP [ 9 ] [ 15 ] = P [ 9 ] [ 15 ] + P [ 6 ] [ 15 ] * dt ;
nextP [ 9 ] [ 16 ] = P [ 9 ] [ 16 ] + P [ 6 ] [ 16 ] * dt ;
nextP [ 9 ] [ 17 ] = P [ 9 ] [ 17 ] + P [ 6 ] [ 17 ] * dt ;
nextP [ 9 ] [ 18 ] = P [ 9 ] [ 18 ] + P [ 6 ] [ 18 ] * dt ;
nextP [ 9 ] [ 19 ] = P [ 9 ] [ 19 ] + P [ 6 ] [ 19 ] * dt ;
nextP [ 9 ] [ 20 ] = P [ 9 ] [ 20 ] + P [ 6 ] [ 20 ] * dt ;
2014-01-03 03:52:37 -04:00
nextP [ 10 ] [ 0 ] = P [ 10 ] [ 0 ] + P [ 10 ] [ 1 ] * SF [ 6 ] + P [ 10 ] [ 2 ] * SPP [ 7 ] + P [ 10 ] [ 3 ] * SPP [ 6 ] + P [ 10 ] [ 10 ] * SPP [ 5 ] + P [ 10 ] [ 11 ] * SPP [ 4 ] + P [ 10 ] [ 12 ] * SPP [ 3 ] ;
nextP [ 10 ] [ 1 ] = P [ 10 ] [ 1 ] + P [ 10 ] [ 0 ] * SF [ 5 ] + P [ 10 ] [ 2 ] * SF [ 4 ] + P [ 10 ] [ 3 ] * SPP [ 7 ] + P [ 10 ] [ 11 ] * SPP [ 3 ] - P [ 10 ] [ 12 ] * SPP [ 4 ] - ( P [ 10 ] [ 10 ] * q0 ) / 2 ;
nextP [ 10 ] [ 2 ] = P [ 10 ] [ 2 ] + P [ 10 ] [ 0 ] * SF [ 3 ] + P [ 10 ] [ 3 ] * SF [ 5 ] + P [ 10 ] [ 1 ] * SPP [ 6 ] - P [ 10 ] [ 10 ] * SPP [ 3 ] + P [ 10 ] [ 12 ] * SPP [ 5 ] - ( P [ 10 ] [ 11 ] * q0 ) / 2 ;
nextP [ 10 ] [ 3 ] = P [ 10 ] [ 3 ] + P [ 10 ] [ 0 ] * SF [ 4 ] + P [ 10 ] [ 1 ] * SF [ 3 ] + P [ 10 ] [ 2 ] * SF [ 6 ] + P [ 10 ] [ 10 ] * SPP [ 4 ] - P [ 10 ] [ 11 ] * SPP [ 5 ] - ( P [ 10 ] [ 12 ] * q0 ) / 2 ;
nextP [ 10 ] [ 4 ] = P [ 10 ] [ 4 ] + P [ 10 ] [ 1 ] * SF [ 0 ] + P [ 10 ] [ 0 ] * SF [ 2 ] + P [ 10 ] [ 2 ] * SPP [ 0 ] - P [ 10 ] [ 3 ] * SPP [ 2 ] ;
nextP [ 10 ] [ 5 ] = P [ 10 ] [ 5 ] + P [ 10 ] [ 0 ] * SF [ 1 ] + P [ 10 ] [ 2 ] * SF [ 0 ] + P [ 10 ] [ 3 ] * SF [ 2 ] - P [ 10 ] [ 1 ] * SPP [ 0 ] ;
nextP [ 10 ] [ 6 ] = P [ 10 ] [ 6 ] + P [ 10 ] [ 1 ] * SF [ 1 ] + P [ 10 ] [ 3 ] * SF [ 0 ] + P [ 10 ] [ 0 ] * SPP [ 0 ] - P [ 10 ] [ 2 ] * SPP [ 1 ] ;
2013-12-29 05:48:15 -04:00
nextP [ 10 ] [ 7 ] = P [ 10 ] [ 7 ] + P [ 10 ] [ 4 ] * dt ;
nextP [ 10 ] [ 8 ] = P [ 10 ] [ 8 ] + P [ 10 ] [ 5 ] * dt ;
nextP [ 10 ] [ 9 ] = P [ 10 ] [ 9 ] + P [ 10 ] [ 6 ] * dt ;
nextP [ 10 ] [ 10 ] = P [ 10 ] [ 10 ] ;
nextP [ 10 ] [ 11 ] = P [ 10 ] [ 11 ] ;
nextP [ 10 ] [ 12 ] = P [ 10 ] [ 12 ] ;
nextP [ 10 ] [ 13 ] = P [ 10 ] [ 13 ] ;
nextP [ 10 ] [ 14 ] = P [ 10 ] [ 14 ] ;
nextP [ 10 ] [ 15 ] = P [ 10 ] [ 15 ] ;
nextP [ 10 ] [ 16 ] = P [ 10 ] [ 16 ] ;
nextP [ 10 ] [ 17 ] = P [ 10 ] [ 17 ] ;
nextP [ 10 ] [ 18 ] = P [ 10 ] [ 18 ] ;
nextP [ 10 ] [ 19 ] = P [ 10 ] [ 19 ] ;
nextP [ 10 ] [ 20 ] = P [ 10 ] [ 20 ] ;
2014-01-03 03:52:37 -04:00
nextP [ 11 ] [ 0 ] = P [ 11 ] [ 0 ] + P [ 11 ] [ 1 ] * SF [ 6 ] + P [ 11 ] [ 2 ] * SPP [ 7 ] + P [ 11 ] [ 3 ] * SPP [ 6 ] + P [ 11 ] [ 10 ] * SPP [ 5 ] + P [ 11 ] [ 11 ] * SPP [ 4 ] + P [ 11 ] [ 12 ] * SPP [ 3 ] ;
nextP [ 11 ] [ 1 ] = P [ 11 ] [ 1 ] + P [ 11 ] [ 0 ] * SF [ 5 ] + P [ 11 ] [ 2 ] * SF [ 4 ] + P [ 11 ] [ 3 ] * SPP [ 7 ] + P [ 11 ] [ 11 ] * SPP [ 3 ] - P [ 11 ] [ 12 ] * SPP [ 4 ] - ( P [ 11 ] [ 10 ] * q0 ) / 2 ;
nextP [ 11 ] [ 2 ] = P [ 11 ] [ 2 ] + P [ 11 ] [ 0 ] * SF [ 3 ] + P [ 11 ] [ 3 ] * SF [ 5 ] + P [ 11 ] [ 1 ] * SPP [ 6 ] - P [ 11 ] [ 10 ] * SPP [ 3 ] + P [ 11 ] [ 12 ] * SPP [ 5 ] - ( P [ 11 ] [ 11 ] * q0 ) / 2 ;
nextP [ 11 ] [ 3 ] = P [ 11 ] [ 3 ] + P [ 11 ] [ 0 ] * SF [ 4 ] + P [ 11 ] [ 1 ] * SF [ 3 ] + P [ 11 ] [ 2 ] * SF [ 6 ] + P [ 11 ] [ 10 ] * SPP [ 4 ] - P [ 11 ] [ 11 ] * SPP [ 5 ] - ( P [ 11 ] [ 12 ] * q0 ) / 2 ;
nextP [ 11 ] [ 4 ] = P [ 11 ] [ 4 ] + P [ 11 ] [ 1 ] * SF [ 0 ] + P [ 11 ] [ 0 ] * SF [ 2 ] + P [ 11 ] [ 2 ] * SPP [ 0 ] - P [ 11 ] [ 3 ] * SPP [ 2 ] ;
nextP [ 11 ] [ 5 ] = P [ 11 ] [ 5 ] + P [ 11 ] [ 0 ] * SF [ 1 ] + P [ 11 ] [ 2 ] * SF [ 0 ] + P [ 11 ] [ 3 ] * SF [ 2 ] - P [ 11 ] [ 1 ] * SPP [ 0 ] ;
nextP [ 11 ] [ 6 ] = P [ 11 ] [ 6 ] + P [ 11 ] [ 1 ] * SF [ 1 ] + P [ 11 ] [ 3 ] * SF [ 0 ] + P [ 11 ] [ 0 ] * SPP [ 0 ] - P [ 11 ] [ 2 ] * SPP [ 1 ] ;
2013-12-29 05:48:15 -04:00
nextP [ 11 ] [ 7 ] = P [ 11 ] [ 7 ] + P [ 11 ] [ 4 ] * dt ;
nextP [ 11 ] [ 8 ] = P [ 11 ] [ 8 ] + P [ 11 ] [ 5 ] * dt ;
nextP [ 11 ] [ 9 ] = P [ 11 ] [ 9 ] + P [ 11 ] [ 6 ] * dt ;
nextP [ 11 ] [ 10 ] = P [ 11 ] [ 10 ] ;
nextP [ 11 ] [ 11 ] = P [ 11 ] [ 11 ] ;
nextP [ 11 ] [ 12 ] = P [ 11 ] [ 12 ] ;
nextP [ 11 ] [ 13 ] = P [ 11 ] [ 13 ] ;
nextP [ 11 ] [ 14 ] = P [ 11 ] [ 14 ] ;
nextP [ 11 ] [ 15 ] = P [ 11 ] [ 15 ] ;
nextP [ 11 ] [ 16 ] = P [ 11 ] [ 16 ] ;
nextP [ 11 ] [ 17 ] = P [ 11 ] [ 17 ] ;
nextP [ 11 ] [ 18 ] = P [ 11 ] [ 18 ] ;
nextP [ 11 ] [ 19 ] = P [ 11 ] [ 19 ] ;
nextP [ 11 ] [ 20 ] = P [ 11 ] [ 20 ] ;
2014-01-03 03:52:37 -04:00
nextP [ 12 ] [ 0 ] = P [ 12 ] [ 0 ] + P [ 12 ] [ 1 ] * SF [ 6 ] + P [ 12 ] [ 2 ] * SPP [ 7 ] + P [ 12 ] [ 3 ] * SPP [ 6 ] + P [ 12 ] [ 10 ] * SPP [ 5 ] + P [ 12 ] [ 11 ] * SPP [ 4 ] + P [ 12 ] [ 12 ] * SPP [ 3 ] ;
nextP [ 12 ] [ 1 ] = P [ 12 ] [ 1 ] + P [ 12 ] [ 0 ] * SF [ 5 ] + P [ 12 ] [ 2 ] * SF [ 4 ] + P [ 12 ] [ 3 ] * SPP [ 7 ] + P [ 12 ] [ 11 ] * SPP [ 3 ] - P [ 12 ] [ 12 ] * SPP [ 4 ] - ( P [ 12 ] [ 10 ] * q0 ) / 2 ;
nextP [ 12 ] [ 2 ] = P [ 12 ] [ 2 ] + P [ 12 ] [ 0 ] * SF [ 3 ] + P [ 12 ] [ 3 ] * SF [ 5 ] + P [ 12 ] [ 1 ] * SPP [ 6 ] - P [ 12 ] [ 10 ] * SPP [ 3 ] + P [ 12 ] [ 12 ] * SPP [ 5 ] - ( P [ 12 ] [ 11 ] * q0 ) / 2 ;
nextP [ 12 ] [ 3 ] = P [ 12 ] [ 3 ] + P [ 12 ] [ 0 ] * SF [ 4 ] + P [ 12 ] [ 1 ] * SF [ 3 ] + P [ 12 ] [ 2 ] * SF [ 6 ] + P [ 12 ] [ 10 ] * SPP [ 4 ] - P [ 12 ] [ 11 ] * SPP [ 5 ] - ( P [ 12 ] [ 12 ] * q0 ) / 2 ;
nextP [ 12 ] [ 4 ] = P [ 12 ] [ 4 ] + P [ 12 ] [ 1 ] * SF [ 0 ] + P [ 12 ] [ 0 ] * SF [ 2 ] + P [ 12 ] [ 2 ] * SPP [ 0 ] - P [ 12 ] [ 3 ] * SPP [ 2 ] ;
nextP [ 12 ] [ 5 ] = P [ 12 ] [ 5 ] + P [ 12 ] [ 0 ] * SF [ 1 ] + P [ 12 ] [ 2 ] * SF [ 0 ] + P [ 12 ] [ 3 ] * SF [ 2 ] - P [ 12 ] [ 1 ] * SPP [ 0 ] ;
nextP [ 12 ] [ 6 ] = P [ 12 ] [ 6 ] + P [ 12 ] [ 1 ] * SF [ 1 ] + P [ 12 ] [ 3 ] * SF [ 0 ] + P [ 12 ] [ 0 ] * SPP [ 0 ] - P [ 12 ] [ 2 ] * SPP [ 1 ] ;
2013-12-29 05:48:15 -04:00
nextP [ 12 ] [ 7 ] = P [ 12 ] [ 7 ] + P [ 12 ] [ 4 ] * dt ;
nextP [ 12 ] [ 8 ] = P [ 12 ] [ 8 ] + P [ 12 ] [ 5 ] * dt ;
nextP [ 12 ] [ 9 ] = P [ 12 ] [ 9 ] + P [ 12 ] [ 6 ] * dt ;
nextP [ 12 ] [ 10 ] = P [ 12 ] [ 10 ] ;
nextP [ 12 ] [ 11 ] = P [ 12 ] [ 11 ] ;
nextP [ 12 ] [ 12 ] = P [ 12 ] [ 12 ] ;
nextP [ 12 ] [ 13 ] = P [ 12 ] [ 13 ] ;
nextP [ 12 ] [ 14 ] = P [ 12 ] [ 14 ] ;
nextP [ 12 ] [ 15 ] = P [ 12 ] [ 15 ] ;
nextP [ 12 ] [ 16 ] = P [ 12 ] [ 16 ] ;
nextP [ 12 ] [ 17 ] = P [ 12 ] [ 17 ] ;
nextP [ 12 ] [ 18 ] = P [ 12 ] [ 18 ] ;
nextP [ 12 ] [ 19 ] = P [ 12 ] [ 19 ] ;
nextP [ 12 ] [ 20 ] = P [ 12 ] [ 20 ] ;
2014-01-03 03:52:37 -04:00
nextP [ 13 ] [ 0 ] = P [ 13 ] [ 0 ] + P [ 13 ] [ 1 ] * SF [ 6 ] + P [ 13 ] [ 2 ] * SPP [ 7 ] + P [ 13 ] [ 3 ] * SPP [ 6 ] + P [ 13 ] [ 10 ] * SPP [ 5 ] + P [ 13 ] [ 11 ] * SPP [ 4 ] + P [ 13 ] [ 12 ] * SPP [ 3 ] ;
nextP [ 13 ] [ 1 ] = P [ 13 ] [ 1 ] + P [ 13 ] [ 0 ] * SF [ 5 ] + P [ 13 ] [ 2 ] * SF [ 4 ] + P [ 13 ] [ 3 ] * SPP [ 7 ] + P [ 13 ] [ 11 ] * SPP [ 3 ] - P [ 13 ] [ 12 ] * SPP [ 4 ] - ( P [ 13 ] [ 10 ] * q0 ) / 2 ;
nextP [ 13 ] [ 2 ] = P [ 13 ] [ 2 ] + P [ 13 ] [ 0 ] * SF [ 3 ] + P [ 13 ] [ 3 ] * SF [ 5 ] + P [ 13 ] [ 1 ] * SPP [ 6 ] - P [ 13 ] [ 10 ] * SPP [ 3 ] + P [ 13 ] [ 12 ] * SPP [ 5 ] - ( P [ 13 ] [ 11 ] * q0 ) / 2 ;
nextP [ 13 ] [ 3 ] = P [ 13 ] [ 3 ] + P [ 13 ] [ 0 ] * SF [ 4 ] + P [ 13 ] [ 1 ] * SF [ 3 ] + P [ 13 ] [ 2 ] * SF [ 6 ] + P [ 13 ] [ 10 ] * SPP [ 4 ] - P [ 13 ] [ 11 ] * SPP [ 5 ] - ( P [ 13 ] [ 12 ] * q0 ) / 2 ;
nextP [ 13 ] [ 4 ] = P [ 13 ] [ 4 ] + P [ 13 ] [ 1 ] * SF [ 0 ] + P [ 13 ] [ 0 ] * SF [ 2 ] + P [ 13 ] [ 2 ] * SPP [ 0 ] - P [ 13 ] [ 3 ] * SPP [ 2 ] ;
nextP [ 13 ] [ 5 ] = P [ 13 ] [ 5 ] + P [ 13 ] [ 0 ] * SF [ 1 ] + P [ 13 ] [ 2 ] * SF [ 0 ] + P [ 13 ] [ 3 ] * SF [ 2 ] - P [ 13 ] [ 1 ] * SPP [ 0 ] ;
nextP [ 13 ] [ 6 ] = P [ 13 ] [ 6 ] + P [ 13 ] [ 1 ] * SF [ 1 ] + P [ 13 ] [ 3 ] * SF [ 0 ] + P [ 13 ] [ 0 ] * SPP [ 0 ] - P [ 13 ] [ 2 ] * SPP [ 1 ] ;
2013-12-29 05:48:15 -04:00
nextP [ 13 ] [ 7 ] = P [ 13 ] [ 7 ] + P [ 13 ] [ 4 ] * dt ;
nextP [ 13 ] [ 8 ] = P [ 13 ] [ 8 ] + P [ 13 ] [ 5 ] * dt ;
nextP [ 13 ] [ 9 ] = P [ 13 ] [ 9 ] + P [ 13 ] [ 6 ] * dt ;
nextP [ 13 ] [ 10 ] = P [ 13 ] [ 10 ] ;
nextP [ 13 ] [ 11 ] = P [ 13 ] [ 11 ] ;
nextP [ 13 ] [ 12 ] = P [ 13 ] [ 12 ] ;
nextP [ 13 ] [ 13 ] = P [ 13 ] [ 13 ] ;
nextP [ 13 ] [ 14 ] = P [ 13 ] [ 14 ] ;
nextP [ 13 ] [ 15 ] = P [ 13 ] [ 15 ] ;
nextP [ 13 ] [ 16 ] = P [ 13 ] [ 16 ] ;
nextP [ 13 ] [ 17 ] = P [ 13 ] [ 17 ] ;
nextP [ 13 ] [ 18 ] = P [ 13 ] [ 18 ] ;
nextP [ 13 ] [ 19 ] = P [ 13 ] [ 19 ] ;
nextP [ 13 ] [ 20 ] = P [ 13 ] [ 20 ] ;
2014-01-03 03:52:37 -04:00
nextP [ 14 ] [ 0 ] = P [ 14 ] [ 0 ] + P [ 14 ] [ 1 ] * SF [ 6 ] + P [ 14 ] [ 2 ] * SPP [ 7 ] + P [ 14 ] [ 3 ] * SPP [ 6 ] + P [ 14 ] [ 10 ] * SPP [ 5 ] + P [ 14 ] [ 11 ] * SPP [ 4 ] + P [ 14 ] [ 12 ] * SPP [ 3 ] ;
nextP [ 14 ] [ 1 ] = P [ 14 ] [ 1 ] + P [ 14 ] [ 0 ] * SF [ 5 ] + P [ 14 ] [ 2 ] * SF [ 4 ] + P [ 14 ] [ 3 ] * SPP [ 7 ] + P [ 14 ] [ 11 ] * SPP [ 3 ] - P [ 14 ] [ 12 ] * SPP [ 4 ] - ( P [ 14 ] [ 10 ] * q0 ) / 2 ;
nextP [ 14 ] [ 2 ] = P [ 14 ] [ 2 ] + P [ 14 ] [ 0 ] * SF [ 3 ] + P [ 14 ] [ 3 ] * SF [ 5 ] + P [ 14 ] [ 1 ] * SPP [ 6 ] - P [ 14 ] [ 10 ] * SPP [ 3 ] + P [ 14 ] [ 12 ] * SPP [ 5 ] - ( P [ 14 ] [ 11 ] * q0 ) / 2 ;
nextP [ 14 ] [ 3 ] = P [ 14 ] [ 3 ] + P [ 14 ] [ 0 ] * SF [ 4 ] + P [ 14 ] [ 1 ] * SF [ 3 ] + P [ 14 ] [ 2 ] * SF [ 6 ] + P [ 14 ] [ 10 ] * SPP [ 4 ] - P [ 14 ] [ 11 ] * SPP [ 5 ] - ( P [ 14 ] [ 12 ] * q0 ) / 2 ;
nextP [ 14 ] [ 4 ] = P [ 14 ] [ 4 ] + P [ 14 ] [ 1 ] * SF [ 0 ] + P [ 14 ] [ 0 ] * SF [ 2 ] + P [ 14 ] [ 2 ] * SPP [ 0 ] - P [ 14 ] [ 3 ] * SPP [ 2 ] ;
nextP [ 14 ] [ 5 ] = P [ 14 ] [ 5 ] + P [ 14 ] [ 0 ] * SF [ 1 ] + P [ 14 ] [ 2 ] * SF [ 0 ] + P [ 14 ] [ 3 ] * SF [ 2 ] - P [ 14 ] [ 1 ] * SPP [ 0 ] ;
nextP [ 14 ] [ 6 ] = P [ 14 ] [ 6 ] + P [ 14 ] [ 1 ] * SF [ 1 ] + P [ 14 ] [ 3 ] * SF [ 0 ] + P [ 14 ] [ 0 ] * SPP [ 0 ] - P [ 14 ] [ 2 ] * SPP [ 1 ] ;
2013-12-29 05:48:15 -04:00
nextP [ 14 ] [ 7 ] = P [ 14 ] [ 7 ] + P [ 14 ] [ 4 ] * dt ;
nextP [ 14 ] [ 8 ] = P [ 14 ] [ 8 ] + P [ 14 ] [ 5 ] * dt ;
nextP [ 14 ] [ 9 ] = P [ 14 ] [ 9 ] + P [ 14 ] [ 6 ] * dt ;
nextP [ 14 ] [ 10 ] = P [ 14 ] [ 10 ] ;
nextP [ 14 ] [ 11 ] = P [ 14 ] [ 11 ] ;
nextP [ 14 ] [ 12 ] = P [ 14 ] [ 12 ] ;
nextP [ 14 ] [ 13 ] = P [ 14 ] [ 13 ] ;
nextP [ 14 ] [ 14 ] = P [ 14 ] [ 14 ] ;
nextP [ 14 ] [ 15 ] = P [ 14 ] [ 15 ] ;
nextP [ 14 ] [ 16 ] = P [ 14 ] [ 16 ] ;
nextP [ 14 ] [ 17 ] = P [ 14 ] [ 17 ] ;
nextP [ 14 ] [ 18 ] = P [ 14 ] [ 18 ] ;
nextP [ 14 ] [ 19 ] = P [ 14 ] [ 19 ] ;
nextP [ 14 ] [ 20 ] = P [ 14 ] [ 20 ] ;
2014-01-03 03:52:37 -04:00
nextP [ 15 ] [ 0 ] = P [ 15 ] [ 0 ] + P [ 15 ] [ 1 ] * SF [ 6 ] + P [ 15 ] [ 2 ] * SPP [ 7 ] + P [ 15 ] [ 3 ] * SPP [ 6 ] + P [ 15 ] [ 10 ] * SPP [ 5 ] + P [ 15 ] [ 11 ] * SPP [ 4 ] + P [ 15 ] [ 12 ] * SPP [ 3 ] ;
nextP [ 15 ] [ 1 ] = P [ 15 ] [ 1 ] + P [ 15 ] [ 0 ] * SF [ 5 ] + P [ 15 ] [ 2 ] * SF [ 4 ] + P [ 15 ] [ 3 ] * SPP [ 7 ] + P [ 15 ] [ 11 ] * SPP [ 3 ] - P [ 15 ] [ 12 ] * SPP [ 4 ] - ( P [ 15 ] [ 10 ] * q0 ) / 2 ;
nextP [ 15 ] [ 2 ] = P [ 15 ] [ 2 ] + P [ 15 ] [ 0 ] * SF [ 3 ] + P [ 15 ] [ 3 ] * SF [ 5 ] + P [ 15 ] [ 1 ] * SPP [ 6 ] - P [ 15 ] [ 10 ] * SPP [ 3 ] + P [ 15 ] [ 12 ] * SPP [ 5 ] - ( P [ 15 ] [ 11 ] * q0 ) / 2 ;
nextP [ 15 ] [ 3 ] = P [ 15 ] [ 3 ] + P [ 15 ] [ 0 ] * SF [ 4 ] + P [ 15 ] [ 1 ] * SF [ 3 ] + P [ 15 ] [ 2 ] * SF [ 6 ] + P [ 15 ] [ 10 ] * SPP [ 4 ] - P [ 15 ] [ 11 ] * SPP [ 5 ] - ( P [ 15 ] [ 12 ] * q0 ) / 2 ;
nextP [ 15 ] [ 4 ] = P [ 15 ] [ 4 ] + P [ 15 ] [ 1 ] * SF [ 0 ] + P [ 15 ] [ 0 ] * SF [ 2 ] + P [ 15 ] [ 2 ] * SPP [ 0 ] - P [ 15 ] [ 3 ] * SPP [ 2 ] ;
nextP [ 15 ] [ 5 ] = P [ 15 ] [ 5 ] + P [ 15 ] [ 0 ] * SF [ 1 ] + P [ 15 ] [ 2 ] * SF [ 0 ] + P [ 15 ] [ 3 ] * SF [ 2 ] - P [ 15 ] [ 1 ] * SPP [ 0 ] ;
nextP [ 15 ] [ 6 ] = P [ 15 ] [ 6 ] + P [ 15 ] [ 1 ] * SF [ 1 ] + P [ 15 ] [ 3 ] * SF [ 0 ] + P [ 15 ] [ 0 ] * SPP [ 0 ] - P [ 15 ] [ 2 ] * SPP [ 1 ] ;
2013-12-29 05:48:15 -04:00
nextP [ 15 ] [ 7 ] = P [ 15 ] [ 7 ] + P [ 15 ] [ 4 ] * dt ;
nextP [ 15 ] [ 8 ] = P [ 15 ] [ 8 ] + P [ 15 ] [ 5 ] * dt ;
nextP [ 15 ] [ 9 ] = P [ 15 ] [ 9 ] + P [ 15 ] [ 6 ] * dt ;
nextP [ 15 ] [ 10 ] = P [ 15 ] [ 10 ] ;
nextP [ 15 ] [ 11 ] = P [ 15 ] [ 11 ] ;
nextP [ 15 ] [ 12 ] = P [ 15 ] [ 12 ] ;
nextP [ 15 ] [ 13 ] = P [ 15 ] [ 13 ] ;
nextP [ 15 ] [ 14 ] = P [ 15 ] [ 14 ] ;
nextP [ 15 ] [ 15 ] = P [ 15 ] [ 15 ] ;
nextP [ 15 ] [ 16 ] = P [ 15 ] [ 16 ] ;
nextP [ 15 ] [ 17 ] = P [ 15 ] [ 17 ] ;
nextP [ 15 ] [ 18 ] = P [ 15 ] [ 18 ] ;
nextP [ 15 ] [ 19 ] = P [ 15 ] [ 19 ] ;
nextP [ 15 ] [ 20 ] = P [ 15 ] [ 20 ] ;
2014-01-03 03:52:37 -04:00
nextP [ 16 ] [ 0 ] = P [ 16 ] [ 0 ] + P [ 16 ] [ 1 ] * SF [ 6 ] + P [ 16 ] [ 2 ] * SPP [ 7 ] + P [ 16 ] [ 3 ] * SPP [ 6 ] + P [ 16 ] [ 10 ] * SPP [ 5 ] + P [ 16 ] [ 11 ] * SPP [ 4 ] + P [ 16 ] [ 12 ] * SPP [ 3 ] ;
nextP [ 16 ] [ 1 ] = P [ 16 ] [ 1 ] + P [ 16 ] [ 0 ] * SF [ 5 ] + P [ 16 ] [ 2 ] * SF [ 4 ] + P [ 16 ] [ 3 ] * SPP [ 7 ] + P [ 16 ] [ 11 ] * SPP [ 3 ] - P [ 16 ] [ 12 ] * SPP [ 4 ] - ( P [ 16 ] [ 10 ] * q0 ) / 2 ;
nextP [ 16 ] [ 2 ] = P [ 16 ] [ 2 ] + P [ 16 ] [ 0 ] * SF [ 3 ] + P [ 16 ] [ 3 ] * SF [ 5 ] + P [ 16 ] [ 1 ] * SPP [ 6 ] - P [ 16 ] [ 10 ] * SPP [ 3 ] + P [ 16 ] [ 12 ] * SPP [ 5 ] - ( P [ 16 ] [ 11 ] * q0 ) / 2 ;
nextP [ 16 ] [ 3 ] = P [ 16 ] [ 3 ] + P [ 16 ] [ 0 ] * SF [ 4 ] + P [ 16 ] [ 1 ] * SF [ 3 ] + P [ 16 ] [ 2 ] * SF [ 6 ] + P [ 16 ] [ 10 ] * SPP [ 4 ] - P [ 16 ] [ 11 ] * SPP [ 5 ] - ( P [ 16 ] [ 12 ] * q0 ) / 2 ;
nextP [ 16 ] [ 4 ] = P [ 16 ] [ 4 ] + P [ 16 ] [ 1 ] * SF [ 0 ] + P [ 16 ] [ 0 ] * SF [ 2 ] + P [ 16 ] [ 2 ] * SPP [ 0 ] - P [ 16 ] [ 3 ] * SPP [ 2 ] ;
nextP [ 16 ] [ 5 ] = P [ 16 ] [ 5 ] + P [ 16 ] [ 0 ] * SF [ 1 ] + P [ 16 ] [ 2 ] * SF [ 0 ] + P [ 16 ] [ 3 ] * SF [ 2 ] - P [ 16 ] [ 1 ] * SPP [ 0 ] ;
nextP [ 16 ] [ 6 ] = P [ 16 ] [ 6 ] + P [ 16 ] [ 1 ] * SF [ 1 ] + P [ 16 ] [ 3 ] * SF [ 0 ] + P [ 16 ] [ 0 ] * SPP [ 0 ] - P [ 16 ] [ 2 ] * SPP [ 1 ] ;
2013-12-29 05:48:15 -04:00
nextP [ 16 ] [ 7 ] = P [ 16 ] [ 7 ] + P [ 16 ] [ 4 ] * dt ;
nextP [ 16 ] [ 8 ] = P [ 16 ] [ 8 ] + P [ 16 ] [ 5 ] * dt ;
nextP [ 16 ] [ 9 ] = P [ 16 ] [ 9 ] + P [ 16 ] [ 6 ] * dt ;
nextP [ 16 ] [ 10 ] = P [ 16 ] [ 10 ] ;
nextP [ 16 ] [ 11 ] = P [ 16 ] [ 11 ] ;
nextP [ 16 ] [ 12 ] = P [ 16 ] [ 12 ] ;
nextP [ 16 ] [ 13 ] = P [ 16 ] [ 13 ] ;
nextP [ 16 ] [ 14 ] = P [ 16 ] [ 14 ] ;
nextP [ 16 ] [ 15 ] = P [ 16 ] [ 15 ] ;
nextP [ 16 ] [ 16 ] = P [ 16 ] [ 16 ] ;
nextP [ 16 ] [ 17 ] = P [ 16 ] [ 17 ] ;
nextP [ 16 ] [ 18 ] = P [ 16 ] [ 18 ] ;
nextP [ 16 ] [ 19 ] = P [ 16 ] [ 19 ] ;
nextP [ 16 ] [ 20 ] = P [ 16 ] [ 20 ] ;
2014-01-03 03:52:37 -04:00
nextP [ 17 ] [ 0 ] = P [ 17 ] [ 0 ] + P [ 17 ] [ 1 ] * SF [ 6 ] + P [ 17 ] [ 2 ] * SPP [ 7 ] + P [ 17 ] [ 3 ] * SPP [ 6 ] + P [ 17 ] [ 10 ] * SPP [ 5 ] + P [ 17 ] [ 11 ] * SPP [ 4 ] + P [ 17 ] [ 12 ] * SPP [ 3 ] ;
nextP [ 17 ] [ 1 ] = P [ 17 ] [ 1 ] + P [ 17 ] [ 0 ] * SF [ 5 ] + P [ 17 ] [ 2 ] * SF [ 4 ] + P [ 17 ] [ 3 ] * SPP [ 7 ] + P [ 17 ] [ 11 ] * SPP [ 3 ] - P [ 17 ] [ 12 ] * SPP [ 4 ] - ( P [ 17 ] [ 10 ] * q0 ) / 2 ;
nextP [ 17 ] [ 2 ] = P [ 17 ] [ 2 ] + P [ 17 ] [ 0 ] * SF [ 3 ] + P [ 17 ] [ 3 ] * SF [ 5 ] + P [ 17 ] [ 1 ] * SPP [ 6 ] - P [ 17 ] [ 10 ] * SPP [ 3 ] + P [ 17 ] [ 12 ] * SPP [ 5 ] - ( P [ 17 ] [ 11 ] * q0 ) / 2 ;
nextP [ 17 ] [ 3 ] = P [ 17 ] [ 3 ] + P [ 17 ] [ 0 ] * SF [ 4 ] + P [ 17 ] [ 1 ] * SF [ 3 ] + P [ 17 ] [ 2 ] * SF [ 6 ] + P [ 17 ] [ 10 ] * SPP [ 4 ] - P [ 17 ] [ 11 ] * SPP [ 5 ] - ( P [ 17 ] [ 12 ] * q0 ) / 2 ;
nextP [ 17 ] [ 4 ] = P [ 17 ] [ 4 ] + P [ 17 ] [ 1 ] * SF [ 0 ] + P [ 17 ] [ 0 ] * SF [ 2 ] + P [ 17 ] [ 2 ] * SPP [ 0 ] - P [ 17 ] [ 3 ] * SPP [ 2 ] ;
nextP [ 17 ] [ 5 ] = P [ 17 ] [ 5 ] + P [ 17 ] [ 0 ] * SF [ 1 ] + P [ 17 ] [ 2 ] * SF [ 0 ] + P [ 17 ] [ 3 ] * SF [ 2 ] - P [ 17 ] [ 1 ] * SPP [ 0 ] ;
nextP [ 17 ] [ 6 ] = P [ 17 ] [ 6 ] + P [ 17 ] [ 1 ] * SF [ 1 ] + P [ 17 ] [ 3 ] * SF [ 0 ] + P [ 17 ] [ 0 ] * SPP [ 0 ] - P [ 17 ] [ 2 ] * SPP [ 1 ] ;
2013-12-29 05:48:15 -04:00
nextP [ 17 ] [ 7 ] = P [ 17 ] [ 7 ] + P [ 17 ] [ 4 ] * dt ;
nextP [ 17 ] [ 8 ] = P [ 17 ] [ 8 ] + P [ 17 ] [ 5 ] * dt ;
nextP [ 17 ] [ 9 ] = P [ 17 ] [ 9 ] + P [ 17 ] [ 6 ] * dt ;
nextP [ 17 ] [ 10 ] = P [ 17 ] [ 10 ] ;
nextP [ 17 ] [ 11 ] = P [ 17 ] [ 11 ] ;
nextP [ 17 ] [ 12 ] = P [ 17 ] [ 12 ] ;
nextP [ 17 ] [ 13 ] = P [ 17 ] [ 13 ] ;
nextP [ 17 ] [ 14 ] = P [ 17 ] [ 14 ] ;
nextP [ 17 ] [ 15 ] = P [ 17 ] [ 15 ] ;
nextP [ 17 ] [ 16 ] = P [ 17 ] [ 16 ] ;
nextP [ 17 ] [ 17 ] = P [ 17 ] [ 17 ] ;
nextP [ 17 ] [ 18 ] = P [ 17 ] [ 18 ] ;
nextP [ 17 ] [ 19 ] = P [ 17 ] [ 19 ] ;
nextP [ 17 ] [ 20 ] = P [ 17 ] [ 20 ] ;
2014-01-03 03:52:37 -04:00
nextP [ 18 ] [ 0 ] = P [ 18 ] [ 0 ] + P [ 18 ] [ 1 ] * SF [ 6 ] + P [ 18 ] [ 2 ] * SPP [ 7 ] + P [ 18 ] [ 3 ] * SPP [ 6 ] + P [ 18 ] [ 10 ] * SPP [ 5 ] + P [ 18 ] [ 11 ] * SPP [ 4 ] + P [ 18 ] [ 12 ] * SPP [ 3 ] ;
nextP [ 18 ] [ 1 ] = P [ 18 ] [ 1 ] + P [ 18 ] [ 0 ] * SF [ 5 ] + P [ 18 ] [ 2 ] * SF [ 4 ] + P [ 18 ] [ 3 ] * SPP [ 7 ] + P [ 18 ] [ 11 ] * SPP [ 3 ] - P [ 18 ] [ 12 ] * SPP [ 4 ] - ( P [ 18 ] [ 10 ] * q0 ) / 2 ;
nextP [ 18 ] [ 2 ] = P [ 18 ] [ 2 ] + P [ 18 ] [ 0 ] * SF [ 3 ] + P [ 18 ] [ 3 ] * SF [ 5 ] + P [ 18 ] [ 1 ] * SPP [ 6 ] - P [ 18 ] [ 10 ] * SPP [ 3 ] + P [ 18 ] [ 12 ] * SPP [ 5 ] - ( P [ 18 ] [ 11 ] * q0 ) / 2 ;
nextP [ 18 ] [ 3 ] = P [ 18 ] [ 3 ] + P [ 18 ] [ 0 ] * SF [ 4 ] + P [ 18 ] [ 1 ] * SF [ 3 ] + P [ 18 ] [ 2 ] * SF [ 6 ] + P [ 18 ] [ 10 ] * SPP [ 4 ] - P [ 18 ] [ 11 ] * SPP [ 5 ] - ( P [ 18 ] [ 12 ] * q0 ) / 2 ;
nextP [ 18 ] [ 4 ] = P [ 18 ] [ 4 ] + P [ 18 ] [ 1 ] * SF [ 0 ] + P [ 18 ] [ 0 ] * SF [ 2 ] + P [ 18 ] [ 2 ] * SPP [ 0 ] - P [ 18 ] [ 3 ] * SPP [ 2 ] ;
nextP [ 18 ] [ 5 ] = P [ 18 ] [ 5 ] + P [ 18 ] [ 0 ] * SF [ 1 ] + P [ 18 ] [ 2 ] * SF [ 0 ] + P [ 18 ] [ 3 ] * SF [ 2 ] - P [ 18 ] [ 1 ] * SPP [ 0 ] ;
nextP [ 18 ] [ 6 ] = P [ 18 ] [ 6 ] + P [ 18 ] [ 1 ] * SF [ 1 ] + P [ 18 ] [ 3 ] * SF [ 0 ] + P [ 18 ] [ 0 ] * SPP [ 0 ] - P [ 18 ] [ 2 ] * SPP [ 1 ] ;
2013-12-29 05:48:15 -04:00
nextP [ 18 ] [ 7 ] = P [ 18 ] [ 7 ] + P [ 18 ] [ 4 ] * dt ;
nextP [ 18 ] [ 8 ] = P [ 18 ] [ 8 ] + P [ 18 ] [ 5 ] * dt ;
nextP [ 18 ] [ 9 ] = P [ 18 ] [ 9 ] + P [ 18 ] [ 6 ] * dt ;
nextP [ 18 ] [ 10 ] = P [ 18 ] [ 10 ] ;
nextP [ 18 ] [ 11 ] = P [ 18 ] [ 11 ] ;
nextP [ 18 ] [ 12 ] = P [ 18 ] [ 12 ] ;
nextP [ 18 ] [ 13 ] = P [ 18 ] [ 13 ] ;
nextP [ 18 ] [ 14 ] = P [ 18 ] [ 14 ] ;
nextP [ 18 ] [ 15 ] = P [ 18 ] [ 15 ] ;
nextP [ 18 ] [ 16 ] = P [ 18 ] [ 16 ] ;
nextP [ 18 ] [ 17 ] = P [ 18 ] [ 17 ] ;
nextP [ 18 ] [ 18 ] = P [ 18 ] [ 18 ] ;
nextP [ 18 ] [ 19 ] = P [ 18 ] [ 19 ] ;
nextP [ 18 ] [ 20 ] = P [ 18 ] [ 20 ] ;
2014-01-03 03:52:37 -04:00
nextP [ 19 ] [ 0 ] = P [ 19 ] [ 0 ] + P [ 19 ] [ 1 ] * SF [ 6 ] + P [ 19 ] [ 2 ] * SPP [ 7 ] + P [ 19 ] [ 3 ] * SPP [ 6 ] + P [ 19 ] [ 10 ] * SPP [ 5 ] + P [ 19 ] [ 11 ] * SPP [ 4 ] + P [ 19 ] [ 12 ] * SPP [ 3 ] ;
nextP [ 19 ] [ 1 ] = P [ 19 ] [ 1 ] + P [ 19 ] [ 0 ] * SF [ 5 ] + P [ 19 ] [ 2 ] * SF [ 4 ] + P [ 19 ] [ 3 ] * SPP [ 7 ] + P [ 19 ] [ 11 ] * SPP [ 3 ] - P [ 19 ] [ 12 ] * SPP [ 4 ] - ( P [ 19 ] [ 10 ] * q0 ) / 2 ;
nextP [ 19 ] [ 2 ] = P [ 19 ] [ 2 ] + P [ 19 ] [ 0 ] * SF [ 3 ] + P [ 19 ] [ 3 ] * SF [ 5 ] + P [ 19 ] [ 1 ] * SPP [ 6 ] - P [ 19 ] [ 10 ] * SPP [ 3 ] + P [ 19 ] [ 12 ] * SPP [ 5 ] - ( P [ 19 ] [ 11 ] * q0 ) / 2 ;
nextP [ 19 ] [ 3 ] = P [ 19 ] [ 3 ] + P [ 19 ] [ 0 ] * SF [ 4 ] + P [ 19 ] [ 1 ] * SF [ 3 ] + P [ 19 ] [ 2 ] * SF [ 6 ] + P [ 19 ] [ 10 ] * SPP [ 4 ] - P [ 19 ] [ 11 ] * SPP [ 5 ] - ( P [ 19 ] [ 12 ] * q0 ) / 2 ;
nextP [ 19 ] [ 4 ] = P [ 19 ] [ 4 ] + P [ 19 ] [ 1 ] * SF [ 0 ] + P [ 19 ] [ 0 ] * SF [ 2 ] + P [ 19 ] [ 2 ] * SPP [ 0 ] - P [ 19 ] [ 3 ] * SPP [ 2 ] ;
nextP [ 19 ] [ 5 ] = P [ 19 ] [ 5 ] + P [ 19 ] [ 0 ] * SF [ 1 ] + P [ 19 ] [ 2 ] * SF [ 0 ] + P [ 19 ] [ 3 ] * SF [ 2 ] - P [ 19 ] [ 1 ] * SPP [ 0 ] ;
nextP [ 19 ] [ 6 ] = P [ 19 ] [ 6 ] + P [ 19 ] [ 1 ] * SF [ 1 ] + P [ 19 ] [ 3 ] * SF [ 0 ] + P [ 19 ] [ 0 ] * SPP [ 0 ] - P [ 19 ] [ 2 ] * SPP [ 1 ] ;
2013-12-29 05:48:15 -04:00
nextP [ 19 ] [ 7 ] = P [ 19 ] [ 7 ] + P [ 19 ] [ 4 ] * dt ;
nextP [ 19 ] [ 8 ] = P [ 19 ] [ 8 ] + P [ 19 ] [ 5 ] * dt ;
nextP [ 19 ] [ 9 ] = P [ 19 ] [ 9 ] + P [ 19 ] [ 6 ] * dt ;
nextP [ 19 ] [ 10 ] = P [ 19 ] [ 10 ] ;
nextP [ 19 ] [ 11 ] = P [ 19 ] [ 11 ] ;
nextP [ 19 ] [ 12 ] = P [ 19 ] [ 12 ] ;
nextP [ 19 ] [ 13 ] = P [ 19 ] [ 13 ] ;
nextP [ 19 ] [ 14 ] = P [ 19 ] [ 14 ] ;
nextP [ 19 ] [ 15 ] = P [ 19 ] [ 15 ] ;
nextP [ 19 ] [ 16 ] = P [ 19 ] [ 16 ] ;
nextP [ 19 ] [ 17 ] = P [ 19 ] [ 17 ] ;
nextP [ 19 ] [ 18 ] = P [ 19 ] [ 18 ] ;
nextP [ 19 ] [ 19 ] = P [ 19 ] [ 19 ] ;
nextP [ 19 ] [ 20 ] = P [ 19 ] [ 20 ] ;
2014-01-03 03:52:37 -04:00
nextP [ 20 ] [ 0 ] = P [ 20 ] [ 0 ] + P [ 20 ] [ 1 ] * SF [ 6 ] + P [ 20 ] [ 2 ] * SPP [ 7 ] + P [ 20 ] [ 3 ] * SPP [ 6 ] + P [ 20 ] [ 10 ] * SPP [ 5 ] + P [ 20 ] [ 11 ] * SPP [ 4 ] + P [ 20 ] [ 12 ] * SPP [ 3 ] ;
nextP [ 20 ] [ 1 ] = P [ 20 ] [ 1 ] + P [ 20 ] [ 0 ] * SF [ 5 ] + P [ 20 ] [ 2 ] * SF [ 4 ] + P [ 20 ] [ 3 ] * SPP [ 7 ] + P [ 20 ] [ 11 ] * SPP [ 3 ] - P [ 20 ] [ 12 ] * SPP [ 4 ] - ( P [ 20 ] [ 10 ] * q0 ) / 2 ;
nextP [ 20 ] [ 2 ] = P [ 20 ] [ 2 ] + P [ 20 ] [ 0 ] * SF [ 3 ] + P [ 20 ] [ 3 ] * SF [ 5 ] + P [ 20 ] [ 1 ] * SPP [ 6 ] - P [ 20 ] [ 10 ] * SPP [ 3 ] + P [ 20 ] [ 12 ] * SPP [ 5 ] - ( P [ 20 ] [ 11 ] * q0 ) / 2 ;
nextP [ 20 ] [ 3 ] = P [ 20 ] [ 3 ] + P [ 20 ] [ 0 ] * SF [ 4 ] + P [ 20 ] [ 1 ] * SF [ 3 ] + P [ 20 ] [ 2 ] * SF [ 6 ] + P [ 20 ] [ 10 ] * SPP [ 4 ] - P [ 20 ] [ 11 ] * SPP [ 5 ] - ( P [ 20 ] [ 12 ] * q0 ) / 2 ;
nextP [ 20 ] [ 4 ] = P [ 20 ] [ 4 ] + P [ 20 ] [ 1 ] * SF [ 0 ] + P [ 20 ] [ 0 ] * SF [ 2 ] + P [ 20 ] [ 2 ] * SPP [ 0 ] - P [ 20 ] [ 3 ] * SPP [ 2 ] ;
nextP [ 20 ] [ 5 ] = P [ 20 ] [ 5 ] + P [ 20 ] [ 0 ] * SF [ 1 ] + P [ 20 ] [ 2 ] * SF [ 0 ] + P [ 20 ] [ 3 ] * SF [ 2 ] - P [ 20 ] [ 1 ] * SPP [ 0 ] ;
nextP [ 20 ] [ 6 ] = P [ 20 ] [ 6 ] + P [ 20 ] [ 1 ] * SF [ 1 ] + P [ 20 ] [ 3 ] * SF [ 0 ] + P [ 20 ] [ 0 ] * SPP [ 0 ] - P [ 20 ] [ 2 ] * SPP [ 1 ] ;
2013-12-29 05:48:15 -04:00
nextP [ 20 ] [ 7 ] = P [ 20 ] [ 7 ] + P [ 20 ] [ 4 ] * dt ;
nextP [ 20 ] [ 8 ] = P [ 20 ] [ 8 ] + P [ 20 ] [ 5 ] * dt ;
nextP [ 20 ] [ 9 ] = P [ 20 ] [ 9 ] + P [ 20 ] [ 6 ] * dt ;
nextP [ 20 ] [ 10 ] = P [ 20 ] [ 10 ] ;
nextP [ 20 ] [ 11 ] = P [ 20 ] [ 11 ] ;
nextP [ 20 ] [ 12 ] = P [ 20 ] [ 12 ] ;
nextP [ 20 ] [ 13 ] = P [ 20 ] [ 13 ] ;
nextP [ 20 ] [ 14 ] = P [ 20 ] [ 14 ] ;
nextP [ 20 ] [ 15 ] = P [ 20 ] [ 15 ] ;
nextP [ 20 ] [ 16 ] = P [ 20 ] [ 16 ] ;
nextP [ 20 ] [ 17 ] = P [ 20 ] [ 17 ] ;
nextP [ 20 ] [ 18 ] = P [ 20 ] [ 18 ] ;
nextP [ 20 ] [ 19 ] = P [ 20 ] [ 19 ] ;
nextP [ 20 ] [ 20 ] = P [ 20 ] [ 20 ] ;
2014-01-03 03:52:37 -04:00
for ( uint8_t i = 0 ; i < = 20 ; i + + )
2013-12-29 05:48:15 -04:00
{
nextP [ i ] [ i ] = nextP [ i ] [ i ] + processNoise [ i ] ;
}
2013-12-30 16:56:28 -04:00
// If on ground or no compasss fitted, inhibit magnetic field state updates by
2013-12-29 05:48:15 -04:00
// setting the corresponding covariance terms to zero
2013-12-30 16:56:28 -04:00
if ( onGround | | ! useCompass )
2013-12-29 05:48:15 -04:00
{
2014-01-03 03:52:37 -04:00
zeroRows ( nextP , 15 , 20 ) ;
zeroCols ( nextP , 15 , 20 ) ;
2013-12-29 05:48:15 -04:00
}
// If on ground or not using airspeed sensing, inhibit wind velocity
2013-12-30 16:56:28 -04:00
// covariance growth.
2013-12-29 05:48:15 -04:00
if ( onGround | | ! useAirspeed )
{
2014-01-03 03:52:37 -04:00
zeroRows ( nextP , 13 , 14 ) ;
zeroCols ( nextP , 13 , 14 ) ;
2013-12-29 05:48:15 -04:00
}
// If the total position variance exceeds 1E6 (1000m), then stop covariance
// growth by setting the predicted to the previous values
// This prevent an ill conditioned matrix from occurring for long periods
// without GPS
2013-12-30 06:27:50 -04:00
if ( ( P [ 7 ] [ 7 ] + P [ 8 ] [ 8 ] ) > 1e6 f )
2013-12-29 05:48:15 -04:00
{
for ( uint8_t i = 7 ; i < = 8 ; i + + )
{
2014-01-03 03:52:37 -04:00
for ( uint8_t j = 0 ; j < = 20 ; j + + )
2013-12-29 05:48:15 -04:00
{
nextP [ i ] [ j ] = P [ i ] [ j ] ;
nextP [ j ] [ i ] = P [ j ] [ i ] ;
}
}
}
2014-01-03 15:59:47 -04:00
// Copy to output whilst forcing symmetry to prevent ill-conditioning
// of the matrix
for ( uint8_t i = 0 ; i < = 20 ; i + + ) P [ i ] [ i ] = nextP [ i ] [ i ] ;
for ( uint8_t i = 1 ; i < = 20 ; i + + )
{
for ( uint8_t j = 0 ; j < = i - 1 ; j + + )
{
P [ i ] [ j ] = 0.5f * ( nextP [ i ] [ j ] + nextP [ j ] [ i ] ) ;
P [ j ] [ i ] = P [ i ] [ j ] ;
}
}
ConstrainVariances ( ) ;
2014-01-03 04:00:15 -04:00
2013-12-30 06:41:28 -04:00
perf_end ( _perf_CovariancePrediction ) ;
2013-12-25 18:58:02 -04:00
}
2013-12-29 03:37:55 -04:00
void NavEKF : : FuseVelPosNED ( )
2013-12-25 18:58:02 -04:00
{
2013-12-30 06:41:28 -04:00
perf_begin ( _perf_FuseVelPosNED ) ;
2013-12-29 03:37:55 -04:00
// declare variables used by fault isolation logic
2014-01-03 20:47:26 -04:00
uint32_t gpsRetryTime = 10000 ; // time in msec before GPS fusion will be retried following innovation consistency failure
2013-12-29 05:48:15 -04:00
uint32_t gpsRetryTimeNoTAS = 5000 ; // retry time if no TAS measurement available
uint32_t hgtRetryTime = 5000 ; // height measurement retry time
2013-12-29 21:27:06 -04:00
uint32_t horizRetryTime = 0 ;
2013-12-29 22:25:02 -04:00
bool velHealth = false ;
bool posHealth = false ;
2013-12-30 06:27:50 -04:00
bool hgtHealth = false ;
2013-12-29 05:48:15 -04:00
bool velTimeout ;
bool posTimeout ;
bool hgtTimeout ;
2014-01-03 03:52:37 -04:00
Vector21 Kfusion ;
2013-12-25 18:58:02 -04:00
2014-01-01 08:15:37 -04:00
// declare variables used to check measurement errors
2013-12-29 22:25:02 -04:00
Vector3f velInnov ;
2013-12-30 06:27:50 -04:00
Vector2 posInnov ;
2013-12-29 05:48:15 -04:00
float hgtInnov = 0 ;
2013-12-25 18:58:02 -04:00
2014-01-01 08:15:37 -04:00
// declare variables used to control access to arrays
2013-12-29 05:48:15 -04:00
bool fuseData [ 6 ] = { false , false , false , false , false , false } ;
uint8_t stateIndex ;
uint8_t obsIndex ;
2013-12-30 16:56:28 -04:00
uint8_t indexLimit ; // used to prevent access to wind and magnetic field states and variances when on ground
2013-12-25 18:58:02 -04:00
2014-01-01 08:15:37 -04:00
// declare variables used by state and covariance update calculations
2013-12-29 05:48:15 -04:00
float velErr ;
float posErr ;
2013-12-29 22:25:02 -04:00
Vector6 R_OBS ;
Vector6 observation ;
2013-12-29 05:48:15 -04:00
float SK ;
2013-12-25 18:58:02 -04:00
2014-01-01 08:15:37 -04:00
// Perform sequential fusion of GPS measurements. This assumes that the
// errors in the different velocity and position components are
// uncorrelated which is not true, however in the absence of covariance
// data from the GPS receiver it is the only assumption we can make
// so we might as well take advantage of the computational efficiencies
// associated with sequential fusion
2013-12-29 05:48:15 -04:00
if ( fuseVelData | | fusePosData | | fuseHgtData )
{
// set the GPS data timeout depending on whether airspeed data is present
if ( useAirspeed ) horizRetryTime = gpsRetryTime ;
else horizRetryTime = gpsRetryTimeNoTAS ;
// Form the observation vector
for ( uint8_t i = 0 ; i < = 2 ; i + + ) observation [ i ] = velNED [ i ] ;
for ( uint8_t i = 3 ; i < = 4 ; i + + ) observation [ i ] = posNE [ i - 3 ] ;
2013-12-29 23:43:29 -04:00
observation [ 5 ] = - hgtMea ;
2014-01-04 00:20:14 -04:00
// zero observations if in static mode (used for pre-arm and bench testing)
if ( staticMode ) {
for ( uint8_t i = 0 ; i < = 2 ; i + + ) observation [ i ] = 0.0f ;
// cancel static mode (it needs to be set every frame if required)
staticMode = false ;
}
2014-01-01 08:15:37 -04:00
2014-01-01 17:12:06 -04:00
// additional error in GPS velocity caused by manoeuvring
2014-01-01 08:15:37 -04:00
velErr = _gpsVelVarAccScale * accNavMag ;
// additional error in GPS position caused by manoeuvring
posErr = _gpsPosVarAccScale * accNavMag ;
2014-01-01 17:12:06 -04:00
// Estimate the GPS Velocity, GPS horiz position and height measurement variances.
R_OBS [ 0 ] = _gpsHorizVelVar + sq ( velErr ) ;
R_OBS [ 1 ] = R_OBS [ 0 ] ;
R_OBS [ 2 ] = _gpsVertVelVar + sq ( velErr ) ;
R_OBS [ 3 ] = _gpsHorizPosVar + sq ( posErr ) ;
R_OBS [ 4 ] = R_OBS [ 3 ] ;
2014-01-01 08:15:37 -04:00
R_OBS [ 5 ] = _gpsVertPosVar ;
2013-12-29 05:48:15 -04:00
// Set innovation variances to zero default
for ( uint8_t i = 0 ; i < = 5 ; i + + )
{
varInnovVelPos [ i ] = 0 ;
}
// calculate innovations and check GPS data validity using an innovation consistency check
if ( fuseVelData )
{
// test velocity measurements
uint8_t imax = 2 ;
if ( fusionModeGPS = = 1 ) imax = 1 ;
for ( uint8_t i = 0 ; i < = imax ; i + + )
{
2013-12-29 23:43:29 -04:00
velInnov [ i ] = statesAtVelTime [ i + 4 ] - observation [ i ] ;
2013-12-29 05:48:15 -04:00
stateIndex = 4 + i ;
varInnovVelPos [ i ] = P [ stateIndex ] [ stateIndex ] + R_OBS [ i ] ;
}
// apply a 5-sigma threshold
2013-12-29 21:27:06 -04:00
2013-12-29 05:48:15 -04:00
velHealth = ( ( sq ( velInnov [ 0 ] ) + sq ( velInnov [ 1 ] ) + sq ( velInnov [ 2 ] ) ) < ( 25.0f * ( varInnovVelPos [ 0 ] + varInnovVelPos [ 1 ] + varInnovVelPos [ 2 ] ) ) ) ;
velTimeout = ( hal . scheduler - > millis ( ) - velFailTime ) > horizRetryTime ;
if ( velHealth | | velTimeout )
{
velHealth = true ;
velFailTime = hal . scheduler - > millis ( ) ;
}
else
{
velHealth = false ;
}
}
if ( fusePosData )
{
// test horizontal position measurements
2013-12-29 23:43:29 -04:00
posInnov [ 0 ] = statesAtPosTime [ 7 ] - observation [ 3 ] ;
posInnov [ 1 ] = statesAtPosTime [ 8 ] - observation [ 4 ] ;
2013-12-29 05:48:15 -04:00
varInnovVelPos [ 3 ] = P [ 7 ] [ 7 ] + R_OBS [ 3 ] ;
varInnovVelPos [ 4 ] = P [ 8 ] [ 8 ] + R_OBS [ 4 ] ;
// apply a 10-sigma threshold
posHealth = ( ( sq ( posInnov [ 0 ] ) + sq ( posInnov [ 1 ] ) ) < ( 100.0f * ( varInnovVelPos [ 3 ] + varInnovVelPos [ 4 ] ) ) ) ;
posTimeout = ( hal . scheduler - > millis ( ) - posFailTime ) > horizRetryTime ;
if ( posHealth | | posTimeout )
{
posHealth = true ;
posFailTime = hal . scheduler - > millis ( ) ;
}
else
{
posHealth = false ;
}
}
// test height measurements
if ( fuseHgtData )
{
2013-12-29 23:43:29 -04:00
hgtInnov = statesAtHgtTime [ 9 ] - observation [ 5 ] ;
2013-12-29 05:48:15 -04:00
varInnovVelPos [ 5 ] = P [ 9 ] [ 9 ] + R_OBS [ 5 ] ;
// apply a 10-sigma threshold
2013-12-29 23:59:09 -04:00
hgtHealth = ( sq ( hgtInnov ) < ( 100.0f * varInnovVelPos [ 5 ] ) ) ;
2013-12-29 05:48:15 -04:00
hgtTimeout = ( hal . scheduler - > millis ( ) - hgtFailTime ) > hgtRetryTime ;
if ( hgtHealth | | hgtTimeout )
{
hgtHealth = true ;
hgtFailTime = hal . scheduler - > millis ( ) ;
}
else
{
hgtHealth = false ;
}
}
// Set range for sequential fusion of velocity and position measurements depending
// on which data is available and its health
2014-01-04 00:20:14 -04:00
if ( ( fuseVelData & & fusionModeGPS = = 0 & & velHealth ) | | staticMode )
2013-12-29 05:48:15 -04:00
{
fuseData [ 0 ] = true ;
fuseData [ 1 ] = true ;
fuseData [ 2 ] = true ;
}
if ( fuseVelData & & fusionModeGPS = = 1 & & velHealth )
{
fuseData [ 0 ] = true ;
fuseData [ 1 ] = true ;
}
2014-01-04 00:20:14 -04:00
if ( ( fusePosData & & fusionModeGPS < = 2 & & posHealth ) | | staticMode )
2013-12-29 05:48:15 -04:00
{
fuseData [ 3 ] = true ;
fuseData [ 4 ] = true ;
}
2014-01-04 00:20:14 -04:00
if ( ( fuseHgtData & & hgtHealth ) | | staticMode )
2013-12-29 05:48:15 -04:00
{
fuseData [ 5 ] = true ;
}
2013-12-30 16:56:28 -04:00
// Limit access to first 13 states when on ground.
if ( ! onGround )
{
2014-01-03 03:52:37 -04:00
indexLimit = 20 ;
2013-12-30 16:56:28 -04:00
}
else
{
indexLimit = 12 ;
}
2013-12-29 05:48:15 -04:00
// Fuse measurements sequentially
for ( obsIndex = 0 ; obsIndex < = 5 ; obsIndex + + )
{
if ( fuseData [ obsIndex ] )
{
stateIndex = 4 + obsIndex ;
// Calculate the measurement innovation, using states from a
// different time coordinate if fusing height data
2013-12-30 06:27:50 -04:00
if ( obsIndex < = 2 )
2013-12-29 05:48:15 -04:00
{
innovVelPos [ obsIndex ] = statesAtVelTime [ stateIndex ] - observation [ obsIndex ] ;
}
else if ( obsIndex = = 3 | | obsIndex = = 4 )
{
innovVelPos [ obsIndex ] = statesAtPosTime [ stateIndex ] - observation [ obsIndex ] ;
}
2013-12-30 06:27:50 -04:00
else
2013-12-29 05:48:15 -04:00
{
innovVelPos [ obsIndex ] = statesAtHgtTime [ stateIndex ] - observation [ obsIndex ] ;
}
// Calculate the Kalman Gain
// Calculate innovation variances - also used for data logging
varInnovVelPos [ obsIndex ] = P [ stateIndex ] [ stateIndex ] + R_OBS [ obsIndex ] ;
SK = 1.0f / varInnovVelPos [ obsIndex ] ;
// Check the innovation for consistency and don't fuse if > TBD Sigma
// Currently disabled for testing
2013-12-30 16:56:28 -04:00
for ( uint8_t i = 0 ; i < = indexLimit ; i + + )
2013-12-29 05:48:15 -04:00
{
Kfusion [ i ] = P [ i ] [ stateIndex ] * SK ;
}
// Calculate state corrections and re-normalise the quaternions
2013-12-30 16:56:28 -04:00
for ( uint8_t i = 0 ; i < = indexLimit ; i + + )
2013-12-29 05:48:15 -04:00
{
states [ i ] = states [ i ] - Kfusion [ i ] * innovVelPos [ obsIndex ] ;
}
2013-12-30 02:32:09 -04:00
Quaternion q ( states [ 0 ] , states [ 1 ] , states [ 2 ] , states [ 3 ] ) ;
q . normalize ( ) ;
for ( uint8_t i = 0 ; i < = 3 ; i + + ) {
states [ i ] = q [ i ] ;
2013-12-29 05:48:15 -04:00
}
2013-12-30 02:32:09 -04:00
2013-12-29 05:48:15 -04:00
// Update the covariance - take advantage of direct observation of a
// single state at index = stateIndex to reduce computations
// Optimised implementation of standard equation P = (I - K*H)*P;
2013-12-30 16:56:28 -04:00
for ( uint8_t i = 0 ; i < = indexLimit ; i + + )
2013-12-29 05:48:15 -04:00
{
2013-12-30 16:56:28 -04:00
for ( uint8_t j = 0 ; j < = indexLimit ; j + + )
2013-12-29 05:48:15 -04:00
{
KHP [ i ] [ j ] = Kfusion [ i ] * P [ stateIndex ] [ j ] ;
}
}
2013-12-30 16:56:28 -04:00
for ( uint8_t i = 0 ; i < = indexLimit ; i + + )
2013-12-29 05:48:15 -04:00
{
2013-12-30 16:56:28 -04:00
for ( uint8_t j = 0 ; j < = indexLimit ; j + + )
2013-12-29 05:48:15 -04:00
{
P [ i ] [ j ] = P [ i ] [ j ] - KHP [ i ] [ j ] ;
}
}
}
}
}
2014-01-03 15:59:47 -04:00
// force the covariance matrix to me symmetrical and limit the variances to prevent
// ill-condiioning.
ForceSymmetry ( ) ;
ConstrainVariances ( ) ;
2013-12-30 06:41:28 -04:00
perf_end ( _perf_FuseVelPosNED ) ;
2013-12-25 18:58:02 -04:00
}
2013-12-29 03:37:55 -04:00
void NavEKF : : FuseMagnetometer ( )
2013-12-25 18:58:02 -04:00
{
2013-12-30 06:41:28 -04:00
perf_begin ( _perf_FuseMagnetometer ) ;
2014-01-03 00:37:19 -04:00
ftype & q0 = mag_state . q0 ;
ftype & q1 = mag_state . q1 ;
ftype & q2 = mag_state . q2 ;
ftype & q3 = mag_state . q3 ;
ftype & magN = mag_state . magN ;
ftype & magE = mag_state . magE ;
ftype & magD = mag_state . magD ;
ftype & magXbias = mag_state . magXbias ;
ftype & magYbias = mag_state . magYbias ;
ftype & magZbias = mag_state . magZbias ;
2013-12-29 05:48:15 -04:00
uint8_t & obsIndex = mag_state . obsIndex ;
Matrix3f & DCM = mag_state . DCM ;
Vector3f & MagPred = mag_state . MagPred ;
2014-01-03 00:37:19 -04:00
ftype & R_MAG = mag_state . R_MAG ;
ftype * SH_MAG = & mag_state . SH_MAG [ 0 ] ;
2014-01-03 03:52:37 -04:00
Vector21 H_MAG ;
2013-12-29 22:25:02 -04:00
Vector6 SK_MX ;
Vector6 SK_MY ;
Vector6 SK_MZ ;
2014-01-03 03:52:37 -04:00
Vector21 Kfusion ;
2013-12-30 16:56:28 -04:00
uint8_t indexLimit ; // used to prevent access to wind and magnetic field states and variances when on ground
2013-12-29 03:37:55 -04:00
// Perform sequential fusion of Magnetometer measurements.
// This assumes that the errors in the different components are
// uncorrelated which is not true, however in the absence of covariance
// data fit is the only assumption we can make
// so we might as well take advantage of the computational efficiencies
// associated with sequential fusion
2013-12-29 05:48:15 -04:00
if ( fuseMagData | | obsIndex = = 1 | | obsIndex = = 2 )
{
2013-12-30 19:21:04 -04:00
// Prevent access last 11 states when on ground.
if ( ! onGround )
{
2014-01-03 03:52:37 -04:00
indexLimit = 20 ;
2013-12-30 19:21:04 -04:00
}
else
{
indexLimit = 12 ;
}
2013-12-29 05:48:15 -04:00
// Calculate observation jacobians and Kalman gains
if ( fuseMagData )
{
// Copy required states to local variable names
q0 = statesAtMagMeasTime [ 0 ] ;
q1 = statesAtMagMeasTime [ 1 ] ;
q2 = statesAtMagMeasTime [ 2 ] ;
q3 = statesAtMagMeasTime [ 3 ] ;
2014-01-03 03:52:37 -04:00
magN = statesAtMagMeasTime [ 15 ] ;
magE = statesAtMagMeasTime [ 16 ] ;
magD = statesAtMagMeasTime [ 17 ] ;
magXbias = statesAtMagMeasTime [ 18 ] ;
magYbias = statesAtMagMeasTime [ 19 ] ;
magZbias = statesAtMagMeasTime [ 20 ] ;
2013-12-29 05:48:15 -04:00
// rotate predicted earth components into body axes and calculate
// predicted measurements
DCM [ 0 ] [ 0 ] = q0 * q0 + q1 * q1 - q2 * q2 - q3 * q3 ;
DCM [ 0 ] [ 1 ] = 2 * ( q1 * q2 + q0 * q3 ) ;
DCM [ 0 ] [ 2 ] = 2 * ( q1 * q3 - q0 * q2 ) ;
DCM [ 1 ] [ 0 ] = 2 * ( q1 * q2 - q0 * q3 ) ;
DCM [ 1 ] [ 1 ] = q0 * q0 - q1 * q1 + q2 * q2 - q3 * q3 ;
DCM [ 1 ] [ 2 ] = 2 * ( q2 * q3 + q0 * q1 ) ;
DCM [ 2 ] [ 0 ] = 2 * ( q1 * q3 + q0 * q2 ) ;
DCM [ 2 ] [ 1 ] = 2 * ( q2 * q3 - q0 * q1 ) ;
DCM [ 2 ] [ 2 ] = q0 * q0 - q1 * q1 - q2 * q2 + q3 * q3 ;
MagPred [ 0 ] = DCM [ 0 ] [ 0 ] * magN + DCM [ 0 ] [ 1 ] * magE + DCM [ 0 ] [ 2 ] * magD + magXbias ;
MagPred [ 1 ] = DCM [ 1 ] [ 0 ] * magN + DCM [ 1 ] [ 1 ] * magE + DCM [ 1 ] [ 2 ] * magD + magYbias ;
MagPred [ 2 ] = DCM [ 2 ] [ 0 ] * magN + DCM [ 2 ] [ 1 ] * magE + DCM [ 2 ] [ 2 ] * magD + magZbias ;
// scale magnetometer observation error with total angular rate
2014-01-03 22:04:00 -04:00
R_MAG = _magVar + sq ( _magVarRateScale * dAngIMU . length ( ) / dtIMU ) ;
2013-12-29 05:48:15 -04:00
// Calculate observation jacobians
SH_MAG [ 0 ] = 2 * magD * q3 + 2 * magE * q2 + 2 * magN * q1 ;
SH_MAG [ 1 ] = 2 * magD * q0 - 2 * magE * q1 + 2 * magN * q2 ;
SH_MAG [ 2 ] = 2 * magD * q1 + 2 * magE * q0 - 2 * magN * q3 ;
SH_MAG [ 3 ] = sq ( q3 ) ;
SH_MAG [ 4 ] = sq ( q2 ) ;
SH_MAG [ 5 ] = sq ( q1 ) ;
SH_MAG [ 6 ] = sq ( q0 ) ;
SH_MAG [ 7 ] = 2 * magN * q0 ;
SH_MAG [ 8 ] = 2 * magE * q3 ;
2014-01-03 03:52:37 -04:00
for ( uint8_t i = 0 ; i < = 20 ; i + + ) H_MAG [ i ] = 0 ;
2013-12-29 05:48:15 -04:00
H_MAG [ 0 ] = SH_MAG [ 7 ] + SH_MAG [ 8 ] - 2 * magD * q2 ;
H_MAG [ 1 ] = SH_MAG [ 0 ] ;
H_MAG [ 2 ] = 2 * magE * q1 - 2 * magD * q0 - 2 * magN * q2 ;
H_MAG [ 3 ] = SH_MAG [ 2 ] ;
2014-01-03 03:52:37 -04:00
H_MAG [ 15 ] = SH_MAG [ 5 ] - SH_MAG [ 4 ] - SH_MAG [ 3 ] + SH_MAG [ 6 ] ;
H_MAG [ 16 ] = 2 * q0 * q3 + 2 * q1 * q2 ;
H_MAG [ 17 ] = 2 * q1 * q3 - 2 * q0 * q2 ;
H_MAG [ 18 ] = 1 ;
2013-12-29 05:48:15 -04:00
// Calculate Kalman gain
2014-01-03 03:52:37 -04:00
SK_MX [ 0 ] = 1 / ( P [ 18 ] [ 18 ] + R_MAG + P [ 1 ] [ 18 ] * SH_MAG [ 0 ] + P [ 3 ] [ 18 ] * SH_MAG [ 2 ] - P [ 15 ] [ 18 ] * ( SH_MAG [ 3 ] + SH_MAG [ 4 ] - SH_MAG [ 5 ] - SH_MAG [ 6 ] ) - ( 2 * magD * q0 - 2 * magE * q1 + 2 * magN * q2 ) * ( P [ 18 ] [ 2 ] + P [ 1 ] [ 2 ] * SH_MAG [ 0 ] + P [ 3 ] [ 2 ] * SH_MAG [ 2 ] - P [ 15 ] [ 2 ] * ( SH_MAG [ 3 ] + SH_MAG [ 4 ] - SH_MAG [ 5 ] - SH_MAG [ 6 ] ) + P [ 16 ] [ 2 ] * ( 2 * q0 * q3 + 2 * q1 * q2 ) - P [ 17 ] [ 2 ] * ( 2 * q0 * q2 - 2 * q1 * q3 ) - P [ 2 ] [ 2 ] * ( 2 * magD * q0 - 2 * magE * q1 + 2 * magN * q2 ) + P [ 0 ] [ 2 ] * ( SH_MAG [ 7 ] + SH_MAG [ 8 ] - 2 * magD * q2 ) ) + ( SH_MAG [ 7 ] + SH_MAG [ 8 ] - 2 * magD * q2 ) * ( P [ 18 ] [ 0 ] + P [ 1 ] [ 0 ] * SH_MAG [ 0 ] + P [ 3 ] [ 0 ] * SH_MAG [ 2 ] - P [ 15 ] [ 0 ] * ( SH_MAG [ 3 ] + SH_MAG [ 4 ] - SH_MAG [ 5 ] - SH_MAG [ 6 ] ) + P [ 16 ] [ 0 ] * ( 2 * q0 * q3 + 2 * q1 * q2 ) - P [ 17 ] [ 0 ] * ( 2 * q0 * q2 - 2 * q1 * q3 ) - P [ 2 ] [ 0 ] * ( 2 * magD * q0 - 2 * magE * q1 + 2 * magN * q2 ) + P [ 0 ] [ 0 ] * ( SH_MAG [ 7 ] + SH_MAG [ 8 ] - 2 * magD * q2 ) ) + SH_MAG [ 0 ] * ( P [ 18 ] [ 1 ] + P [ 1 ] [ 1 ] * SH_MAG [ 0 ] + P [ 3 ] [ 1 ] * SH_MAG [ 2 ] - P [ 15 ] [ 1 ] * ( SH_MAG [ 3 ] + SH_MAG [ 4 ] - SH_MAG [ 5 ] - SH_MAG [ 6 ] ) + P [ 16 ] [ 1 ] * ( 2 * q0 * q3 + 2 * q1 * q2 ) - P [ 17 ] [ 1 ] * ( 2 * q0 * q2 - 2 * q1 * q3 ) - P [ 2 ] [ 1 ] * ( 2 * magD * q0 - 2 * magE * q1 + 2 * magN * q2 ) + P [ 0 ] [ 1 ] * ( SH_MAG [ 7 ] + SH_MAG [ 8 ] - 2 * magD * q2 ) ) + SH_MAG [ 2 ] * ( P [ 18 ] [ 3 ] + P [ 1 ] [ 3 ] * SH_MAG [ 0 ] + P [ 3 ] [ 3 ] * SH_MAG [ 2 ] - P [ 15 ] [ 3 ] * ( SH_MAG [ 3 ] + SH_MAG [ 4 ] - SH_MAG [ 5 ] - SH_MAG [ 6 ] ) + P [ 16 ] [ 3 ] * ( 2 * q0 * q3 + 2 * q1 * q2 ) - P [ 17 ] [ 3 ] * ( 2 * q0 * q2 - 2 * q1 * q3 ) - P [ 2 ] [ 3 ] * ( 2 * magD * q0 - 2 * magE * q1 + 2 * magN * q2 ) + P [ 0 ] [ 3 ] * ( SH_MAG [ 7 ] + SH_MAG [ 8 ] - 2 * magD * q2 ) ) - ( SH_MAG [ 3 ] + SH_MAG [ 4 ] - SH_MAG [ 5 ] - SH_MAG [ 6 ] ) * ( P [ 18 ] [ 15 ] + P [ 1 ] [ 15 ] * SH_MAG [ 0 ] + P [ 3 ] [ 15 ] * SH_MAG [ 2 ] - P [ 15 ] [ 15 ] * ( SH_MAG [ 3 ] + SH_MAG [ 4 ] - SH_MAG [ 5 ] - SH_MAG [ 6 ] ) + P [ 16 ] [ 15 ] * ( 2 * q0 * q3 + 2 * q1 * q2 ) - P [ 17 ] [ 15 ] * ( 2 * q0 * q2 - 2 * q1 * q3 ) - P [ 2 ] [ 15 ] * ( 2 * magD * q0 - 2 * magE * q1 + 2 * magN * q2 ) + P [ 0 ] [ 15 ] * ( SH_MAG [ 7 ] + SH_MAG [ 8 ] - 2 * magD * q2 ) ) + P [ 16 ] [ 18 ] * ( 2 * q0 * q3 + 2 * q1 * q2 ) - P [ 17 ] [ 18 ] * ( 2 * q0 * q2 - 2 * q1 * q3 ) - P [ 2 ] [ 18 ] * ( 2 * magD * q0 - 2 * magE * q1 + 2 * magN * q2 ) + ( 2 * q0 * q3 + 2 * q1 * q2 ) * ( P [ 18 ] [ 16 ] + P [ 1 ] [ 16 ] * SH_MAG [ 0 ] + P [ 3 ] [ 16 ] * SH_MAG [ 2 ] - P [ 15 ] [ 16 ] * ( SH_MAG [ 3 ] + SH_MAG [ 4 ] - SH_MAG [ 5 ] - SH_MAG [ 6 ] ) + P [ 16 ] [ 16 ] * ( 2 * q0 * q3 + 2 * q1 * q2 ) - P [ 17 ] [ 16 ] * ( 2 * q0 * q2 - 2 * q1 * q3 ) - P [ 2 ] [ 16 ] * ( 2 * magD * q0 - 2 * magE * q1 + 2 * magN * q2 ) + P [ 0 ] [ 16 ] * ( SH_MAG [ 7 ] + SH_MAG [ 8 ] - 2 * magD * q2 ) ) - ( 2 * q0 * q2 - 2 * q1 * q3 ) * ( P [ 18 ] [ 17 ] + P [ 1 ] [ 17 ] * SH_MAG [ 0 ] + P [ 3 ] [ 17 ] * SH_MAG [ 2 ] - P [ 15 ] [ 17 ] * ( SH_MAG [ 3 ] + SH_MAG [ 4 ] - SH_MAG [ 5 ] - SH_MAG [ 6 ] ) + P [ 16 ] [ 17 ] * ( 2 * q0 * q3 + 2 * q1 * q2 ) - P [ 17 ] [ 17 ] * ( 2 * q0 * q2 - 2 * q1 * q3 ) - P [ 2 ] [ 17 ] * ( 2 * magD * q0 - 2 * magE * q1 + 2 * magN * q2 ) + P [ 0 ] [ 17 ] * ( SH_MAG [ 7 ] + SH_MAG [ 8 ] - 2 * magD * q2 ) ) + P [ 0 ] [ 18 ] * ( SH_MAG [ 7 ] + SH_MAG [ 8 ] - 2 * magD * q2 ) ) ;
2013-12-29 05:48:15 -04:00
SK_MX [ 1 ] = SH_MAG [ 3 ] + SH_MAG [ 4 ] - SH_MAG [ 5 ] - SH_MAG [ 6 ] ;
SK_MX [ 2 ] = 2 * magD * q0 - 2 * magE * q1 + 2 * magN * q2 ;
SK_MX [ 3 ] = SH_MAG [ 7 ] + SH_MAG [ 8 ] - 2 * magD * q2 ;
SK_MX [ 4 ] = 2 * q0 * q2 - 2 * q1 * q3 ;
SK_MX [ 5 ] = 2 * q0 * q3 + 2 * q1 * q2 ;
2014-01-03 03:52:37 -04:00
Kfusion [ 0 ] = SK_MX [ 0 ] * ( P [ 0 ] [ 18 ] + P [ 0 ] [ 1 ] * SH_MAG [ 0 ] + P [ 0 ] [ 3 ] * SH_MAG [ 2 ] + P [ 0 ] [ 0 ] * SK_MX [ 3 ] - P [ 0 ] [ 2 ] * SK_MX [ 2 ] - P [ 0 ] [ 15 ] * SK_MX [ 1 ] + P [ 0 ] [ 16 ] * SK_MX [ 5 ] - P [ 0 ] [ 17 ] * SK_MX [ 4 ] ) ;
Kfusion [ 1 ] = SK_MX [ 0 ] * ( P [ 1 ] [ 18 ] + P [ 1 ] [ 1 ] * SH_MAG [ 0 ] + P [ 1 ] [ 3 ] * SH_MAG [ 2 ] + P [ 1 ] [ 0 ] * SK_MX [ 3 ] - P [ 1 ] [ 2 ] * SK_MX [ 2 ] - P [ 1 ] [ 15 ] * SK_MX [ 1 ] + P [ 1 ] [ 16 ] * SK_MX [ 5 ] - P [ 1 ] [ 17 ] * SK_MX [ 4 ] ) ;
Kfusion [ 2 ] = SK_MX [ 0 ] * ( P [ 2 ] [ 18 ] + P [ 2 ] [ 1 ] * SH_MAG [ 0 ] + P [ 2 ] [ 3 ] * SH_MAG [ 2 ] + P [ 2 ] [ 0 ] * SK_MX [ 3 ] - P [ 2 ] [ 2 ] * SK_MX [ 2 ] - P [ 2 ] [ 15 ] * SK_MX [ 1 ] + P [ 2 ] [ 16 ] * SK_MX [ 5 ] - P [ 2 ] [ 17 ] * SK_MX [ 4 ] ) ;
Kfusion [ 3 ] = SK_MX [ 0 ] * ( P [ 3 ] [ 18 ] + P [ 3 ] [ 1 ] * SH_MAG [ 0 ] + P [ 3 ] [ 3 ] * SH_MAG [ 2 ] + P [ 3 ] [ 0 ] * SK_MX [ 3 ] - P [ 3 ] [ 2 ] * SK_MX [ 2 ] - P [ 3 ] [ 15 ] * SK_MX [ 1 ] + P [ 3 ] [ 16 ] * SK_MX [ 5 ] - P [ 3 ] [ 17 ] * SK_MX [ 4 ] ) ;
Kfusion [ 4 ] = SK_MX [ 0 ] * ( P [ 4 ] [ 18 ] + P [ 4 ] [ 1 ] * SH_MAG [ 0 ] + P [ 4 ] [ 3 ] * SH_MAG [ 2 ] + P [ 4 ] [ 0 ] * SK_MX [ 3 ] - P [ 4 ] [ 2 ] * SK_MX [ 2 ] - P [ 4 ] [ 15 ] * SK_MX [ 1 ] + P [ 4 ] [ 16 ] * SK_MX [ 5 ] - P [ 4 ] [ 17 ] * SK_MX [ 4 ] ) ;
Kfusion [ 5 ] = SK_MX [ 0 ] * ( P [ 5 ] [ 18 ] + P [ 5 ] [ 1 ] * SH_MAG [ 0 ] + P [ 5 ] [ 3 ] * SH_MAG [ 2 ] + P [ 5 ] [ 0 ] * SK_MX [ 3 ] - P [ 5 ] [ 2 ] * SK_MX [ 2 ] - P [ 5 ] [ 15 ] * SK_MX [ 1 ] + P [ 5 ] [ 16 ] * SK_MX [ 5 ] - P [ 5 ] [ 17 ] * SK_MX [ 4 ] ) ;
Kfusion [ 6 ] = SK_MX [ 0 ] * ( P [ 6 ] [ 18 ] + P [ 6 ] [ 1 ] * SH_MAG [ 0 ] + P [ 6 ] [ 3 ] * SH_MAG [ 2 ] + P [ 6 ] [ 0 ] * SK_MX [ 3 ] - P [ 6 ] [ 2 ] * SK_MX [ 2 ] - P [ 6 ] [ 15 ] * SK_MX [ 1 ] + P [ 6 ] [ 16 ] * SK_MX [ 5 ] - P [ 6 ] [ 17 ] * SK_MX [ 4 ] ) ;
Kfusion [ 7 ] = SK_MX [ 0 ] * ( P [ 7 ] [ 18 ] + P [ 7 ] [ 1 ] * SH_MAG [ 0 ] + P [ 7 ] [ 3 ] * SH_MAG [ 2 ] + P [ 7 ] [ 0 ] * SK_MX [ 3 ] - P [ 7 ] [ 2 ] * SK_MX [ 2 ] - P [ 7 ] [ 15 ] * SK_MX [ 1 ] + P [ 7 ] [ 16 ] * SK_MX [ 5 ] - P [ 7 ] [ 17 ] * SK_MX [ 4 ] ) ;
Kfusion [ 8 ] = SK_MX [ 0 ] * ( P [ 8 ] [ 18 ] + P [ 8 ] [ 1 ] * SH_MAG [ 0 ] + P [ 8 ] [ 3 ] * SH_MAG [ 2 ] + P [ 8 ] [ 0 ] * SK_MX [ 3 ] - P [ 8 ] [ 2 ] * SK_MX [ 2 ] - P [ 8 ] [ 15 ] * SK_MX [ 1 ] + P [ 8 ] [ 16 ] * SK_MX [ 5 ] - P [ 8 ] [ 17 ] * SK_MX [ 4 ] ) ;
Kfusion [ 9 ] = SK_MX [ 0 ] * ( P [ 9 ] [ 18 ] + P [ 9 ] [ 1 ] * SH_MAG [ 0 ] + P [ 9 ] [ 3 ] * SH_MAG [ 2 ] + P [ 9 ] [ 0 ] * SK_MX [ 3 ] - P [ 9 ] [ 2 ] * SK_MX [ 2 ] - P [ 9 ] [ 15 ] * SK_MX [ 1 ] + P [ 9 ] [ 16 ] * SK_MX [ 5 ] - P [ 9 ] [ 17 ] * SK_MX [ 4 ] ) ;
Kfusion [ 10 ] = SK_MX [ 0 ] * ( P [ 10 ] [ 18 ] + P [ 10 ] [ 1 ] * SH_MAG [ 0 ] + P [ 10 ] [ 3 ] * SH_MAG [ 2 ] + P [ 10 ] [ 0 ] * SK_MX [ 3 ] - P [ 10 ] [ 2 ] * SK_MX [ 2 ] - P [ 10 ] [ 15 ] * SK_MX [ 1 ] + P [ 10 ] [ 16 ] * SK_MX [ 5 ] - P [ 10 ] [ 17 ] * SK_MX [ 4 ] ) ;
Kfusion [ 11 ] = SK_MX [ 0 ] * ( P [ 11 ] [ 18 ] + P [ 11 ] [ 1 ] * SH_MAG [ 0 ] + P [ 11 ] [ 3 ] * SH_MAG [ 2 ] + P [ 11 ] [ 0 ] * SK_MX [ 3 ] - P [ 11 ] [ 2 ] * SK_MX [ 2 ] - P [ 11 ] [ 15 ] * SK_MX [ 1 ] + P [ 11 ] [ 16 ] * SK_MX [ 5 ] - P [ 11 ] [ 17 ] * SK_MX [ 4 ] ) ;
Kfusion [ 12 ] = SK_MX [ 0 ] * ( P [ 12 ] [ 18 ] + P [ 12 ] [ 1 ] * SH_MAG [ 0 ] + P [ 12 ] [ 3 ] * SH_MAG [ 2 ] + P [ 12 ] [ 0 ] * SK_MX [ 3 ] - P [ 12 ] [ 2 ] * SK_MX [ 2 ] - P [ 12 ] [ 15 ] * SK_MX [ 1 ] + P [ 12 ] [ 16 ] * SK_MX [ 5 ] - P [ 12 ] [ 17 ] * SK_MX [ 4 ] ) ;
Kfusion [ 13 ] = SK_MX [ 0 ] * ( P [ 13 ] [ 18 ] + P [ 13 ] [ 1 ] * SH_MAG [ 0 ] + P [ 13 ] [ 3 ] * SH_MAG [ 2 ] + P [ 13 ] [ 0 ] * SK_MX [ 3 ] - P [ 13 ] [ 2 ] * SK_MX [ 2 ] - P [ 13 ] [ 15 ] * SK_MX [ 1 ] + P [ 13 ] [ 16 ] * SK_MX [ 5 ] - P [ 13 ] [ 17 ] * SK_MX [ 4 ] ) ;
Kfusion [ 14 ] = SK_MX [ 0 ] * ( P [ 14 ] [ 18 ] + P [ 14 ] [ 1 ] * SH_MAG [ 0 ] + P [ 14 ] [ 3 ] * SH_MAG [ 2 ] + P [ 14 ] [ 0 ] * SK_MX [ 3 ] - P [ 14 ] [ 2 ] * SK_MX [ 2 ] - P [ 14 ] [ 15 ] * SK_MX [ 1 ] + P [ 14 ] [ 16 ] * SK_MX [ 5 ] - P [ 14 ] [ 17 ] * SK_MX [ 4 ] ) ;
Kfusion [ 15 ] = SK_MX [ 0 ] * ( P [ 15 ] [ 18 ] + P [ 15 ] [ 1 ] * SH_MAG [ 0 ] + P [ 15 ] [ 3 ] * SH_MAG [ 2 ] + P [ 15 ] [ 0 ] * SK_MX [ 3 ] - P [ 15 ] [ 2 ] * SK_MX [ 2 ] - P [ 15 ] [ 15 ] * SK_MX [ 1 ] + P [ 15 ] [ 16 ] * SK_MX [ 5 ] - P [ 15 ] [ 17 ] * SK_MX [ 4 ] ) ;
Kfusion [ 16 ] = SK_MX [ 0 ] * ( P [ 16 ] [ 18 ] + P [ 16 ] [ 1 ] * SH_MAG [ 0 ] + P [ 16 ] [ 3 ] * SH_MAG [ 2 ] + P [ 16 ] [ 0 ] * SK_MX [ 3 ] - P [ 16 ] [ 2 ] * SK_MX [ 2 ] - P [ 16 ] [ 15 ] * SK_MX [ 1 ] + P [ 16 ] [ 16 ] * SK_MX [ 5 ] - P [ 16 ] [ 17 ] * SK_MX [ 4 ] ) ;
Kfusion [ 17 ] = SK_MX [ 0 ] * ( P [ 17 ] [ 18 ] + P [ 17 ] [ 1 ] * SH_MAG [ 0 ] + P [ 17 ] [ 3 ] * SH_MAG [ 2 ] + P [ 17 ] [ 0 ] * SK_MX [ 3 ] - P [ 17 ] [ 2 ] * SK_MX [ 2 ] - P [ 17 ] [ 15 ] * SK_MX [ 1 ] + P [ 17 ] [ 16 ] * SK_MX [ 5 ] - P [ 17 ] [ 17 ] * SK_MX [ 4 ] ) ;
Kfusion [ 18 ] = SK_MX [ 0 ] * ( P [ 18 ] [ 18 ] + P [ 18 ] [ 1 ] * SH_MAG [ 0 ] + P [ 18 ] [ 3 ] * SH_MAG [ 2 ] + P [ 18 ] [ 0 ] * SK_MX [ 3 ] - P [ 18 ] [ 2 ] * SK_MX [ 2 ] - P [ 18 ] [ 15 ] * SK_MX [ 1 ] + P [ 18 ] [ 16 ] * SK_MX [ 5 ] - P [ 18 ] [ 17 ] * SK_MX [ 4 ] ) ;
Kfusion [ 19 ] = SK_MX [ 0 ] * ( P [ 19 ] [ 18 ] + P [ 19 ] [ 1 ] * SH_MAG [ 0 ] + P [ 19 ] [ 3 ] * SH_MAG [ 2 ] + P [ 19 ] [ 0 ] * SK_MX [ 3 ] - P [ 19 ] [ 2 ] * SK_MX [ 2 ] - P [ 19 ] [ 15 ] * SK_MX [ 1 ] + P [ 19 ] [ 16 ] * SK_MX [ 5 ] - P [ 19 ] [ 17 ] * SK_MX [ 4 ] ) ;
Kfusion [ 20 ] = SK_MX [ 0 ] * ( P [ 20 ] [ 18 ] + P [ 20 ] [ 1 ] * SH_MAG [ 0 ] + P [ 20 ] [ 3 ] * SH_MAG [ 2 ] + P [ 20 ] [ 0 ] * SK_MX [ 3 ] - P [ 20 ] [ 2 ] * SK_MX [ 2 ] - P [ 20 ] [ 15 ] * SK_MX [ 1 ] + P [ 20 ] [ 16 ] * SK_MX [ 5 ] - P [ 20 ] [ 17 ] * SK_MX [ 4 ] ) ;
2013-12-29 05:48:15 -04:00
varInnovMag [ 0 ] = 1.0f / SK_MX [ 0 ] ;
// reset the observation index to 0 (we start by fusing the X
// measurement)
obsIndex = 0 ;
2013-12-30 04:58:24 -04:00
// set flags to indicate to other processes that fusion has been perfomred and is required on the next time step
magFusePerformed = true ;
magFuseRequired = true ;
2013-12-29 05:48:15 -04:00
}
else if ( obsIndex = = 1 ) // we are now fusing the Y measurement
{
// Calculate observation jacobians
2014-01-03 03:52:37 -04:00
for ( uint8_t i = 0 ; i < = 20 ; i + + ) H_MAG [ i ] = 0 ;
2013-12-29 05:48:15 -04:00
H_MAG [ 0 ] = SH_MAG [ 2 ] ;
H_MAG [ 1 ] = SH_MAG [ 1 ] ;
H_MAG [ 2 ] = SH_MAG [ 0 ] ;
H_MAG [ 3 ] = 2 * magD * q2 - SH_MAG [ 8 ] - SH_MAG [ 7 ] ;
2014-01-03 03:52:37 -04:00
H_MAG [ 15 ] = 2 * q1 * q2 - 2 * q0 * q3 ;
H_MAG [ 16 ] = SH_MAG [ 4 ] - SH_MAG [ 3 ] - SH_MAG [ 5 ] + SH_MAG [ 6 ] ;
H_MAG [ 17 ] = 2 * q0 * q1 + 2 * q2 * q3 ;
H_MAG [ 19 ] = 1 ;
2013-12-29 05:48:15 -04:00
// Calculate Kalman gain
2014-01-03 03:52:37 -04:00
SK_MY [ 0 ] = 1 / ( P [ 19 ] [ 19 ] + R_MAG + P [ 0 ] [ 19 ] * SH_MAG [ 2 ] + P [ 1 ] [ 19 ] * SH_MAG [ 1 ] + P [ 2 ] [ 19 ] * SH_MAG [ 0 ] - P [ 16 ] [ 19 ] * ( SH_MAG [ 3 ] - SH_MAG [ 4 ] + SH_MAG [ 5 ] - SH_MAG [ 6 ] ) - ( 2 * q0 * q3 - 2 * q1 * q2 ) * ( P [ 19 ] [ 15 ] + P [ 0 ] [ 15 ] * SH_MAG [ 2 ] + P [ 1 ] [ 15 ] * SH_MAG [ 1 ] + P [ 2 ] [ 15 ] * SH_MAG [ 0 ] - P [ 16 ] [ 15 ] * ( SH_MAG [ 3 ] - SH_MAG [ 4 ] + SH_MAG [ 5 ] - SH_MAG [ 6 ] ) - P [ 15 ] [ 15 ] * ( 2 * q0 * q3 - 2 * q1 * q2 ) + P [ 17 ] [ 15 ] * ( 2 * q0 * q1 + 2 * q2 * q3 ) - P [ 3 ] [ 15 ] * ( SH_MAG [ 7 ] + SH_MAG [ 8 ] - 2 * magD * q2 ) ) + ( 2 * q0 * q1 + 2 * q2 * q3 ) * ( P [ 19 ] [ 17 ] + P [ 0 ] [ 17 ] * SH_MAG [ 2 ] + P [ 1 ] [ 17 ] * SH_MAG [ 1 ] + P [ 2 ] [ 17 ] * SH_MAG [ 0 ] - P [ 16 ] [ 17 ] * ( SH_MAG [ 3 ] - SH_MAG [ 4 ] + SH_MAG [ 5 ] - SH_MAG [ 6 ] ) - P [ 15 ] [ 17 ] * ( 2 * q0 * q3 - 2 * q1 * q2 ) + P [ 17 ] [ 17 ] * ( 2 * q0 * q1 + 2 * q2 * q3 ) - P [ 3 ] [ 17 ] * ( SH_MAG [ 7 ] + SH_MAG [ 8 ] - 2 * magD * q2 ) ) - ( SH_MAG [ 7 ] + SH_MAG [ 8 ] - 2 * magD * q2 ) * ( P [ 19 ] [ 3 ] + P [ 0 ] [ 3 ] * SH_MAG [ 2 ] + P [ 1 ] [ 3 ] * SH_MAG [ 1 ] + P [ 2 ] [ 3 ] * SH_MAG [ 0 ] - P [ 16 ] [ 3 ] * ( SH_MAG [ 3 ] - SH_MAG [ 4 ] + SH_MAG [ 5 ] - SH_MAG [ 6 ] ) - P [ 15 ] [ 3 ] * ( 2 * q0 * q3 - 2 * q1 * q2 ) + P [ 17 ] [ 3 ] * ( 2 * q0 * q1 + 2 * q2 * q3 ) - P [ 3 ] [ 3 ] * ( SH_MAG [ 7 ] + SH_MAG [ 8 ] - 2 * magD * q2 ) ) - P [ 15 ] [ 19 ] * ( 2 * q0 * q3 - 2 * q1 * q2 ) + P [ 17 ] [ 19 ] * ( 2 * q0 * q1 + 2 * q2 * q3 ) + SH_MAG [ 2 ] * ( P [ 19 ] [ 0 ] + P [ 0 ] [ 0 ] * SH_MAG [ 2 ] + P [ 1 ] [ 0 ] * SH_MAG [ 1 ] + P [ 2 ] [ 0 ] * SH_MAG [ 0 ] - P [ 16 ] [ 0 ] * ( SH_MAG [ 3 ] - SH_MAG [ 4 ] + SH_MAG [ 5 ] - SH_MAG [ 6 ] ) - P [ 15 ] [ 0 ] * ( 2 * q0 * q3 - 2 * q1 * q2 ) + P [ 17 ] [ 0 ] * ( 2 * q0 * q1 + 2 * q2 * q3 ) - P [ 3 ] [ 0 ] * ( SH_MAG [ 7 ] + SH_MAG [ 8 ] - 2 * magD * q2 ) ) + SH_MAG [ 1 ] * ( P [ 19 ] [ 1 ] + P [ 0 ] [ 1 ] * SH_MAG [ 2 ] + P [ 1 ] [ 1 ] * SH_MAG [ 1 ] + P [ 2 ] [ 1 ] * SH_MAG [ 0 ] - P [ 16 ] [ 1 ] * ( SH_MAG [ 3 ] - SH_MAG [ 4 ] + SH_MAG [ 5 ] - SH_MAG [ 6 ] ) - P [ 15 ] [ 1 ] * ( 2 * q0 * q3 - 2 * q1 * q2 ) + P [ 17 ] [ 1 ] * ( 2 * q0 * q1 + 2 * q2 * q3 ) - P [ 3 ] [ 1 ] * ( SH_MAG [ 7 ] + SH_MAG [ 8 ] - 2 * magD * q2 ) ) + SH_MAG [ 0 ] * ( P [ 19 ] [ 2 ] + P [ 0 ] [ 2 ] * SH_MAG [ 2 ] + P [ 1 ] [ 2 ] * SH_MAG [ 1 ] + P [ 2 ] [ 2 ] * SH_MAG [ 0 ] - P [ 16 ] [ 2 ] * ( SH_MAG [ 3 ] - SH_MAG [ 4 ] + SH_MAG [ 5 ] - SH_MAG [ 6 ] ) - P [ 15 ] [ 2 ] * ( 2 * q0 * q3 - 2 * q1 * q2 ) + P [ 17 ] [ 2 ] * ( 2 * q0 * q1 + 2 * q2 * q3 ) - P [ 3 ] [ 2 ] * ( SH_MAG [ 7 ] + SH_MAG [ 8 ] - 2 * magD * q2 ) ) - ( SH_MAG [ 3 ] - SH_MAG [ 4 ] + SH_MAG [ 5 ] - SH_MAG [ 6 ] ) * ( P [ 19 ] [ 16 ] + P [ 0 ] [ 16 ] * SH_MAG [ 2 ] + P [ 1 ] [ 16 ] * SH_MAG [ 1 ] + P [ 2 ] [ 16 ] * SH_MAG [ 0 ] - P [ 16 ] [ 16 ] * ( SH_MAG [ 3 ] - SH_MAG [ 4 ] + SH_MAG [ 5 ] - SH_MAG [ 6 ] ) - P [ 15 ] [ 16 ] * ( 2 * q0 * q3 - 2 * q1 * q2 ) + P [ 17 ] [ 16 ] * ( 2 * q0 * q1 + 2 * q2 * q3 ) - P [ 3 ] [ 16 ] * ( SH_MAG [ 7 ] + SH_MAG [ 8 ] - 2 * magD * q2 ) ) - P [ 3 ] [ 19 ] * ( SH_MAG [ 7 ] + SH_MAG [ 8 ] - 2 * magD * q2 ) ) ;
2013-12-29 05:48:15 -04:00
SK_MY [ 1 ] = SH_MAG [ 3 ] - SH_MAG [ 4 ] + SH_MAG [ 5 ] - SH_MAG [ 6 ] ;
SK_MY [ 2 ] = SH_MAG [ 7 ] + SH_MAG [ 8 ] - 2 * magD * q2 ;
SK_MY [ 3 ] = 2 * q0 * q3 - 2 * q1 * q2 ;
SK_MY [ 4 ] = 2 * q0 * q1 + 2 * q2 * q3 ;
2014-01-03 03:52:37 -04:00
Kfusion [ 0 ] = SK_MY [ 0 ] * ( P [ 0 ] [ 19 ] + P [ 0 ] [ 0 ] * SH_MAG [ 2 ] + P [ 0 ] [ 1 ] * SH_MAG [ 1 ] + P [ 0 ] [ 2 ] * SH_MAG [ 0 ] - P [ 0 ] [ 3 ] * SK_MY [ 2 ] - P [ 0 ] [ 16 ] * SK_MY [ 1 ] - P [ 0 ] [ 15 ] * SK_MY [ 3 ] + P [ 0 ] [ 17 ] * SK_MY [ 4 ] ) ;
Kfusion [ 1 ] = SK_MY [ 0 ] * ( P [ 1 ] [ 19 ] + P [ 1 ] [ 0 ] * SH_MAG [ 2 ] + P [ 1 ] [ 1 ] * SH_MAG [ 1 ] + P [ 1 ] [ 2 ] * SH_MAG [ 0 ] - P [ 1 ] [ 3 ] * SK_MY [ 2 ] - P [ 1 ] [ 16 ] * SK_MY [ 1 ] - P [ 1 ] [ 15 ] * SK_MY [ 3 ] + P [ 1 ] [ 17 ] * SK_MY [ 4 ] ) ;
Kfusion [ 2 ] = SK_MY [ 0 ] * ( P [ 2 ] [ 19 ] + P [ 2 ] [ 0 ] * SH_MAG [ 2 ] + P [ 2 ] [ 1 ] * SH_MAG [ 1 ] + P [ 2 ] [ 2 ] * SH_MAG [ 0 ] - P [ 2 ] [ 3 ] * SK_MY [ 2 ] - P [ 2 ] [ 16 ] * SK_MY [ 1 ] - P [ 2 ] [ 15 ] * SK_MY [ 3 ] + P [ 2 ] [ 17 ] * SK_MY [ 4 ] ) ;
Kfusion [ 3 ] = SK_MY [ 0 ] * ( P [ 3 ] [ 19 ] + P [ 3 ] [ 0 ] * SH_MAG [ 2 ] + P [ 3 ] [ 1 ] * SH_MAG [ 1 ] + P [ 3 ] [ 2 ] * SH_MAG [ 0 ] - P [ 3 ] [ 3 ] * SK_MY [ 2 ] - P [ 3 ] [ 16 ] * SK_MY [ 1 ] - P [ 3 ] [ 15 ] * SK_MY [ 3 ] + P [ 3 ] [ 17 ] * SK_MY [ 4 ] ) ;
Kfusion [ 4 ] = SK_MY [ 0 ] * ( P [ 4 ] [ 19 ] + P [ 4 ] [ 0 ] * SH_MAG [ 2 ] + P [ 4 ] [ 1 ] * SH_MAG [ 1 ] + P [ 4 ] [ 2 ] * SH_MAG [ 0 ] - P [ 4 ] [ 3 ] * SK_MY [ 2 ] - P [ 4 ] [ 16 ] * SK_MY [ 1 ] - P [ 4 ] [ 15 ] * SK_MY [ 3 ] + P [ 4 ] [ 17 ] * SK_MY [ 4 ] ) ;
Kfusion [ 5 ] = SK_MY [ 0 ] * ( P [ 5 ] [ 19 ] + P [ 5 ] [ 0 ] * SH_MAG [ 2 ] + P [ 5 ] [ 1 ] * SH_MAG [ 1 ] + P [ 5 ] [ 2 ] * SH_MAG [ 0 ] - P [ 5 ] [ 3 ] * SK_MY [ 2 ] - P [ 5 ] [ 16 ] * SK_MY [ 1 ] - P [ 5 ] [ 15 ] * SK_MY [ 3 ] + P [ 5 ] [ 17 ] * SK_MY [ 4 ] ) ;
Kfusion [ 6 ] = SK_MY [ 0 ] * ( P [ 6 ] [ 19 ] + P [ 6 ] [ 0 ] * SH_MAG [ 2 ] + P [ 6 ] [ 1 ] * SH_MAG [ 1 ] + P [ 6 ] [ 2 ] * SH_MAG [ 0 ] - P [ 6 ] [ 3 ] * SK_MY [ 2 ] - P [ 6 ] [ 16 ] * SK_MY [ 1 ] - P [ 6 ] [ 15 ] * SK_MY [ 3 ] + P [ 6 ] [ 17 ] * SK_MY [ 4 ] ) ;
Kfusion [ 7 ] = SK_MY [ 0 ] * ( P [ 7 ] [ 19 ] + P [ 7 ] [ 0 ] * SH_MAG [ 2 ] + P [ 7 ] [ 1 ] * SH_MAG [ 1 ] + P [ 7 ] [ 2 ] * SH_MAG [ 0 ] - P [ 7 ] [ 3 ] * SK_MY [ 2 ] - P [ 7 ] [ 16 ] * SK_MY [ 1 ] - P [ 7 ] [ 15 ] * SK_MY [ 3 ] + P [ 7 ] [ 17 ] * SK_MY [ 4 ] ) ;
Kfusion [ 8 ] = SK_MY [ 0 ] * ( P [ 8 ] [ 19 ] + P [ 8 ] [ 0 ] * SH_MAG [ 2 ] + P [ 8 ] [ 1 ] * SH_MAG [ 1 ] + P [ 8 ] [ 2 ] * SH_MAG [ 0 ] - P [ 8 ] [ 3 ] * SK_MY [ 2 ] - P [ 8 ] [ 16 ] * SK_MY [ 1 ] - P [ 8 ] [ 15 ] * SK_MY [ 3 ] + P [ 8 ] [ 17 ] * SK_MY [ 4 ] ) ;
Kfusion [ 9 ] = SK_MY [ 0 ] * ( P [ 9 ] [ 19 ] + P [ 9 ] [ 0 ] * SH_MAG [ 2 ] + P [ 9 ] [ 1 ] * SH_MAG [ 1 ] + P [ 9 ] [ 2 ] * SH_MAG [ 0 ] - P [ 9 ] [ 3 ] * SK_MY [ 2 ] - P [ 9 ] [ 16 ] * SK_MY [ 1 ] - P [ 9 ] [ 15 ] * SK_MY [ 3 ] + P [ 9 ] [ 17 ] * SK_MY [ 4 ] ) ;
Kfusion [ 10 ] = SK_MY [ 0 ] * ( P [ 10 ] [ 19 ] + P [ 10 ] [ 0 ] * SH_MAG [ 2 ] + P [ 10 ] [ 1 ] * SH_MAG [ 1 ] + P [ 10 ] [ 2 ] * SH_MAG [ 0 ] - P [ 10 ] [ 3 ] * SK_MY [ 2 ] - P [ 10 ] [ 16 ] * SK_MY [ 1 ] - P [ 10 ] [ 15 ] * SK_MY [ 3 ] + P [ 10 ] [ 17 ] * SK_MY [ 4 ] ) ;
Kfusion [ 11 ] = SK_MY [ 0 ] * ( P [ 11 ] [ 19 ] + P [ 11 ] [ 0 ] * SH_MAG [ 2 ] + P [ 11 ] [ 1 ] * SH_MAG [ 1 ] + P [ 11 ] [ 2 ] * SH_MAG [ 0 ] - P [ 11 ] [ 3 ] * SK_MY [ 2 ] - P [ 11 ] [ 16 ] * SK_MY [ 1 ] - P [ 11 ] [ 15 ] * SK_MY [ 3 ] + P [ 11 ] [ 17 ] * SK_MY [ 4 ] ) ;
Kfusion [ 12 ] = SK_MY [ 0 ] * ( P [ 12 ] [ 19 ] + P [ 12 ] [ 0 ] * SH_MAG [ 2 ] + P [ 12 ] [ 1 ] * SH_MAG [ 1 ] + P [ 12 ] [ 2 ] * SH_MAG [ 0 ] - P [ 12 ] [ 3 ] * SK_MY [ 2 ] - P [ 12 ] [ 16 ] * SK_MY [ 1 ] - P [ 12 ] [ 15 ] * SK_MY [ 3 ] + P [ 12 ] [ 17 ] * SK_MY [ 4 ] ) ;
Kfusion [ 13 ] = SK_MY [ 0 ] * ( P [ 13 ] [ 19 ] + P [ 13 ] [ 0 ] * SH_MAG [ 2 ] + P [ 13 ] [ 1 ] * SH_MAG [ 1 ] + P [ 13 ] [ 2 ] * SH_MAG [ 0 ] - P [ 13 ] [ 3 ] * SK_MY [ 2 ] - P [ 13 ] [ 16 ] * SK_MY [ 1 ] - P [ 13 ] [ 15 ] * SK_MY [ 3 ] + P [ 13 ] [ 17 ] * SK_MY [ 4 ] ) ;
Kfusion [ 14 ] = SK_MY [ 0 ] * ( P [ 14 ] [ 19 ] + P [ 14 ] [ 0 ] * SH_MAG [ 2 ] + P [ 14 ] [ 1 ] * SH_MAG [ 1 ] + P [ 14 ] [ 2 ] * SH_MAG [ 0 ] - P [ 14 ] [ 3 ] * SK_MY [ 2 ] - P [ 14 ] [ 16 ] * SK_MY [ 1 ] - P [ 14 ] [ 15 ] * SK_MY [ 3 ] + P [ 14 ] [ 17 ] * SK_MY [ 4 ] ) ;
Kfusion [ 15 ] = SK_MY [ 0 ] * ( P [ 15 ] [ 19 ] + P [ 15 ] [ 0 ] * SH_MAG [ 2 ] + P [ 15 ] [ 1 ] * SH_MAG [ 1 ] + P [ 15 ] [ 2 ] * SH_MAG [ 0 ] - P [ 15 ] [ 3 ] * SK_MY [ 2 ] - P [ 15 ] [ 16 ] * SK_MY [ 1 ] - P [ 15 ] [ 15 ] * SK_MY [ 3 ] + P [ 15 ] [ 17 ] * SK_MY [ 4 ] ) ;
Kfusion [ 16 ] = SK_MY [ 0 ] * ( P [ 16 ] [ 19 ] + P [ 16 ] [ 0 ] * SH_MAG [ 2 ] + P [ 16 ] [ 1 ] * SH_MAG [ 1 ] + P [ 16 ] [ 2 ] * SH_MAG [ 0 ] - P [ 16 ] [ 3 ] * SK_MY [ 2 ] - P [ 16 ] [ 16 ] * SK_MY [ 1 ] - P [ 16 ] [ 15 ] * SK_MY [ 3 ] + P [ 16 ] [ 17 ] * SK_MY [ 4 ] ) ;
Kfusion [ 17 ] = SK_MY [ 0 ] * ( P [ 17 ] [ 19 ] + P [ 17 ] [ 0 ] * SH_MAG [ 2 ] + P [ 17 ] [ 1 ] * SH_MAG [ 1 ] + P [ 17 ] [ 2 ] * SH_MAG [ 0 ] - P [ 17 ] [ 3 ] * SK_MY [ 2 ] - P [ 17 ] [ 16 ] * SK_MY [ 1 ] - P [ 17 ] [ 15 ] * SK_MY [ 3 ] + P [ 17 ] [ 17 ] * SK_MY [ 4 ] ) ;
Kfusion [ 18 ] = SK_MY [ 0 ] * ( P [ 18 ] [ 19 ] + P [ 18 ] [ 0 ] * SH_MAG [ 2 ] + P [ 18 ] [ 1 ] * SH_MAG [ 1 ] + P [ 18 ] [ 2 ] * SH_MAG [ 0 ] - P [ 18 ] [ 3 ] * SK_MY [ 2 ] - P [ 18 ] [ 16 ] * SK_MY [ 1 ] - P [ 18 ] [ 15 ] * SK_MY [ 3 ] + P [ 18 ] [ 17 ] * SK_MY [ 4 ] ) ;
Kfusion [ 19 ] = SK_MY [ 0 ] * ( P [ 19 ] [ 19 ] + P [ 19 ] [ 0 ] * SH_MAG [ 2 ] + P [ 19 ] [ 1 ] * SH_MAG [ 1 ] + P [ 19 ] [ 2 ] * SH_MAG [ 0 ] - P [ 19 ] [ 3 ] * SK_MY [ 2 ] - P [ 19 ] [ 16 ] * SK_MY [ 1 ] - P [ 19 ] [ 15 ] * SK_MY [ 3 ] + P [ 19 ] [ 17 ] * SK_MY [ 4 ] ) ;
Kfusion [ 20 ] = SK_MY [ 0 ] * ( P [ 20 ] [ 19 ] + P [ 20 ] [ 0 ] * SH_MAG [ 2 ] + P [ 20 ] [ 1 ] * SH_MAG [ 1 ] + P [ 20 ] [ 2 ] * SH_MAG [ 0 ] - P [ 20 ] [ 3 ] * SK_MY [ 2 ] - P [ 20 ] [ 16 ] * SK_MY [ 1 ] - P [ 20 ] [ 15 ] * SK_MY [ 3 ] + P [ 20 ] [ 17 ] * SK_MY [ 4 ] ) ;
2013-12-29 05:48:15 -04:00
varInnovMag [ 1 ] = 1.0f / SK_MY [ 0 ] ;
2013-12-30 04:58:24 -04:00
// set flags to indicate to other processes that fusion has been perfomred and is required on the next time step
magFusePerformed = true ;
magFuseRequired = true ;
2013-12-29 05:48:15 -04:00
}
else if ( obsIndex = = 2 ) // we are now fusing the Z measurement
{
// Calculate observation jacobians
2014-01-03 03:52:37 -04:00
for ( uint8_t i = 0 ; i < = 20 ; i + + ) H_MAG [ i ] = 0 ;
2013-12-29 05:48:15 -04:00
H_MAG [ 0 ] = SH_MAG [ 1 ] ;
H_MAG [ 1 ] = 2 * magN * q3 - 2 * magE * q0 - 2 * magD * q1 ;
H_MAG [ 2 ] = SH_MAG [ 7 ] + SH_MAG [ 8 ] - 2 * magD * q2 ;
H_MAG [ 3 ] = SH_MAG [ 0 ] ;
2014-01-03 03:52:37 -04:00
H_MAG [ 15 ] = 2 * q0 * q2 + 2 * q1 * q3 ;
H_MAG [ 16 ] = 2 * q2 * q3 - 2 * q0 * q1 ;
H_MAG [ 17 ] = SH_MAG [ 3 ] - SH_MAG [ 4 ] - SH_MAG [ 5 ] + SH_MAG [ 6 ] ;
H_MAG [ 20 ] = 1 ;
2013-12-29 05:48:15 -04:00
// Calculate Kalman gain
2014-01-03 03:52:37 -04:00
SK_MZ [ 0 ] = 1 / ( P [ 20 ] [ 20 ] + R_MAG + P [ 0 ] [ 20 ] * SH_MAG [ 1 ] + P [ 3 ] [ 20 ] * SH_MAG [ 0 ] + P [ 17 ] [ 20 ] * ( SH_MAG [ 3 ] - SH_MAG [ 4 ] - SH_MAG [ 5 ] + SH_MAG [ 6 ] ) - ( 2 * magD * q1 + 2 * magE * q0 - 2 * magN * q3 ) * ( P [ 20 ] [ 1 ] + P [ 0 ] [ 1 ] * SH_MAG [ 1 ] + P [ 3 ] [ 1 ] * SH_MAG [ 0 ] + P [ 17 ] [ 1 ] * ( SH_MAG [ 3 ] - SH_MAG [ 4 ] - SH_MAG [ 5 ] + SH_MAG [ 6 ] ) + P [ 15 ] [ 1 ] * ( 2 * q0 * q2 + 2 * q1 * q3 ) - P [ 16 ] [ 1 ] * ( 2 * q0 * q1 - 2 * q2 * q3 ) - P [ 1 ] [ 1 ] * ( 2 * magD * q1 + 2 * magE * q0 - 2 * magN * q3 ) + P [ 2 ] [ 1 ] * ( SH_MAG [ 7 ] + SH_MAG [ 8 ] - 2 * magD * q2 ) ) + ( SH_MAG [ 7 ] + SH_MAG [ 8 ] - 2 * magD * q2 ) * ( P [ 20 ] [ 2 ] + P [ 0 ] [ 2 ] * SH_MAG [ 1 ] + P [ 3 ] [ 2 ] * SH_MAG [ 0 ] + P [ 17 ] [ 2 ] * ( SH_MAG [ 3 ] - SH_MAG [ 4 ] - SH_MAG [ 5 ] + SH_MAG [ 6 ] ) + P [ 15 ] [ 2 ] * ( 2 * q0 * q2 + 2 * q1 * q3 ) - P [ 16 ] [ 2 ] * ( 2 * q0 * q1 - 2 * q2 * q3 ) - P [ 1 ] [ 2 ] * ( 2 * magD * q1 + 2 * magE * q0 - 2 * magN * q3 ) + P [ 2 ] [ 2 ] * ( SH_MAG [ 7 ] + SH_MAG [ 8 ] - 2 * magD * q2 ) ) + SH_MAG [ 1 ] * ( P [ 20 ] [ 0 ] + P [ 0 ] [ 0 ] * SH_MAG [ 1 ] + P [ 3 ] [ 0 ] * SH_MAG [ 0 ] + P [ 17 ] [ 0 ] * ( SH_MAG [ 3 ] - SH_MAG [ 4 ] - SH_MAG [ 5 ] + SH_MAG [ 6 ] ) + P [ 15 ] [ 0 ] * ( 2 * q0 * q2 + 2 * q1 * q3 ) - P [ 16 ] [ 0 ] * ( 2 * q0 * q1 - 2 * q2 * q3 ) - P [ 1 ] [ 0 ] * ( 2 * magD * q1 + 2 * magE * q0 - 2 * magN * q3 ) + P [ 2 ] [ 0 ] * ( SH_MAG [ 7 ] + SH_MAG [ 8 ] - 2 * magD * q2 ) ) + SH_MAG [ 0 ] * ( P [ 20 ] [ 3 ] + P [ 0 ] [ 3 ] * SH_MAG [ 1 ] + P [ 3 ] [ 3 ] * SH_MAG [ 0 ] + P [ 17 ] [ 3 ] * ( SH_MAG [ 3 ] - SH_MAG [ 4 ] - SH_MAG [ 5 ] + SH_MAG [ 6 ] ) + P [ 15 ] [ 3 ] * ( 2 * q0 * q2 + 2 * q1 * q3 ) - P [ 16 ] [ 3 ] * ( 2 * q0 * q1 - 2 * q2 * q3 ) - P [ 1 ] [ 3 ] * ( 2 * magD * q1 + 2 * magE * q0 - 2 * magN * q3 ) + P [ 2 ] [ 3 ] * ( SH_MAG [ 7 ] + SH_MAG [ 8 ] - 2 * magD * q2 ) ) + ( SH_MAG [ 3 ] - SH_MAG [ 4 ] - SH_MAG [ 5 ] + SH_MAG [ 6 ] ) * ( P [ 20 ] [ 17 ] + P [ 0 ] [ 17 ] * SH_MAG [ 1 ] + P [ 3 ] [ 17 ] * SH_MAG [ 0 ] + P [ 17 ] [ 17 ] * ( SH_MAG [ 3 ] - SH_MAG [ 4 ] - SH_MAG [ 5 ] + SH_MAG [ 6 ] ) + P [ 15 ] [ 17 ] * ( 2 * q0 * q2 + 2 * q1 * q3 ) - P [ 16 ] [ 17 ] * ( 2 * q0 * q1 - 2 * q2 * q3 ) - P [ 1 ] [ 17 ] * ( 2 * magD * q1 + 2 * magE * q0 - 2 * magN * q3 ) + P [ 2 ] [ 17 ] * ( SH_MAG [ 7 ] + SH_MAG [ 8 ] - 2 * magD * q2 ) ) + P [ 15 ] [ 20 ] * ( 2 * q0 * q2 + 2 * q1 * q3 ) - P [ 16 ] [ 20 ] * ( 2 * q0 * q1 - 2 * q2 * q3 ) - P [ 1 ] [ 20 ] * ( 2 * magD * q1 + 2 * magE * q0 - 2 * magN * q3 ) + ( 2 * q0 * q2 + 2 * q1 * q3 ) * ( P [ 20 ] [ 15 ] + P [ 0 ] [ 15 ] * SH_MAG [ 1 ] + P [ 3 ] [ 15 ] * SH_MAG [ 0 ] + P [ 17 ] [ 15 ] * ( SH_MAG [ 3 ] - SH_MAG [ 4 ] - SH_MAG [ 5 ] + SH_MAG [ 6 ] ) + P [ 15 ] [ 15 ] * ( 2 * q0 * q2 + 2 * q1 * q3 ) - P [ 16 ] [ 15 ] * ( 2 * q0 * q1 - 2 * q2 * q3 ) - P [ 1 ] [ 15 ] * ( 2 * magD * q1 + 2 * magE * q0 - 2 * magN * q3 ) + P [ 2 ] [ 15 ] * ( SH_MAG [ 7 ] + SH_MAG [ 8 ] - 2 * magD * q2 ) ) - ( 2 * q0 * q1 - 2 * q2 * q3 ) * ( P [ 20 ] [ 16 ] + P [ 0 ] [ 16 ] * SH_MAG [ 1 ] + P [ 3 ] [ 16 ] * SH_MAG [ 0 ] + P [ 17 ] [ 16 ] * ( SH_MAG [ 3 ] - SH_MAG [ 4 ] - SH_MAG [ 5 ] + SH_MAG [ 6 ] ) + P [ 15 ] [ 16 ] * ( 2 * q0 * q2 + 2 * q1 * q3 ) - P [ 16 ] [ 16 ] * ( 2 * q0 * q1 - 2 * q2 * q3 ) - P [ 1 ] [ 16 ] * ( 2 * magD * q1 + 2 * magE * q0 - 2 * magN * q3 ) + P [ 2 ] [ 16 ] * ( SH_MAG [ 7 ] + SH_MAG [ 8 ] - 2 * magD * q2 ) ) + P [ 2 ] [ 20 ] * ( SH_MAG [ 7 ] + SH_MAG [ 8 ] - 2 * magD * q2 ) ) ;
2013-12-29 05:48:15 -04:00
SK_MZ [ 1 ] = SH_MAG [ 3 ] - SH_MAG [ 4 ] - SH_MAG [ 5 ] + SH_MAG [ 6 ] ;
SK_MZ [ 2 ] = 2 * magD * q1 + 2 * magE * q0 - 2 * magN * q3 ;
SK_MZ [ 3 ] = SH_MAG [ 7 ] + SH_MAG [ 8 ] - 2 * magD * q2 ;
SK_MZ [ 4 ] = 2 * q0 * q1 - 2 * q2 * q3 ;
SK_MZ [ 5 ] = 2 * q0 * q2 + 2 * q1 * q3 ;
2014-01-03 03:52:37 -04:00
Kfusion [ 0 ] = SK_MZ [ 0 ] * ( P [ 0 ] [ 20 ] + P [ 0 ] [ 0 ] * SH_MAG [ 1 ] + P [ 0 ] [ 3 ] * SH_MAG [ 0 ] - P [ 0 ] [ 1 ] * SK_MZ [ 2 ] + P [ 0 ] [ 2 ] * SK_MZ [ 3 ] + P [ 0 ] [ 17 ] * SK_MZ [ 1 ] + P [ 0 ] [ 15 ] * SK_MZ [ 5 ] - P [ 0 ] [ 16 ] * SK_MZ [ 4 ] ) ;
Kfusion [ 1 ] = SK_MZ [ 0 ] * ( P [ 1 ] [ 20 ] + P [ 1 ] [ 0 ] * SH_MAG [ 1 ] + P [ 1 ] [ 3 ] * SH_MAG [ 0 ] - P [ 1 ] [ 1 ] * SK_MZ [ 2 ] + P [ 1 ] [ 2 ] * SK_MZ [ 3 ] + P [ 1 ] [ 17 ] * SK_MZ [ 1 ] + P [ 1 ] [ 15 ] * SK_MZ [ 5 ] - P [ 1 ] [ 16 ] * SK_MZ [ 4 ] ) ;
Kfusion [ 2 ] = SK_MZ [ 0 ] * ( P [ 2 ] [ 20 ] + P [ 2 ] [ 0 ] * SH_MAG [ 1 ] + P [ 2 ] [ 3 ] * SH_MAG [ 0 ] - P [ 2 ] [ 1 ] * SK_MZ [ 2 ] + P [ 2 ] [ 2 ] * SK_MZ [ 3 ] + P [ 2 ] [ 17 ] * SK_MZ [ 1 ] + P [ 2 ] [ 15 ] * SK_MZ [ 5 ] - P [ 2 ] [ 16 ] * SK_MZ [ 4 ] ) ;
Kfusion [ 3 ] = SK_MZ [ 0 ] * ( P [ 3 ] [ 20 ] + P [ 3 ] [ 0 ] * SH_MAG [ 1 ] + P [ 3 ] [ 3 ] * SH_MAG [ 0 ] - P [ 3 ] [ 1 ] * SK_MZ [ 2 ] + P [ 3 ] [ 2 ] * SK_MZ [ 3 ] + P [ 3 ] [ 17 ] * SK_MZ [ 1 ] + P [ 3 ] [ 15 ] * SK_MZ [ 5 ] - P [ 3 ] [ 16 ] * SK_MZ [ 4 ] ) ;
Kfusion [ 4 ] = SK_MZ [ 0 ] * ( P [ 4 ] [ 20 ] + P [ 4 ] [ 0 ] * SH_MAG [ 1 ] + P [ 4 ] [ 3 ] * SH_MAG [ 0 ] - P [ 4 ] [ 1 ] * SK_MZ [ 2 ] + P [ 4 ] [ 2 ] * SK_MZ [ 3 ] + P [ 4 ] [ 17 ] * SK_MZ [ 1 ] + P [ 4 ] [ 15 ] * SK_MZ [ 5 ] - P [ 4 ] [ 16 ] * SK_MZ [ 4 ] ) ;
Kfusion [ 5 ] = SK_MZ [ 0 ] * ( P [ 5 ] [ 20 ] + P [ 5 ] [ 0 ] * SH_MAG [ 1 ] + P [ 5 ] [ 3 ] * SH_MAG [ 0 ] - P [ 5 ] [ 1 ] * SK_MZ [ 2 ] + P [ 5 ] [ 2 ] * SK_MZ [ 3 ] + P [ 5 ] [ 17 ] * SK_MZ [ 1 ] + P [ 5 ] [ 15 ] * SK_MZ [ 5 ] - P [ 5 ] [ 16 ] * SK_MZ [ 4 ] ) ;
Kfusion [ 6 ] = SK_MZ [ 0 ] * ( P [ 6 ] [ 20 ] + P [ 6 ] [ 0 ] * SH_MAG [ 1 ] + P [ 6 ] [ 3 ] * SH_MAG [ 0 ] - P [ 6 ] [ 1 ] * SK_MZ [ 2 ] + P [ 6 ] [ 2 ] * SK_MZ [ 3 ] + P [ 6 ] [ 17 ] * SK_MZ [ 1 ] + P [ 6 ] [ 15 ] * SK_MZ [ 5 ] - P [ 6 ] [ 16 ] * SK_MZ [ 4 ] ) ;
Kfusion [ 7 ] = SK_MZ [ 0 ] * ( P [ 7 ] [ 20 ] + P [ 7 ] [ 0 ] * SH_MAG [ 1 ] + P [ 7 ] [ 3 ] * SH_MAG [ 0 ] - P [ 7 ] [ 1 ] * SK_MZ [ 2 ] + P [ 7 ] [ 2 ] * SK_MZ [ 3 ] + P [ 7 ] [ 17 ] * SK_MZ [ 1 ] + P [ 7 ] [ 15 ] * SK_MZ [ 5 ] - P [ 7 ] [ 16 ] * SK_MZ [ 4 ] ) ;
Kfusion [ 8 ] = SK_MZ [ 0 ] * ( P [ 8 ] [ 20 ] + P [ 8 ] [ 0 ] * SH_MAG [ 1 ] + P [ 8 ] [ 3 ] * SH_MAG [ 0 ] - P [ 8 ] [ 1 ] * SK_MZ [ 2 ] + P [ 8 ] [ 2 ] * SK_MZ [ 3 ] + P [ 8 ] [ 17 ] * SK_MZ [ 1 ] + P [ 8 ] [ 15 ] * SK_MZ [ 5 ] - P [ 8 ] [ 16 ] * SK_MZ [ 4 ] ) ;
Kfusion [ 9 ] = SK_MZ [ 0 ] * ( P [ 9 ] [ 20 ] + P [ 9 ] [ 0 ] * SH_MAG [ 1 ] + P [ 9 ] [ 3 ] * SH_MAG [ 0 ] - P [ 9 ] [ 1 ] * SK_MZ [ 2 ] + P [ 9 ] [ 2 ] * SK_MZ [ 3 ] + P [ 9 ] [ 17 ] * SK_MZ [ 1 ] + P [ 9 ] [ 15 ] * SK_MZ [ 5 ] - P [ 9 ] [ 16 ] * SK_MZ [ 4 ] ) ;
Kfusion [ 10 ] = SK_MZ [ 0 ] * ( P [ 10 ] [ 20 ] + P [ 10 ] [ 0 ] * SH_MAG [ 1 ] + P [ 10 ] [ 3 ] * SH_MAG [ 0 ] - P [ 10 ] [ 1 ] * SK_MZ [ 2 ] + P [ 10 ] [ 2 ] * SK_MZ [ 3 ] + P [ 10 ] [ 17 ] * SK_MZ [ 1 ] + P [ 10 ] [ 15 ] * SK_MZ [ 5 ] - P [ 10 ] [ 16 ] * SK_MZ [ 4 ] ) ;
Kfusion [ 11 ] = SK_MZ [ 0 ] * ( P [ 11 ] [ 20 ] + P [ 11 ] [ 0 ] * SH_MAG [ 1 ] + P [ 11 ] [ 3 ] * SH_MAG [ 0 ] - P [ 11 ] [ 1 ] * SK_MZ [ 2 ] + P [ 11 ] [ 2 ] * SK_MZ [ 3 ] + P [ 11 ] [ 17 ] * SK_MZ [ 1 ] + P [ 11 ] [ 15 ] * SK_MZ [ 5 ] - P [ 11 ] [ 16 ] * SK_MZ [ 4 ] ) ;
Kfusion [ 12 ] = SK_MZ [ 0 ] * ( P [ 12 ] [ 20 ] + P [ 12 ] [ 0 ] * SH_MAG [ 1 ] + P [ 12 ] [ 3 ] * SH_MAG [ 0 ] - P [ 12 ] [ 1 ] * SK_MZ [ 2 ] + P [ 12 ] [ 2 ] * SK_MZ [ 3 ] + P [ 12 ] [ 17 ] * SK_MZ [ 1 ] + P [ 12 ] [ 15 ] * SK_MZ [ 5 ] - P [ 12 ] [ 16 ] * SK_MZ [ 4 ] ) ;
Kfusion [ 13 ] = SK_MZ [ 0 ] * ( P [ 13 ] [ 20 ] + P [ 13 ] [ 0 ] * SH_MAG [ 1 ] + P [ 13 ] [ 3 ] * SH_MAG [ 0 ] - P [ 13 ] [ 1 ] * SK_MZ [ 2 ] + P [ 13 ] [ 2 ] * SK_MZ [ 3 ] + P [ 13 ] [ 17 ] * SK_MZ [ 1 ] + P [ 13 ] [ 15 ] * SK_MZ [ 5 ] - P [ 13 ] [ 16 ] * SK_MZ [ 4 ] ) ;
Kfusion [ 14 ] = SK_MZ [ 0 ] * ( P [ 14 ] [ 20 ] + P [ 14 ] [ 0 ] * SH_MAG [ 1 ] + P [ 14 ] [ 3 ] * SH_MAG [ 0 ] - P [ 14 ] [ 1 ] * SK_MZ [ 2 ] + P [ 14 ] [ 2 ] * SK_MZ [ 3 ] + P [ 14 ] [ 17 ] * SK_MZ [ 1 ] + P [ 14 ] [ 15 ] * SK_MZ [ 5 ] - P [ 14 ] [ 16 ] * SK_MZ [ 4 ] ) ;
Kfusion [ 15 ] = SK_MZ [ 0 ] * ( P [ 15 ] [ 20 ] + P [ 15 ] [ 0 ] * SH_MAG [ 1 ] + P [ 15 ] [ 3 ] * SH_MAG [ 0 ] - P [ 15 ] [ 1 ] * SK_MZ [ 2 ] + P [ 15 ] [ 2 ] * SK_MZ [ 3 ] + P [ 15 ] [ 17 ] * SK_MZ [ 1 ] + P [ 15 ] [ 15 ] * SK_MZ [ 5 ] - P [ 15 ] [ 16 ] * SK_MZ [ 4 ] ) ;
Kfusion [ 16 ] = SK_MZ [ 0 ] * ( P [ 16 ] [ 20 ] + P [ 16 ] [ 0 ] * SH_MAG [ 1 ] + P [ 16 ] [ 3 ] * SH_MAG [ 0 ] - P [ 16 ] [ 1 ] * SK_MZ [ 2 ] + P [ 16 ] [ 2 ] * SK_MZ [ 3 ] + P [ 16 ] [ 17 ] * SK_MZ [ 1 ] + P [ 16 ] [ 15 ] * SK_MZ [ 5 ] - P [ 16 ] [ 16 ] * SK_MZ [ 4 ] ) ;
Kfusion [ 17 ] = SK_MZ [ 0 ] * ( P [ 17 ] [ 20 ] + P [ 17 ] [ 0 ] * SH_MAG [ 1 ] + P [ 17 ] [ 3 ] * SH_MAG [ 0 ] - P [ 17 ] [ 1 ] * SK_MZ [ 2 ] + P [ 17 ] [ 2 ] * SK_MZ [ 3 ] + P [ 17 ] [ 17 ] * SK_MZ [ 1 ] + P [ 17 ] [ 15 ] * SK_MZ [ 5 ] - P [ 17 ] [ 16 ] * SK_MZ [ 4 ] ) ;
Kfusion [ 18 ] = SK_MZ [ 0 ] * ( P [ 18 ] [ 20 ] + P [ 18 ] [ 0 ] * SH_MAG [ 1 ] + P [ 18 ] [ 3 ] * SH_MAG [ 0 ] - P [ 18 ] [ 1 ] * SK_MZ [ 2 ] + P [ 18 ] [ 2 ] * SK_MZ [ 3 ] + P [ 18 ] [ 17 ] * SK_MZ [ 1 ] + P [ 18 ] [ 15 ] * SK_MZ [ 5 ] - P [ 18 ] [ 16 ] * SK_MZ [ 4 ] ) ;
Kfusion [ 19 ] = SK_MZ [ 0 ] * ( P [ 19 ] [ 20 ] + P [ 19 ] [ 0 ] * SH_MAG [ 1 ] + P [ 19 ] [ 3 ] * SH_MAG [ 0 ] - P [ 19 ] [ 1 ] * SK_MZ [ 2 ] + P [ 19 ] [ 2 ] * SK_MZ [ 3 ] + P [ 19 ] [ 17 ] * SK_MZ [ 1 ] + P [ 19 ] [ 15 ] * SK_MZ [ 5 ] - P [ 19 ] [ 16 ] * SK_MZ [ 4 ] ) ;
Kfusion [ 20 ] = SK_MZ [ 0 ] * ( P [ 20 ] [ 20 ] + P [ 20 ] [ 0 ] * SH_MAG [ 1 ] + P [ 20 ] [ 3 ] * SH_MAG [ 0 ] - P [ 20 ] [ 1 ] * SK_MZ [ 2 ] + P [ 20 ] [ 2 ] * SK_MZ [ 3 ] + P [ 20 ] [ 17 ] * SK_MZ [ 1 ] + P [ 20 ] [ 15 ] * SK_MZ [ 5 ] - P [ 20 ] [ 16 ] * SK_MZ [ 4 ] ) ;
2013-12-29 05:48:15 -04:00
varInnovMag [ 2 ] = 1.0f / SK_MZ [ 0 ] ;
2013-12-30 04:58:24 -04:00
// set flags to indicate to other processes that fusion has been perfomred and is not required on the next time step
magFusePerformed = true ;
magFuseRequired = false ;
2013-12-29 05:48:15 -04:00
}
// Calculate the measurement innovation
innovMag [ obsIndex ] = MagPred [ obsIndex ] - magData [ obsIndex ] ;
// Check the innovation for consistency and don't fuse if > 5Sigma
if ( ( innovMag [ obsIndex ] * innovMag [ obsIndex ] / varInnovMag [ obsIndex ] ) < 25.0f )
{
// correct the state vector
2013-12-30 16:56:28 -04:00
for ( uint8_t j = 0 ; j < = indexLimit ; j + + )
2013-12-29 05:48:15 -04:00
{
states [ j ] = states [ j ] - Kfusion [ j ] * innovMag [ obsIndex ] ;
}
// normalise the quaternion states
2013-12-30 02:32:09 -04:00
float quatMag = sqrtf ( states [ 0 ] * states [ 0 ] + states [ 1 ] * states [ 1 ] + states [ 2 ] * states [ 2 ] + states [ 3 ] * states [ 3 ] ) ;
2013-12-29 05:48:15 -04:00
if ( quatMag > 1e-12 f )
{
for ( uint8_t j = 0 ; j < = 3 ; j + + )
{
float quatMagInv = 1.0f / quatMag ;
states [ j ] = states [ j ] * quatMagInv ;
}
}
// correct the covariance P = (I - K*H)*P
// take advantage of the empty columns in KH to reduce the
// number of operations
2013-12-30 19:21:04 -04:00
for ( uint8_t i = 0 ; i < = indexLimit ; i + + )
2013-12-29 05:48:15 -04:00
{
for ( uint8_t j = 0 ; j < = 3 ; j + + )
{
KH [ i ] [ j ] = Kfusion [ i ] * H_MAG [ j ] ;
}
2014-01-03 03:52:37 -04:00
for ( uint8_t j = 4 ; j < = 14 ; j + + ) KH [ i ] [ j ] = 0.0f ;
2013-12-30 19:21:04 -04:00
if ( ! onGround )
2013-12-29 05:48:15 -04:00
{
2014-01-03 03:52:37 -04:00
for ( uint8_t j = 15 ; j < = 20 ; j + + )
2013-12-30 19:21:04 -04:00
{
KH [ i ] [ j ] = Kfusion [ i ] * H_MAG [ j ] ;
}
}
else
{
2014-01-03 03:52:37 -04:00
for ( uint8_t j = 15 ; j < = 20 ; j + + )
2013-12-30 19:21:04 -04:00
{
KH [ i ] [ j ] = 0.0f ;
}
2013-12-29 05:48:15 -04:00
}
}
2013-12-30 19:21:04 -04:00
for ( uint8_t i = 0 ; i < = indexLimit ; i + + )
2013-12-29 05:48:15 -04:00
{
2013-12-30 19:21:04 -04:00
for ( uint8_t j = 0 ; j < = indexLimit ; j + + )
2013-12-29 05:48:15 -04:00
{
KHP [ i ] [ j ] = 0 ;
for ( uint8_t k = 0 ; k < = 3 ; k + + )
{
KHP [ i ] [ j ] = KHP [ i ] [ j ] + KH [ i ] [ k ] * P [ k ] [ j ] ;
}
2013-12-30 19:21:04 -04:00
if ( ! onGround )
2013-12-29 05:48:15 -04:00
{
2014-01-03 03:52:37 -04:00
for ( uint8_t k = 15 ; k < = 20 ; k + + )
2013-12-30 19:21:04 -04:00
{
KHP [ i ] [ j ] = KHP [ i ] [ j ] + KH [ i ] [ k ] * P [ k ] [ j ] ;
}
2013-12-29 05:48:15 -04:00
}
}
}
2013-12-30 16:56:28 -04:00
for ( uint8_t i = 0 ; i < = indexLimit ; i + + )
2013-12-29 05:48:15 -04:00
{
2013-12-30 16:56:28 -04:00
for ( uint8_t j = 0 ; j < = indexLimit ; j + + )
2013-12-29 05:48:15 -04:00
{
P [ i ] [ j ] = P [ i ] [ j ] - KHP [ i ] [ j ] ;
}
}
}
obsIndex = obsIndex + 1 ;
}
else
{
2013-12-30 04:58:24 -04:00
// set flags to indicate to other processes that fusion has not been performed and is not required on the next time step
magFusePerformed = false ;
magFuseRequired = false ;
2013-12-29 05:48:15 -04:00
}
2014-01-03 15:59:47 -04:00
// force the covariance matrix to me symmetrical and limit the variances to prevent
// ill-condiioning.
ForceSymmetry ( ) ;
ConstrainVariances ( ) ;
2013-12-30 06:41:28 -04:00
perf_end ( _perf_FuseMagnetometer ) ;
2013-12-25 18:58:02 -04:00
}
2013-12-29 03:37:55 -04:00
void NavEKF : : FuseAirspeed ( )
2013-12-25 18:58:02 -04:00
{
2013-12-30 06:41:28 -04:00
perf_begin ( _perf_FuseAirspeed ) ;
2013-12-29 05:48:15 -04:00
float vn ;
float ve ;
float vd ;
float vwn ;
float vwe ;
2014-01-01 21:15:22 -04:00
float EAS2TAS = _ahrs - > get_EAS2TAS ( ) ;
2014-01-01 17:12:06 -04:00
const float R_TAS = _easVar * sq ( constrain_float ( EAS2TAS , 1.0f , 10.0f ) ) ;
2013-12-29 22:25:02 -04:00
Vector3f SH_TAS ;
2013-12-29 05:48:15 -04:00
float SK_TAS ;
2014-01-03 03:52:37 -04:00
Vector21 H_TAS ;
Vector21 Kfusion ;
2013-12-29 05:48:15 -04:00
float VtasPred ;
// Copy required states to local variable names
vn = statesAtVtasMeasTime [ 4 ] ;
ve = statesAtVtasMeasTime [ 5 ] ;
vd = statesAtVtasMeasTime [ 6 ] ;
2014-01-03 03:52:37 -04:00
vwn = statesAtVtasMeasTime [ 13 ] ;
vwe = statesAtVtasMeasTime [ 14 ] ;
2013-12-29 05:48:15 -04:00
// Calculate the predicted airspeed
2013-12-30 02:32:09 -04:00
VtasPred = sqrtf ( ( ve - vwe ) * ( ve - vwe ) + ( vn - vwn ) * ( vn - vwn ) + vd * vd ) ;
2013-12-29 05:48:15 -04:00
// Perform fusion of True Airspeed measurement
if ( VtasPred > 1.0f )
{
// Calculate observation jacobians
2014-01-03 03:52:37 -04:00
SH_TAS [ 0 ] = 1 / ( sqrt ( sq ( ve - vwe ) + sq ( vn - vwn ) + sq ( vd ) ) ) ;
SH_TAS [ 1 ] = ( SH_TAS [ 0 ] * ( 2 * ve - 2 * vwe ) ) / 2 ;
SH_TAS [ 2 ] = ( SH_TAS [ 0 ] * ( 2 * vn - 2 * vwn ) ) / 2 ;
for ( uint8_t i = 0 ; i < = 20 ; i + + ) H_TAS [ i ] = 0.0f ;
2013-12-29 05:48:15 -04:00
H_TAS [ 4 ] = SH_TAS [ 2 ] ;
H_TAS [ 5 ] = SH_TAS [ 1 ] ;
H_TAS [ 6 ] = vd * SH_TAS [ 0 ] ;
2014-01-03 03:52:37 -04:00
H_TAS [ 13 ] = - SH_TAS [ 2 ] ;
H_TAS [ 14 ] = - SH_TAS [ 1 ] ;
2013-12-29 05:48:15 -04:00
// Calculate Kalman gains
2014-01-03 03:52:37 -04:00
SK_TAS = 1.0f / ( R_TAS + SH_TAS [ 2 ] * ( P [ 4 ] [ 4 ] * SH_TAS [ 2 ] + P [ 5 ] [ 4 ] * SH_TAS [ 1 ] - P [ 13 ] [ 4 ] * SH_TAS [ 2 ] - P [ 14 ] [ 4 ] * SH_TAS [ 1 ] + P [ 6 ] [ 4 ] * vd * SH_TAS [ 0 ] ) + SH_TAS [ 1 ] * ( P [ 4 ] [ 5 ] * SH_TAS [ 2 ] + P [ 5 ] [ 5 ] * SH_TAS [ 1 ] - P [ 13 ] [ 5 ] * SH_TAS [ 2 ] - P [ 14 ] [ 5 ] * SH_TAS [ 1 ] + P [ 6 ] [ 5 ] * vd * SH_TAS [ 0 ] ) - SH_TAS [ 2 ] * ( P [ 4 ] [ 13 ] * SH_TAS [ 2 ] + P [ 5 ] [ 13 ] * SH_TAS [ 1 ] - P [ 13 ] [ 13 ] * SH_TAS [ 2 ] - P [ 14 ] [ 13 ] * SH_TAS [ 1 ] + P [ 6 ] [ 13 ] * vd * SH_TAS [ 0 ] ) - SH_TAS [ 1 ] * ( P [ 4 ] [ 14 ] * SH_TAS [ 2 ] + P [ 5 ] [ 14 ] * SH_TAS [ 1 ] - P [ 13 ] [ 14 ] * SH_TAS [ 2 ] - P [ 14 ] [ 14 ] * SH_TAS [ 1 ] + P [ 6 ] [ 14 ] * vd * SH_TAS [ 0 ] ) + vd * SH_TAS [ 0 ] * ( P [ 4 ] [ 6 ] * SH_TAS [ 2 ] + P [ 5 ] [ 6 ] * SH_TAS [ 1 ] - P [ 13 ] [ 6 ] * SH_TAS [ 2 ] - P [ 14 ] [ 6 ] * SH_TAS [ 1 ] + P [ 6 ] [ 6 ] * vd * SH_TAS [ 0 ] ) ) ;
Kfusion [ 0 ] = SK_TAS * ( P [ 0 ] [ 4 ] * SH_TAS [ 2 ] - P [ 0 ] [ 13 ] * SH_TAS [ 2 ] + P [ 0 ] [ 5 ] * SH_TAS [ 1 ] - P [ 0 ] [ 14 ] * SH_TAS [ 1 ] + P [ 0 ] [ 6 ] * vd * SH_TAS [ 0 ] ) ;
Kfusion [ 1 ] = SK_TAS * ( P [ 1 ] [ 4 ] * SH_TAS [ 2 ] - P [ 1 ] [ 13 ] * SH_TAS [ 2 ] + P [ 1 ] [ 5 ] * SH_TAS [ 1 ] - P [ 1 ] [ 14 ] * SH_TAS [ 1 ] + P [ 1 ] [ 6 ] * vd * SH_TAS [ 0 ] ) ;
Kfusion [ 2 ] = SK_TAS * ( P [ 2 ] [ 4 ] * SH_TAS [ 2 ] - P [ 2 ] [ 13 ] * SH_TAS [ 2 ] + P [ 2 ] [ 5 ] * SH_TAS [ 1 ] - P [ 2 ] [ 14 ] * SH_TAS [ 1 ] + P [ 2 ] [ 6 ] * vd * SH_TAS [ 0 ] ) ;
Kfusion [ 3 ] = SK_TAS * ( P [ 3 ] [ 4 ] * SH_TAS [ 2 ] - P [ 3 ] [ 13 ] * SH_TAS [ 2 ] + P [ 3 ] [ 5 ] * SH_TAS [ 1 ] - P [ 3 ] [ 14 ] * SH_TAS [ 1 ] + P [ 3 ] [ 6 ] * vd * SH_TAS [ 0 ] ) ;
Kfusion [ 4 ] = SK_TAS * ( P [ 4 ] [ 4 ] * SH_TAS [ 2 ] - P [ 4 ] [ 13 ] * SH_TAS [ 2 ] + P [ 4 ] [ 5 ] * SH_TAS [ 1 ] - P [ 4 ] [ 14 ] * SH_TAS [ 1 ] + P [ 4 ] [ 6 ] * vd * SH_TAS [ 0 ] ) ;
Kfusion [ 5 ] = SK_TAS * ( P [ 5 ] [ 4 ] * SH_TAS [ 2 ] - P [ 5 ] [ 13 ] * SH_TAS [ 2 ] + P [ 5 ] [ 5 ] * SH_TAS [ 1 ] - P [ 5 ] [ 14 ] * SH_TAS [ 1 ] + P [ 5 ] [ 6 ] * vd * SH_TAS [ 0 ] ) ;
Kfusion [ 6 ] = SK_TAS * ( P [ 6 ] [ 4 ] * SH_TAS [ 2 ] - P [ 6 ] [ 13 ] * SH_TAS [ 2 ] + P [ 6 ] [ 5 ] * SH_TAS [ 1 ] - P [ 6 ] [ 14 ] * SH_TAS [ 1 ] + P [ 6 ] [ 6 ] * vd * SH_TAS [ 0 ] ) ;
Kfusion [ 7 ] = SK_TAS * ( P [ 7 ] [ 4 ] * SH_TAS [ 2 ] - P [ 7 ] [ 13 ] * SH_TAS [ 2 ] + P [ 7 ] [ 5 ] * SH_TAS [ 1 ] - P [ 7 ] [ 14 ] * SH_TAS [ 1 ] + P [ 7 ] [ 6 ] * vd * SH_TAS [ 0 ] ) ;
Kfusion [ 8 ] = SK_TAS * ( P [ 8 ] [ 4 ] * SH_TAS [ 2 ] - P [ 8 ] [ 13 ] * SH_TAS [ 2 ] + P [ 8 ] [ 5 ] * SH_TAS [ 1 ] - P [ 8 ] [ 14 ] * SH_TAS [ 1 ] + P [ 8 ] [ 6 ] * vd * SH_TAS [ 0 ] ) ;
Kfusion [ 9 ] = SK_TAS * ( P [ 9 ] [ 4 ] * SH_TAS [ 2 ] - P [ 9 ] [ 13 ] * SH_TAS [ 2 ] + P [ 9 ] [ 5 ] * SH_TAS [ 1 ] - P [ 9 ] [ 14 ] * SH_TAS [ 1 ] + P [ 9 ] [ 6 ] * vd * SH_TAS [ 0 ] ) ;
Kfusion [ 10 ] = SK_TAS * ( P [ 10 ] [ 4 ] * SH_TAS [ 2 ] - P [ 10 ] [ 13 ] * SH_TAS [ 2 ] + P [ 10 ] [ 5 ] * SH_TAS [ 1 ] - P [ 10 ] [ 14 ] * SH_TAS [ 1 ] + P [ 10 ] [ 6 ] * vd * SH_TAS [ 0 ] ) ;
Kfusion [ 11 ] = SK_TAS * ( P [ 11 ] [ 4 ] * SH_TAS [ 2 ] - P [ 11 ] [ 13 ] * SH_TAS [ 2 ] + P [ 11 ] [ 5 ] * SH_TAS [ 1 ] - P [ 11 ] [ 14 ] * SH_TAS [ 1 ] + P [ 11 ] [ 6 ] * vd * SH_TAS [ 0 ] ) ;
Kfusion [ 12 ] = SK_TAS * ( P [ 12 ] [ 4 ] * SH_TAS [ 2 ] - P [ 12 ] [ 13 ] * SH_TAS [ 2 ] + P [ 12 ] [ 5 ] * SH_TAS [ 1 ] - P [ 12 ] [ 14 ] * SH_TAS [ 1 ] + P [ 12 ] [ 6 ] * vd * SH_TAS [ 0 ] ) ;
Kfusion [ 13 ] = SK_TAS * ( P [ 13 ] [ 4 ] * SH_TAS [ 2 ] - P [ 13 ] [ 13 ] * SH_TAS [ 2 ] + P [ 13 ] [ 5 ] * SH_TAS [ 1 ] - P [ 13 ] [ 14 ] * SH_TAS [ 1 ] + P [ 13 ] [ 6 ] * vd * SH_TAS [ 0 ] ) ;
Kfusion [ 14 ] = SK_TAS * ( P [ 14 ] [ 4 ] * SH_TAS [ 2 ] - P [ 14 ] [ 13 ] * SH_TAS [ 2 ] + P [ 14 ] [ 5 ] * SH_TAS [ 1 ] - P [ 14 ] [ 14 ] * SH_TAS [ 1 ] + P [ 14 ] [ 6 ] * vd * SH_TAS [ 0 ] ) ;
Kfusion [ 15 ] = SK_TAS * ( P [ 15 ] [ 4 ] * SH_TAS [ 2 ] - P [ 15 ] [ 13 ] * SH_TAS [ 2 ] + P [ 15 ] [ 5 ] * SH_TAS [ 1 ] - P [ 15 ] [ 14 ] * SH_TAS [ 1 ] + P [ 15 ] [ 6 ] * vd * SH_TAS [ 0 ] ) ;
Kfusion [ 16 ] = SK_TAS * ( P [ 16 ] [ 4 ] * SH_TAS [ 2 ] - P [ 16 ] [ 13 ] * SH_TAS [ 2 ] + P [ 16 ] [ 5 ] * SH_TAS [ 1 ] - P [ 16 ] [ 14 ] * SH_TAS [ 1 ] + P [ 16 ] [ 6 ] * vd * SH_TAS [ 0 ] ) ;
Kfusion [ 17 ] = SK_TAS * ( P [ 17 ] [ 4 ] * SH_TAS [ 2 ] - P [ 17 ] [ 13 ] * SH_TAS [ 2 ] + P [ 17 ] [ 5 ] * SH_TAS [ 1 ] - P [ 17 ] [ 14 ] * SH_TAS [ 1 ] + P [ 17 ] [ 6 ] * vd * SH_TAS [ 0 ] ) ;
Kfusion [ 18 ] = SK_TAS * ( P [ 18 ] [ 4 ] * SH_TAS [ 2 ] - P [ 18 ] [ 13 ] * SH_TAS [ 2 ] + P [ 18 ] [ 5 ] * SH_TAS [ 1 ] - P [ 18 ] [ 14 ] * SH_TAS [ 1 ] + P [ 18 ] [ 6 ] * vd * SH_TAS [ 0 ] ) ;
Kfusion [ 19 ] = SK_TAS * ( P [ 19 ] [ 4 ] * SH_TAS [ 2 ] - P [ 19 ] [ 13 ] * SH_TAS [ 2 ] + P [ 19 ] [ 5 ] * SH_TAS [ 1 ] - P [ 19 ] [ 14 ] * SH_TAS [ 1 ] + P [ 19 ] [ 6 ] * vd * SH_TAS [ 0 ] ) ;
Kfusion [ 20 ] = SK_TAS * ( P [ 20 ] [ 4 ] * SH_TAS [ 2 ] - P [ 20 ] [ 13 ] * SH_TAS [ 2 ] + P [ 20 ] [ 5 ] * SH_TAS [ 1 ] - P [ 20 ] [ 14 ] * SH_TAS [ 1 ] + P [ 20 ] [ 6 ] * vd * SH_TAS [ 0 ] ) ;
2013-12-29 05:48:15 -04:00
varInnovVtas = 1.0f / SK_TAS ;
// Calculate the measurement innovation
innovVtas = VtasPred - VtasMeas ;
// Check the innovation for consistency and don't fuse if > 5Sigma
if ( ( innovVtas * innovVtas * SK_TAS ) < 25.0f )
{
// correct the state vector
2014-01-03 03:52:37 -04:00
for ( uint8_t j = 0 ; j < = 20 ; j + + )
2013-12-29 05:48:15 -04:00
{
states [ j ] = states [ j ] - Kfusion [ j ] * innovVtas ;
}
2013-12-30 02:32:09 -04:00
Quaternion q ( states [ 0 ] , states [ 1 ] , states [ 2 ] , states [ 3 ] ) ;
q . normalize ( ) ;
for ( uint8_t i = 0 ; i < = 3 ; i + + ) {
states [ i ] = q [ i ] ;
2013-12-29 05:48:15 -04:00
}
// correct the covariance P = (I - K*H)*P
// take advantage of the empty columns in H to reduce the
// number of operations
2014-01-03 03:52:37 -04:00
for ( uint8_t i = 0 ; i < = 20 ; i + + )
2013-12-29 05:48:15 -04:00
{
for ( uint8_t j = 0 ; j < = 3 ; j + + ) KH [ i ] [ j ] = 0.0 ;
for ( uint8_t j = 4 ; j < = 6 ; j + + )
{
KH [ i ] [ j ] = Kfusion [ i ] * H_TAS [ j ] ;
}
2014-01-03 03:52:37 -04:00
for ( uint8_t j = 7 ; j < = 12 ; j + + ) KH [ i ] [ j ] = 0.0 ;
for ( uint8_t j = 13 ; j < = 14 ; j + + )
2013-12-29 05:48:15 -04:00
{
KH [ i ] [ j ] = Kfusion [ i ] * H_TAS [ j ] ;
}
2014-01-03 03:52:37 -04:00
for ( uint8_t j = 15 ; j < = 20 ; j + + ) KH [ i ] [ j ] = 0.0 ;
2013-12-29 05:48:15 -04:00
}
2014-01-03 03:52:37 -04:00
for ( uint8_t i = 0 ; i < = 20 ; i + + )
2013-12-29 05:48:15 -04:00
{
2014-01-03 03:52:37 -04:00
for ( uint8_t j = 0 ; j < = 20 ; j + + )
2013-12-29 05:48:15 -04:00
{
KHP [ i ] [ j ] = 0 ;
for ( uint8_t k = 4 ; k < = 6 ; k + + )
{
KHP [ i ] [ j ] = KHP [ i ] [ j ] + KH [ i ] [ k ] * P [ k ] [ j ] ;
}
2014-01-03 03:52:37 -04:00
for ( uint8_t k = 13 ; k < = 14 ; k + + )
2013-12-29 05:48:15 -04:00
{
KHP [ i ] [ j ] = KHP [ i ] [ j ] + KH [ i ] [ k ] * P [ k ] [ j ] ;
}
}
}
2014-01-03 03:52:37 -04:00
for ( uint8_t i = 0 ; i < = 20 ; i + + )
2013-12-29 05:48:15 -04:00
{
2014-01-03 03:52:37 -04:00
for ( uint8_t j = 0 ; j < = 20 ; j + + )
2013-12-29 05:48:15 -04:00
{
P [ i ] [ j ] = P [ i ] [ j ] - KHP [ i ] [ j ] ;
}
}
}
}
2014-01-03 15:59:47 -04:00
// force the covariance matrix to me symmetrical and limit the variances to prevent
// ill-condiioning.
ForceSymmetry ( ) ;
ConstrainVariances ( ) ;
2013-12-30 06:41:28 -04:00
perf_end ( _perf_FuseAirspeed ) ;
2013-12-25 18:58:02 -04:00
}
2014-01-03 03:52:37 -04:00
void NavEKF : : zeroRows ( Matrix21 & covMat , uint8_t first , uint8_t last )
2013-12-25 18:58:02 -04:00
{
2013-12-29 05:48:15 -04:00
uint8_t row ;
for ( row = first ; row < = last ; row + + )
{
2014-01-03 03:52:37 -04:00
memset ( & covMat [ row ] [ 0 ] , 0 , sizeof ( covMat [ 0 ] [ 0 ] ) * 21 ) ;
2013-12-29 05:48:15 -04:00
}
2013-12-25 18:58:02 -04:00
}
2014-01-03 03:52:37 -04:00
void NavEKF : : zeroCols ( Matrix21 & covMat , uint8_t first , uint8_t last )
2013-12-25 18:58:02 -04:00
{
2013-12-29 05:48:15 -04:00
uint8_t row ;
2014-01-03 03:52:37 -04:00
for ( row = 0 ; row < = 20 ; row + + )
2013-12-29 05:48:15 -04:00
{
2014-01-03 00:37:19 -04:00
memset ( & covMat [ row ] [ first ] , 0 , sizeof ( covMat [ 0 ] [ 0 ] ) * ( 1 + last - first ) ) ;
2013-12-29 05:48:15 -04:00
}
2013-12-25 18:58:02 -04:00
}
// Store states in a history array along with time stamp
2013-12-29 03:37:55 -04:00
void NavEKF : : StoreStates ( )
2013-12-25 18:58:02 -04:00
{
2013-12-29 05:48:15 -04:00
if ( storeIndex > 49 ) storeIndex = 0 ;
2014-01-03 03:52:37 -04:00
for ( uint8_t i = 0 ; i < = 20 ; i + + ) storedStates [ i ] [ storeIndex ] = states [ i ] ;
2013-12-29 05:48:15 -04:00
statetimeStamp [ storeIndex ] = hal . scheduler - > millis ( ) ;
storeIndex = storeIndex + 1 ;
2013-12-25 18:58:02 -04:00
}
// Output the state vector stored at the time that best matches that specified by msec
2014-01-03 03:52:37 -04:00
void NavEKF : : RecallStates ( Vector21 & statesForFusion , uint32_t msec )
2013-12-25 18:58:02 -04:00
{
2013-12-29 05:48:15 -04:00
uint32_t timeDelta ;
uint32_t bestTimeDelta = 200 ;
uint8_t bestStoreIndex = 0 ;
for ( uint8_t i = 0 ; i < = 49 ; i + + )
{
timeDelta = msec - statetimeStamp [ i ] ;
if ( timeDelta < bestTimeDelta )
{
bestStoreIndex = i ;
bestTimeDelta = timeDelta ;
}
}
if ( bestTimeDelta < 200 ) // only output stored state if < 200 msec retrieval error
{
2014-01-03 03:52:37 -04:00
for ( uint8_t i = 0 ; i < = 20 ; i + + ) {
2013-12-29 21:27:06 -04:00
statesForFusion [ i ] = storedStates [ i ] [ bestStoreIndex ] ;
}
2013-12-29 05:48:15 -04:00
}
else // otherwise output current state
{
2014-01-03 03:52:37 -04:00
for ( uint8_t i = 0 ; i < = 20 ; i + + ) {
2013-12-29 21:27:06 -04:00
statesForFusion [ i ] = states [ i ] ;
}
2013-12-29 05:48:15 -04:00
}
2013-12-25 18:58:02 -04:00
}
2014-01-01 21:15:22 -04:00
void NavEKF : : quat2Tbn ( Matrix3f & Tbn , const Quaternion & quat ) const
2013-12-25 18:58:02 -04:00
{
2013-12-29 05:48:15 -04:00
// Calculate the body to nav cosine matrix
2013-12-29 23:43:29 -04:00
quat . rotation_matrix ( Tbn ) ;
2013-12-25 18:58:02 -04:00
}
2014-01-01 21:15:22 -04:00
void NavEKF : : getEulerAngles ( Vector3f & euler ) const
2013-12-29 08:20:53 -04:00
{
2013-12-29 22:25:02 -04:00
Quaternion q ( states [ 0 ] , states [ 1 ] , states [ 2 ] , states [ 3 ] ) ;
2014-01-02 07:05:09 -04:00
q . to_euler ( & euler . x , & euler . y , & euler . z ) ;
2013-12-29 08:20:53 -04:00
}
2014-01-01 21:15:22 -04:00
void NavEKF : : getVelNED ( Vector3f & vel ) const
2013-12-30 04:58:24 -04:00
{
vel . x = states [ 4 ] ;
vel . y = states [ 5 ] ;
vel . z = states [ 6 ] ;
}
2014-01-01 21:15:22 -04:00
bool NavEKF : : getPosNED ( Vector3f & pos ) const
2013-12-31 00:27:35 -04:00
{
pos . x = states [ 7 ] ;
pos . y = states [ 8 ] ;
pos . z = states [ 9 ] ;
return true ;
}
2014-01-01 21:15:22 -04:00
void NavEKF : : getGyroBias ( Vector3f & gyroBias ) const
2013-12-31 17:54:56 -04:00
{
2014-01-03 22:04:00 -04:00
gyroBias . x = states [ 10 ] * 60.0f * RAD_TO_DEG / dtIMU ;
gyroBias . y = states [ 11 ] * 60.0f * RAD_TO_DEG / dtIMU ;
gyroBias . z = states [ 12 ] * 60.0f * RAD_TO_DEG / dtIMU ;
2013-12-31 17:54:56 -04:00
}
2014-01-01 21:15:22 -04:00
void NavEKF : : getAccelBias ( Vector3f & accelBias ) const
2013-12-31 17:54:56 -04:00
{
2014-01-03 03:52:37 -04:00
accelBias . x = 0.0f ;
accelBias . y = 0.0f ;
accelBias . z = 0.0f ;
2013-12-31 17:54:56 -04:00
}
2014-01-01 21:15:22 -04:00
void NavEKF : : getWind ( Vector3f & wind ) const
2014-01-30 18:11:54 -04:00
{
2014-01-03 03:52:37 -04:00
wind . x = states [ 13 ] ;
wind . y = states [ 14 ] ;
2014-01-30 18:11:54 -04:00
wind . z = 0.0f ; // curently don't estimate this
}
2014-01-01 21:15:22 -04:00
void NavEKF : : getMagNED ( Vector3f & magNED ) const
2013-12-31 17:54:56 -04:00
{
2014-01-03 03:52:37 -04:00
magNED . x = states [ 15 ] * 1000.0f ;
magNED . y = states [ 16 ] * 1000.0f ;
magNED . z = states [ 17 ] * 1000.0f ;
2013-12-31 17:54:56 -04:00
}
2014-01-01 21:15:22 -04:00
void NavEKF : : getMagXYZ ( Vector3f & magXYZ ) const
2013-12-31 17:54:56 -04:00
{
2014-01-03 03:52:37 -04:00
magXYZ . x = states [ 18 ] * 1000.0f ;
magXYZ . y = states [ 19 ] * 1000.0f ;
magXYZ . z = states [ 20 ] * 1000.0f ;
2013-12-31 17:54:56 -04:00
}
2014-01-01 21:15:22 -04:00
bool NavEKF : : getLLH ( struct Location & loc ) const
2013-12-25 18:58:02 -04:00
{
2014-01-02 07:05:09 -04:00
loc . lat = _ahrs - > get_home ( ) . lat ;
loc . lng = _ahrs - > get_home ( ) . lng ;
loc . alt = _ahrs - > get_home ( ) . alt - states [ 9 ] * 100 ;
location_offset ( loc , states [ 7 ] , states [ 8 ] ) ;
2013-12-30 01:19:50 -04:00
return true ;
2013-12-25 18:58:02 -04:00
}
2013-12-29 03:37:55 -04:00
void NavEKF : : OnGroundCheck ( )
2013-12-25 18:58:02 -04:00
{
2014-01-03 06:40:45 -04:00
const AP_Airspeed * airspeed = _ahrs - > get_airspeed ( ) ;
uint8_t lowAirSpd = ( ! airspeed | | ! airspeed - > use ( ) | | airspeed - > get_airspeed ( ) * airspeed - > get_EAS2TAS ( ) < 8.0f ) ;
2014-01-03 06:31:36 -04:00
uint8_t lowGndSpd = ( uint8_t ) ( ( sq ( velNED [ 0 ] ) + sq ( velNED [ 1 ] ) + sq ( velNED [ 2 ] ) ) < 4.0f ) ;
uint8_t lowHgt = ( uint8_t ) ( fabsf ( hgtMea < 15.0f ) ) ;
2014-01-01 02:14:10 -04:00
// Go with a majority vote from three criteria
onGround = ( ( lowAirSpd + lowGndSpd + lowHgt ) > = 2 ) ;
2013-12-25 18:58:02 -04:00
}
2013-12-29 03:37:55 -04:00
void NavEKF : : CovarianceInit ( )
2013-12-25 18:58:02 -04:00
{
2014-01-03 16:57:52 -04:00
// zero the matrix
for ( uint8_t i = 1 ; i < = 20 ; i + + )
{
for ( uint8_t j = 0 ; j < = 20 ; j + + )
{
P [ i ] [ j ] = 0.0f ;
}
}
// Set the diagonals
2013-12-29 05:48:15 -04:00
P [ 1 ] [ 1 ] = 0.25f * sq ( 1.0f * DEG_TO_RAD ) ;
P [ 2 ] [ 2 ] = 0.25f * sq ( 1.0f * DEG_TO_RAD ) ;
P [ 3 ] [ 3 ] = 0.25f * sq ( 10.0f * DEG_TO_RAD ) ;
P [ 4 ] [ 4 ] = sq ( 0.7f ) ;
P [ 5 ] [ 5 ] = P [ 4 ] [ 4 ] ;
P [ 6 ] [ 6 ] = sq ( 0.7f ) ;
P [ 7 ] [ 7 ] = sq ( 15.0f ) ;
P [ 8 ] [ 8 ] = P [ 7 ] [ 7 ] ;
P [ 9 ] [ 9 ] = sq ( 5.0f ) ;
2014-01-03 22:04:00 -04:00
P [ 10 ] [ 10 ] = sq ( radians ( 0.1f * dtIMU ) ) ;
2013-12-29 05:48:15 -04:00
P [ 11 ] [ 11 ] = P [ 10 ] [ 10 ] ;
P [ 12 ] [ 12 ] = P [ 10 ] [ 10 ] ;
2014-01-03 03:52:37 -04:00
P [ 13 ] [ 13 ] = sq ( 8.0f ) ;
P [ 14 ] [ 4 ] = P [ 13 ] [ 13 ] ;
P [ 15 ] [ 15 ] = sq ( 0.02f ) ;
P [ 16 ] [ 16 ] = P [ 15 ] [ 15 ] ;
P [ 17 ] [ 17 ] = P [ 15 ] [ 15 ] ;
2013-12-29 05:48:15 -04:00
P [ 18 ] [ 18 ] = sq ( 0.02f ) ;
P [ 19 ] [ 19 ] = P [ 18 ] [ 18 ] ;
P [ 20 ] [ 20 ] = P [ 18 ] [ 18 ] ;
2013-12-25 18:58:02 -04:00
}
2014-01-03 15:59:47 -04:00
void NavEKF : : ForceSymmetry ( )
2014-01-02 22:10:38 -04:00
{
// Force symmetry on the covariance matrix to prevent ill-conditioning
// of the matrix which would cause the filter to blow-up
2014-01-03 03:52:37 -04:00
for ( uint8_t i = 1 ; i < = 20 ; i + + )
2014-01-02 22:10:38 -04:00
{
for ( uint8_t j = 0 ; j < = i - 1 ; j + + )
{
2014-01-03 15:59:47 -04:00
float temp = 0.5f * ( P [ i ] [ j ] + P [ j ] [ i ] ) ;
2014-01-02 22:10:38 -04:00
P [ i ] [ j ] = temp ;
P [ j ] [ i ] = temp ;
}
}
2014-01-03 15:59:47 -04:00
}
void NavEKF : : ConstrainVariances ( )
{
2014-01-02 22:10:38 -04:00
// Constrain variances to be within set limits
2014-01-03 03:52:37 -04:00
for ( uint8_t i = 0 ; i < = 3 ; i + + ) constrain_float ( P [ 1 ] [ 1 ] , 0.0f , 0.1f ) ;
2014-01-03 15:59:47 -04:00
for ( uint8_t i = 4 ; i < = 6 ; i + + ) constrain_float ( P [ 1 ] [ 1 ] , 0.0f , 1.0e3 f ) ;
for ( uint8_t i = 7 ; i < = 9 ; i + + ) constrain_float ( P [ 1 ] [ 1 ] , 0.0f , 1.0e5 f ) ;
2014-01-03 22:04:00 -04:00
for ( uint8_t i = 10 ; i < = 12 ; i + + ) constrain_float ( P [ 1 ] [ 1 ] , 0.0f , sq ( 0.0175 * dtIMU ) ) ;
2014-01-03 15:59:47 -04:00
for ( uint8_t i = 13 ; i < = 14 ; i + + ) constrain_float ( P [ 1 ] [ 1 ] , 0.0f , 1.0e3 f ) ;
2014-01-03 03:52:37 -04:00
for ( uint8_t i = 15 ; i < = 20 ; i + + ) constrain_float ( P [ 1 ] [ 1 ] , 0.0f , 1.0f ) ;
2014-01-02 22:10:38 -04:00
}
2013-12-29 03:37:55 -04:00
void NavEKF : : readIMUData ( )
2013-12-25 18:58:02 -04:00
{
2013-12-29 05:48:15 -04:00
Vector3f angRate ; // angular rate vector in XYZ body axes measured by the IMU (rad/s)
Vector3f accel ; // acceleration vector in XYZ body axes measured by the IMU (m/s^2)
2014-01-02 20:47:09 -04:00
IMUmsec = hal . scheduler - > millis ( ) ;
dtIMU = _ahrs - > get_ins ( ) . get_delta_time ( ) ;
2014-01-01 21:15:22 -04:00
angRate = _ahrs - > get_ins ( ) . get_gyro ( ) ;
accel = _ahrs - > get_ins ( ) . get_accel ( ) ;
2013-12-29 05:48:15 -04:00
dAngIMU = ( angRate + lastAngRate ) * dtIMU * 0.5f ;
lastAngRate = angRate ;
dVelIMU = ( accel + lastAccel ) * dtIMU * 0.5f ;
lastAccel = accel ;
2013-12-25 18:58:02 -04:00
}
2013-12-29 03:37:55 -04:00
void NavEKF : : readGpsData ( )
2013-12-29 05:48:15 -04:00
{
2014-01-02 20:47:09 -04:00
if ( ( _ahrs - > get_gps ( ) - > last_message_time_ms ( ) ! = lastFixTime_ms ) & &
2014-01-01 21:15:22 -04:00
( _ahrs - > get_gps ( ) - > status ( ) > = GPS : : GPS_OK_FIX_3D ) )
2013-12-29 05:48:15 -04:00
{
2014-01-02 20:47:09 -04:00
lastFixTime_ms = _ahrs - > get_gps ( ) - > last_message_time_ms ( ) ;
2013-12-29 03:37:55 -04:00
newDataGps = true ;
RecallStates ( statesAtVelTime , ( IMUmsec - msecVelDelay ) ) ;
RecallStates ( statesAtPosTime , ( IMUmsec - msecPosDelay ) ) ;
2014-01-01 21:15:22 -04:00
velNED [ 0 ] = _ahrs - > get_gps ( ) - > velocity_north ( ) ; // (rad)
velNED [ 1 ] = _ahrs - > get_gps ( ) - > velocity_east ( ) ; // (m/s)
velNED [ 2 ] = _ahrs - > get_gps ( ) - > velocity_down ( ) ; // (m/s)
2014-01-05 01:37:24 -04:00
//::printf("GPSVEL=(%.2f,%.2f,%.2f)\n", velNED[0], velNED[1], velNED[2]);
2014-01-02 07:05:09 -04:00
2013-12-29 03:37:55 -04:00
// Convert GPS measurements to Pos NE
2014-01-02 07:05:09 -04:00
struct Location gpsloc ;
gpsloc . lat = _ahrs - > get_gps ( ) - > latitude ;
gpsloc . lng = _ahrs - > get_gps ( ) - > longitude ;
Vector2f posdiff = location_diff ( _ahrs - > get_home ( ) , gpsloc ) ;
posNE [ 0 ] = posdiff . x ;
posNE [ 1 ] = posdiff . y ;
2013-12-29 05:48:15 -04:00
}
2013-12-25 18:58:02 -04:00
}
2013-12-29 03:37:55 -04:00
void NavEKF : : readHgtData ( )
2013-12-25 18:58:02 -04:00
{
2013-12-29 05:48:15 -04:00
// ToDo do we check for new height data or grab a height measurement?
// Best to do this at the same time as GPS measurement fusion for efficiency
2014-01-02 07:05:09 -04:00
hgtMea = _baro . get_altitude ( ) ;
2014-01-05 01:37:24 -04:00
#if 0
Vector3f pos ;
getPosNED ( pos ) ;
//::printf("BARO.Alt=%.2f REL.z=%.2f\n", hgtMea, -pos.z);
# endif
2013-12-29 05:48:15 -04:00
// recall states from compass measurement time
2013-12-29 23:43:29 -04:00
RecallStates ( statesAtHgtTime , ( IMUmsec - msecHgtDelay ) ) ;
2013-12-25 18:58:02 -04:00
}
2013-12-29 03:37:55 -04:00
void NavEKF : : readMagData ( )
2013-12-25 18:58:02 -04:00
{
2013-12-29 05:48:15 -04:00
// scale compass data to improve numerical conditioning
2014-01-01 21:15:22 -04:00
if ( _ahrs - > get_compass ( ) - > last_update ! = lastMagUpdate ) {
lastMagUpdate = _ahrs - > get_compass ( ) - > last_update ;
2013-12-30 06:27:50 -04:00
2014-01-02 01:53:33 -04:00
magBias = - _ahrs - > get_compass ( ) - > get_offsets ( ) * 0.001f ;
magData = _ahrs - > get_compass ( ) - > get_field ( ) * 0.001f + magBias ;
2013-12-30 06:27:50 -04:00
2013-12-29 21:12:09 -04:00
// Recall states from compass measurement time
RecallStates ( statesAtMagMeasTime , ( IMUmsec - msecMagDelay ) ) ;
newDataMag = true ;
2013-12-30 06:27:50 -04:00
} else {
2013-12-29 21:12:09 -04:00
newDataMag = false ;
}
2013-12-25 18:58:02 -04:00
}
2013-12-29 03:37:55 -04:00
void NavEKF : : readAirSpdData ( )
2013-12-25 18:58:02 -04:00
{
2014-01-01 21:15:22 -04:00
const AP_Airspeed * aspeed = _ahrs - > get_airspeed ( ) ;
2014-01-03 03:52:37 -04:00
if ( aspeed & &
2014-01-03 06:40:45 -04:00
aspeed - > use ( ) & &
aspeed - > last_update_ms ( ) ! = lastAirspeedUpdate ) {
VtasMeas = aspeed - > get_airspeed ( ) * aspeed - > get_EAS2TAS ( ) ;
2013-12-30 06:27:50 -04:00
lastAirspeedUpdate = aspeed - > last_update_ms ( ) ;
newDataTas = true ;
RecallStates ( statesAtVtasMeasTime , ( IMUmsec - msecTasDelay ) ) ;
} else {
newDataTas = false ;
2013-12-29 03:37:55 -04:00
}
2013-12-25 18:58:02 -04:00
}
2014-01-02 07:05:09 -04:00
void NavEKF : : calcEarthRateNED ( Vector3f & omega , int32_t latitude ) const
2013-12-25 18:58:02 -04:00
{
2014-01-02 07:05:09 -04:00
float lat_rad = radians ( latitude * 1.0e-7 f ) ;
omega . x = earthRate * cosf ( lat_rad ) ;
2013-12-29 05:48:15 -04:00
omega . y = 0 ;
2014-01-02 07:05:09 -04:00
omega . z = - earthRate * sinf ( lat_rad ) ;
2013-12-25 18:58:02 -04:00
}
2013-12-30 19:24:21 -04:00
2014-01-01 22:05:49 -04:00
void NavEKF : : getRotationBodyToNED ( Matrix3f & mat ) const
{
Quaternion q ( states [ 0 ] , states [ 1 ] , states [ 2 ] , states [ 3 ] ) ;
q . rotation_matrix ( mat ) ;
}
2013-12-30 19:24:21 -04:00
# endif // HAL_CPU_CLASS