2015-10-05 23:30:07 -03:00
# include <AP_HAL/AP_HAL.h>
# include "AP_NavEKF2.h"
# include "AP_NavEKF2_core.h"
2020-11-05 19:30:16 -04:00
# include <AP_DAL/AP_DAL.h>
2015-10-05 23:30:07 -03:00
extern const AP_HAL : : HAL & hal ;
/********************************************************
* RESET FUNCTIONS *
* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */
// Reset velocity states to last GPS measurement if available or to zero if in constant position mode or if PV aiding is not absolute
// Do not reset vertical velocity using GPS as there is baro alt available to constrain drift
void NavEKF2_core : : ResetVelocity ( void )
{
2015-10-29 02:06:24 -03:00
// Store the position before the reset so that we can record the reset delta
velResetNE . x = stateStruct . velocity . x ;
velResetNE . y = stateStruct . velocity . y ;
2016-10-25 17:54:29 -03:00
// reset the corresponding covariances
zeroRows ( P , 3 , 4 ) ;
zeroCols ( P , 3 , 4 ) ;
2020-01-26 02:06:58 -04:00
2015-10-05 23:30:07 -03:00
if ( PV_AidingMode ! = AID_ABSOLUTE ) {
stateStruct . velocity . zero ( ) ;
2016-10-25 17:54:29 -03:00
// set the variances using the measurement noise parameter
P [ 4 ] [ 4 ] = P [ 3 ] [ 3 ] = sq ( frontend - > _gpsHorizVelNoise ) ;
2016-07-15 00:09:48 -03:00
} else {
2016-10-25 17:54:29 -03:00
// reset horizontal velocity states to the GPS velocity if available
if ( imuSampleTime_ms - lastTimeGpsReceived_ms < 250 ) {
2020-04-16 03:25:00 -03:00
// correct for antenna position
gps_elements gps_corrected = gpsDataNew ;
CorrectGPSForAntennaOffset ( gps_corrected ) ;
2020-01-26 02:06:58 -04:00
stateStruct . velocity . x = gps_corrected . vel . x ;
stateStruct . velocity . y = gps_corrected . vel . y ;
2016-10-25 17:54:29 -03:00
// set the variances using the reported GPS speed accuracy
P [ 4 ] [ 4 ] = P [ 3 ] [ 3 ] = sq ( MAX ( frontend - > _gpsHorizVelNoise , gpsSpdAccuracy ) ) ;
2018-10-03 23:43:13 -03:00
} else if ( imuSampleTime_ms - extNavVelMeasTime_ms < 250 ) {
// use external nav data as the 2nd preference
stateStruct . velocity = extNavVelDelayed . vel ;
P [ 5 ] [ 5 ] = P [ 4 ] [ 4 ] = P [ 3 ] [ 3 ] = sq ( extNavVelDelayed . err ) ;
2016-10-25 17:54:29 -03:00
} else {
stateStruct . velocity . x = 0.0f ;
stateStruct . velocity . y = 0.0f ;
// set the variances using the likely speed range
P [ 4 ] [ 4 ] = P [ 3 ] [ 3 ] = sq ( 25.0f ) ;
}
2020-11-21 23:48:23 -04:00
// clear the timeout flags and counters
velTimeout = false ;
lastVelPassTime_ms = imuSampleTime_ms ;
2015-10-05 23:30:07 -03:00
}
2015-11-17 19:15:34 -04:00
for ( uint8_t i = 0 ; i < imu_buffer_length ; i + + ) {
2015-10-05 23:30:07 -03:00
storedOutput [ i ] . velocity . x = stateStruct . velocity . x ;
storedOutput [ i ] . velocity . y = stateStruct . velocity . y ;
}
outputDataNew . velocity . x = stateStruct . velocity . x ;
outputDataNew . velocity . y = stateStruct . velocity . y ;
outputDataDelayed . velocity . x = stateStruct . velocity . x ;
outputDataDelayed . velocity . y = stateStruct . velocity . y ;
2015-10-29 02:06:24 -03:00
// Calculate the position jump due to the reset
velResetNE . x = stateStruct . velocity . x - velResetNE . x ;
velResetNE . y = stateStruct . velocity . y - velResetNE . y ;
// store the time of the reset
lastVelReset_ms = imuSampleTime_ms ;
2016-05-20 22:27:58 -03:00
2015-10-05 23:30:07 -03:00
}
// resets position states to last GPS measurement or to zero if in constant position mode
void NavEKF2_core : : ResetPosition ( void )
{
2015-10-29 02:06:24 -03:00
// Store the position before the reset so that we can record the reset delta
posResetNE . x = stateStruct . position . x ;
posResetNE . y = stateStruct . position . y ;
2016-10-25 17:54:29 -03:00
// reset the corresponding covariances
zeroRows ( P , 6 , 7 ) ;
zeroCols ( P , 6 , 7 ) ;
2020-01-26 02:06:58 -04:00
2015-10-05 23:30:07 -03:00
if ( PV_AidingMode ! = AID_ABSOLUTE ) {
// reset all position state history to the last known position
stateStruct . position . x = lastKnownPositionNE . x ;
stateStruct . position . y = lastKnownPositionNE . y ;
2016-10-25 17:54:29 -03:00
// set the variances using the position measurement noise parameter
P [ 6 ] [ 6 ] = P [ 7 ] [ 7 ] = sq ( frontend - > _gpsHorizPosNoise ) ;
2016-07-15 00:09:48 -03:00
} else {
2016-10-25 17:54:29 -03:00
// Use GPS data as first preference if fresh data is available
if ( imuSampleTime_ms - lastTimeGpsReceived_ms < 250 ) {
2020-04-16 03:25:00 -03:00
// correct for antenna position
gps_elements gps_corrected = gpsDataNew ;
CorrectGPSForAntennaOffset ( gps_corrected ) ;
2017-01-28 07:08:46 -04:00
// record the ID of the GPS for the data we are using for the reset
2020-01-26 02:06:58 -04:00
last_gps_idx = gps_corrected . sensor_idx ;
2016-10-25 17:54:29 -03:00
// write to state vector and compensate for offset between last GPS measurement and the EKF time horizon
2020-01-26 02:06:58 -04:00
stateStruct . position . x = gps_corrected . pos . x + 0.001f * gps_corrected . vel . x * ( float ( imuDataDelayed . time_ms ) - float ( gps_corrected . time_ms ) ) ;
stateStruct . position . y = gps_corrected . pos . y + 0.001f * gps_corrected . vel . y * ( float ( imuDataDelayed . time_ms ) - float ( gps_corrected . time_ms ) ) ;
2016-10-25 17:54:29 -03:00
// set the variances using the position measurement noise parameter
P [ 6 ] [ 6 ] = P [ 7 ] [ 7 ] = sq ( MAX ( gpsPosAccuracy , frontend - > _gpsHorizPosNoise ) ) ;
// clear the timeout flags and counters
posTimeout = false ;
lastPosPassTime_ms = imuSampleTime_ms ;
} else if ( imuSampleTime_ms - rngBcnLast3DmeasTime_ms < 250 ) {
// use the range beacon data as a second preference
stateStruct . position . x = receiverPos . x ;
stateStruct . position . y = receiverPos . y ;
// set the variances from the beacon alignment filter
P [ 6 ] [ 6 ] = receiverPosCov [ 0 ] [ 0 ] ;
P [ 7 ] [ 7 ] = receiverPosCov [ 1 ] [ 1 ] ;
// clear the timeout flags and counters
rngBcnTimeout = false ;
lastRngBcnPassTime_ms = imuSampleTime_ms ;
2018-03-07 00:42:31 -04:00
} else if ( imuSampleTime_ms - extNavDataDelayed . time_ms < 250 ) {
2020-04-12 22:17:50 -03:00
// use external nav data as the third preference
2020-04-13 00:19:46 -03:00
ext_nav_elements extNavCorrected = extNavDataDelayed ;
CorrectExtNavForSensorOffset ( extNavCorrected . pos ) ;
stateStruct . position . x = extNavCorrected . pos . x ;
stateStruct . position . y = extNavCorrected . pos . y ;
2020-04-12 22:17:50 -03:00
// set the variances from the external nav filter
2020-04-13 00:19:46 -03:00
P [ 7 ] [ 7 ] = P [ 6 ] [ 6 ] = sq ( extNavCorrected . posErr ) ;
2016-10-25 17:54:29 -03:00
}
2015-10-05 23:30:07 -03:00
}
2015-11-17 19:15:34 -04:00
for ( uint8_t i = 0 ; i < imu_buffer_length ; i + + ) {
2015-10-05 23:30:07 -03:00
storedOutput [ i ] . position . x = stateStruct . position . x ;
storedOutput [ i ] . position . y = stateStruct . position . y ;
}
outputDataNew . position . x = stateStruct . position . x ;
outputDataNew . position . y = stateStruct . position . y ;
outputDataDelayed . position . x = stateStruct . position . x ;
outputDataDelayed . position . y = stateStruct . position . y ;
2015-10-29 02:06:24 -03:00
// Calculate the position jump due to the reset
posResetNE . x = stateStruct . position . x - posResetNE . x ;
posResetNE . y = stateStruct . position . y - posResetNE . y ;
// store the time of the reset
lastPosReset_ms = imuSampleTime_ms ;
2016-05-20 22:27:58 -03:00
2015-10-05 23:30:07 -03:00
}
2020-04-17 23:10:09 -03:00
// reset the stateStruct's NE position to the specified position
// posResetNE is updated to hold the change in position
// storedOutput, outputDataNew and outputDataDelayed are updated with the change in position
// lastPosReset_ms is updated with the time of the reset
2021-05-04 08:12:23 -03:00
void NavEKF2_core : : ResetPositionNE ( ftype posN , ftype posE )
2020-04-17 23:10:09 -03:00
{
// Store the position before the reset so that we can record the reset delta
2021-05-04 08:12:23 -03:00
const Vector3F posOrig = stateStruct . position ;
2020-04-17 23:10:09 -03:00
// Set the position states to the new position
stateStruct . position . x = posN ;
stateStruct . position . y = posE ;
// Calculate the position offset due to the reset
posResetNE . x = stateStruct . position . x - posOrig . x ;
posResetNE . y = stateStruct . position . y - posOrig . y ;
// Add the offset to the output observer states
for ( uint8_t i = 0 ; i < imu_buffer_length ; i + + ) {
storedOutput [ i ] . position . x + = posResetNE . x ;
storedOutput [ i ] . position . y + = posResetNE . y ;
}
outputDataNew . position . x + = posResetNE . x ;
outputDataNew . position . y + = posResetNE . y ;
outputDataDelayed . position . x + = posResetNE . x ;
outputDataDelayed . position . y + = posResetNE . y ;
// store the time of the reset
lastPosReset_ms = imuSampleTime_ms ;
}
2015-10-05 23:30:07 -03:00
// reset the vertical position state using the last height measurement
void NavEKF2_core : : ResetHeight ( void )
{
2016-11-22 06:29:30 -04:00
// Store the position before the reset so that we can record the reset delta
posResetD = stateStruct . position . z ;
2015-10-05 23:30:07 -03:00
// write to the state vector
2015-11-12 04:07:52 -04:00
stateStruct . position . z = - hgtMea ;
2016-07-12 05:56:58 -03:00
outputDataNew . position . z = stateStruct . position . z ;
outputDataDelayed . position . z = stateStruct . position . z ;
// reset the terrain state height
if ( onGround ) {
// assume vehicle is sitting on the ground
terrainState = stateStruct . position . z + rngOnGnd ;
} else {
// can make no assumption other than vehicle is not below ground level
terrainState = MAX ( stateStruct . position . z + rngOnGnd , terrainState ) ;
}
2015-11-17 19:15:34 -04:00
for ( uint8_t i = 0 ; i < imu_buffer_length ; i + + ) {
2015-10-05 23:30:07 -03:00
storedOutput [ i ] . position . z = stateStruct . position . z ;
}
2019-09-22 02:09:58 -03:00
vertCompFiltState . pos = stateStruct . position . z ;
2015-11-12 23:54:02 -04:00
2016-11-22 06:29:30 -04:00
// Calculate the position jump due to the reset
posResetD = stateStruct . position . z - posResetD ;
// store the time of the reset
lastPosResetD_ms = imuSampleTime_ms ;
2016-10-25 17:54:29 -03:00
// clear the timeout flags and counters
hgtTimeout = false ;
lastHgtPassTime_ms = imuSampleTime_ms ;
2016-05-20 22:27:58 -03:00
// reset the corresponding covariances
zeroRows ( P , 8 , 8 ) ;
zeroCols ( P , 8 , 8 ) ;
// set the variances to the measurement variance
P [ 8 ] [ 8 ] = posDownObsNoise ;
2015-11-12 23:54:02 -04:00
// Reset the vertical velocity state using GPS vertical velocity if we are airborne
// Check that GPS vertical velocity data is available and can be used
2020-11-15 05:38:05 -04:00
if ( inFlight & & ! gpsNotAvailable & & frontend - > _fusionModeGPS = = 0 & &
2020-11-20 15:38:49 -04:00
dal . gps ( ) . have_vertical_velocity ( ) ) {
2015-11-12 23:54:02 -04:00
stateStruct . velocity . z = gpsDataNew . vel . z ;
2018-10-03 23:43:13 -03:00
} else if ( inFlight & & useExtNavVel ) {
stateStruct . velocity . z = extNavVelNew . vel . z ;
2015-11-12 23:54:02 -04:00
} else if ( onGround ) {
stateStruct . velocity . z = 0.0f ;
}
2015-11-17 20:33:51 -04:00
for ( uint8_t i = 0 ; i < imu_buffer_length ; i + + ) {
2015-11-12 23:54:02 -04:00
storedOutput [ i ] . velocity . z = stateStruct . velocity . z ;
}
outputDataNew . velocity . z = stateStruct . velocity . z ;
outputDataDelayed . velocity . z = stateStruct . velocity . z ;
2019-09-22 02:09:58 -03:00
vertCompFiltState . vel = outputDataNew . velocity . z ;
2016-05-20 22:27:58 -03:00
// reset the corresponding covariances
zeroRows ( P , 5 , 5 ) ;
zeroCols ( P , 5 , 5 ) ;
// set the variances to the measurement variance
2018-10-03 23:43:13 -03:00
if ( useExtNavVel ) {
P [ 5 ] [ 5 ] = sq ( extNavVelNew . err ) ;
} else {
P [ 5 ] [ 5 ] = sq ( frontend - > _gpsVertVelNoise ) ;
}
2015-10-05 23:30:07 -03:00
}
2020-04-17 23:10:09 -03:00
// reset the stateStruct's D position
// posResetD is updated to hold the change in position
// storedOutput, outputDataNew and outputDataDelayed are updated with the change in position
// lastPosResetD_ms is updated with the time of the reset
2021-05-04 08:12:23 -03:00
void NavEKF2_core : : ResetPositionD ( ftype posD )
2020-04-17 23:10:09 -03:00
{
// Store the position before the reset so that we can record the reset delta
2021-05-04 08:12:23 -03:00
const ftype posDOrig = stateStruct . position . z ;
2020-04-17 23:10:09 -03:00
// write to the state vector
stateStruct . position . z = posD ;
// Calculate the position jump due to the reset
posResetD = stateStruct . position . z - posDOrig ;
// Add the offset to the output observer states
outputDataNew . position . z + = posResetD ;
vertCompFiltState . pos = outputDataNew . position . z ;
outputDataDelayed . position . z + = posResetD ;
for ( uint8_t i = 0 ; i < imu_buffer_length ; i + + ) {
storedOutput [ i ] . position . z + = posResetD ;
}
// store the time of the reset
lastPosResetD_ms = imuSampleTime_ms ;
}
2016-07-12 05:56:58 -03:00
// Zero the EKF height datum
2015-10-05 23:30:07 -03:00
// Return true if the height datum reset has been performed
bool NavEKF2_core : : resetHeightDatum ( void )
{
2019-07-02 23:36:07 -03:00
if ( activeHgtSource = = HGT_SOURCE_RNG | | ! onGround ) {
// only allow resets when on the ground.
// If using using rangefinder for height then never perform a
// reset of the height datum
2015-10-05 23:30:07 -03:00
return false ;
}
// record the old height estimate
2021-05-04 08:12:23 -03:00
ftype oldHgt = - stateStruct . position . z ;
2015-10-05 23:30:07 -03:00
// reset the barometer so that it reads zero at the current height
2020-11-07 02:24:13 -04:00
dal . baro ( ) . update_calibration ( ) ;
2015-10-05 23:30:07 -03:00
// reset the height state
stateStruct . position . z = 0.0f ;
2017-01-06 12:15:35 -04:00
// adjust the height of the EKF origin so that the origin plus baro height before and after the reset is the same
2019-07-01 19:49:48 -03:00
2019-07-02 23:36:07 -03:00
if ( validOrigin ) {
2019-07-01 19:49:48 -03:00
if ( ! gpsGoodToAlign ) {
// if we don't have GPS lock then we shouldn't be doing a
// resetHeightDatum, but if we do then the best option is
// to maintain the old error
2019-07-09 03:27:22 -03:00
EKF_origin . alt + = ( int32_t ) ( 100.0f * oldHgt ) ;
2019-07-01 19:49:48 -03:00
} else {
2019-07-01 16:55:13 -03:00
// if we have a good GPS lock then reset to the GPS
// altitude. This ensures the reported AMSL alt from
// getLLH() is equal to GPS altitude, while also ensuring
// that the relative alt is zero
2020-11-07 02:24:13 -04:00
EKF_origin . alt = dal . gps ( ) . location ( ) . alt ;
2019-07-01 16:55:13 -03:00
}
2019-07-09 03:27:22 -03:00
ekfGpsRefHgt = ( double ) 0.01 * ( double ) EKF_origin . alt ;
2015-10-05 23:30:07 -03:00
}
2019-07-01 19:49:48 -03:00
2019-07-02 03:17:46 -03:00
// set the terrain state to zero (on ground). The adjustment for
// frame height will get added in the later constraints
terrainState = 0 ;
2015-10-05 23:30:07 -03:00
return true ;
}
2020-01-26 02:06:58 -04:00
/*
correct GPS data for position offset of antenna phase centre relative to the IMU
*/
2020-04-16 03:25:00 -03:00
void NavEKF2_core : : CorrectGPSForAntennaOffset ( gps_elements & gps_data ) const
2020-01-26 02:06:58 -04:00
{
2021-05-04 08:12:23 -03:00
const Vector3F posOffsetBody = dal . gps ( ) . get_antenna_offset ( gpsDataDelayed . sensor_idx ) . toftype ( ) - accelPosOffset ;
2020-01-26 02:06:58 -04:00
if ( posOffsetBody . is_zero ( ) ) {
return ;
}
// Don't fuse velocity data if GPS doesn't support it
if ( fuseVelData ) {
// TODO use a filtered angular rate with a group delay that matches the GPS delay
2021-05-04 08:12:23 -03:00
Vector3F angRate = imuDataDelayed . delAng * ( 1.0f / imuDataDelayed . delAngDT ) ;
Vector3F velOffsetBody = angRate % posOffsetBody ;
Vector3F velOffsetEarth = prevTnb . mul_transpose ( velOffsetBody ) ;
2020-01-26 02:06:58 -04:00
gps_data . vel . x - = velOffsetEarth . x ;
gps_data . vel . y - = velOffsetEarth . y ;
gps_data . vel . z - = velOffsetEarth . z ;
}
2021-05-04 08:12:23 -03:00
Vector3F posOffsetEarth = prevTnb . mul_transpose ( posOffsetBody ) ;
2020-01-26 02:06:58 -04:00
gps_data . pos . x - = posOffsetEarth . x ;
gps_data . pos . y - = posOffsetEarth . y ;
gps_data . hgt + = posOffsetEarth . z ;
}
2020-04-13 00:19:46 -03:00
// correct external navigation earth-frame position using sensor body-frame offset
2021-05-04 08:12:23 -03:00
void NavEKF2_core : : CorrectExtNavForSensorOffset ( Vector3F & ext_position ) const
2020-04-13 00:19:46 -03:00
{
# if HAL_VISUALODOM_ENABLED
2020-11-07 02:24:13 -04:00
const auto * visual_odom = dal . visualodom ( ) ;
2020-04-13 00:19:46 -03:00
if ( visual_odom = = nullptr ) {
return ;
}
2021-05-04 08:12:23 -03:00
const Vector3F posOffsetBody = visual_odom - > get_pos_offset ( ) . toftype ( ) - accelPosOffset ;
2020-04-13 00:19:46 -03:00
if ( posOffsetBody . is_zero ( ) ) {
return ;
}
2021-05-04 08:12:23 -03:00
Vector3F posOffsetEarth = prevTnb . mul_transpose ( posOffsetBody ) ;
2020-04-13 00:19:46 -03:00
ext_position . x - = posOffsetEarth . x ;
ext_position . y - = posOffsetEarth . y ;
ext_position . z - = posOffsetEarth . z ;
# endif
}
2018-10-03 23:43:13 -03:00
// correct external navigation earth-frame velocity using sensor body-frame offset
2021-05-04 08:12:23 -03:00
void NavEKF2_core : : CorrectExtNavVelForSensorOffset ( Vector3F & ext_velocity ) const
2018-10-03 23:43:13 -03:00
{
# if HAL_VISUALODOM_ENABLED
2020-11-07 02:24:13 -04:00
const auto * visual_odom = dal . visualodom ( ) ;
2018-10-03 23:43:13 -03:00
if ( visual_odom = = nullptr ) {
return ;
}
2021-05-04 08:12:23 -03:00
const Vector3F posOffsetBody = visual_odom - > get_pos_offset ( ) . toftype ( ) - accelPosOffset ;
2018-10-03 23:43:13 -03:00
if ( posOffsetBody . is_zero ( ) ) {
return ;
}
// TODO use a filtered angular rate with a group delay that matches the sensor delay
2021-05-04 08:12:23 -03:00
const Vector3F angRate = imuDataDelayed . delAng * ( 1.0f / imuDataDelayed . delAngDT ) ;
2018-10-03 23:43:13 -03:00
ext_velocity + = get_vel_correction_for_sensor_offset ( posOffsetBody , prevTnb , angRate ) ;
# endif
}
2015-10-05 23:30:07 -03:00
/********************************************************
* FUSE MEASURED_DATA *
* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */
// select fusion of velocity, position and height measurements
void NavEKF2_core : : SelectVelPosFusion ( )
{
2015-10-18 19:34:11 -03:00
// Check if the magnetometer has been fused on that time step and the filter is running at faster than 200 Hz
// If so, don't fuse measurements on this time step to reduce frame over-runs
2015-10-20 06:12:17 -03:00
// Only allow one time slip to prevent high rate magnetometer data preventing fusion of other measurements
if ( magFusePerformed & & dtIMUavg < 0.005f & & ! posVelFusionDelayed ) {
posVelFusionDelayed = true ;
2015-10-18 19:34:11 -03:00
return ;
2015-10-20 06:12:17 -03:00
} else {
posVelFusionDelayed = false ;
2015-10-18 19:34:11 -03:00
}
2018-03-07 00:42:31 -04:00
// Check for data at the fusion time horizon
extNavDataToFuse = storedExtNav . recall ( extNavDataDelayed , imuDataDelayed . time_ms ) ;
2018-10-03 23:43:13 -03:00
extNavVelToFuse = storedExtNavVel . recall ( extNavVelDelayed , imuDataDelayed . time_ms ) ;
if ( extNavVelToFuse ) {
CorrectExtNavVelForSensorOffset ( extNavVelDelayed . vel ) ;
}
2018-03-07 00:42:31 -04:00
2020-04-23 02:21:40 -03:00
// read GPS data from the sensor and check for new data in the buffer
readGpsData ( ) ;
gpsDataToFuse = storedGPS . recall ( gpsDataDelayed , imuDataDelayed . time_ms ) ;
2015-10-05 23:30:07 -03:00
// Determine if we need to fuse position and velocity data on this time step
2015-11-12 04:07:52 -04:00
if ( gpsDataToFuse & & PV_AidingMode = = AID_ABSOLUTE ) {
2018-03-07 00:42:31 -04:00
// set fusion request flags
if ( frontend - > _fusionModeGPS < = 1 ) {
fuseVelData = true ;
} else {
fuseVelData = false ;
}
fusePosData = true ;
extNavUsedForPos = false ;
2020-01-26 02:06:58 -04:00
// correct for antenna position
CorrectGPSForAntennaOffset ( gpsDataDelayed ) ;
2017-01-28 07:08:46 -04:00
2018-03-07 00:42:31 -04:00
// copy corrected GPS data to observation vector
if ( fuseVelData ) {
velPosObs [ 0 ] = gpsDataDelayed . vel . x ;
velPosObs [ 1 ] = gpsDataDelayed . vel . y ;
velPosObs [ 2 ] = gpsDataDelayed . vel . z ;
}
velPosObs [ 3 ] = gpsDataDelayed . pos . x ;
velPosObs [ 4 ] = gpsDataDelayed . pos . y ;
2017-01-28 07:08:46 -04:00
2018-03-07 00:42:31 -04:00
} else if ( extNavDataToFuse & & PV_AidingMode = = AID_ABSOLUTE ) {
// This is a special case that uses and external nav system for position
extNavUsedForPos = true ;
2020-04-17 23:03:57 -03:00
activeHgtSource = HGT_SOURCE_EXTNAV ;
2018-03-07 00:42:31 -04:00
fuseVelData = false ;
fuseHgtData = true ;
fusePosData = true ;
2020-04-13 00:19:46 -03:00
// correct for external navigation sensor position
CorrectExtNavForSensorOffset ( extNavDataDelayed . pos ) ;
2018-03-07 00:42:31 -04:00
velPosObs [ 3 ] = extNavDataDelayed . pos . x ;
velPosObs [ 4 ] = extNavDataDelayed . pos . y ;
velPosObs [ 5 ] = extNavDataDelayed . pos . z ;
// if compass is disabled, also use it for yaw
if ( ! use_compass ( ) ) {
extNavUsedForYaw = true ;
if ( ! yawAlignComplete ) {
extNavYawResetRequest = true ;
magYawResetRequest = false ;
gpsYawResetRequest = false ;
controlMagYawReset ( ) ;
finalInflightYawInit = true ;
} else {
fuseEulerYaw ( ) ;
}
2017-01-28 07:08:46 -04:00
} else {
2018-03-07 00:42:31 -04:00
extNavUsedForYaw = false ;
2017-01-28 07:08:46 -04:00
}
2015-10-05 23:30:07 -03:00
} else {
fuseVelData = false ;
fusePosData = false ;
}
2018-10-03 23:43:13 -03:00
if ( extNavVelToFuse & & ( frontend - > _fusionModeGPS = = 3 ) ) {
fuseVelData = true ;
velPosObs [ 0 ] = extNavVelDelayed . vel . x ;
velPosObs [ 1 ] = extNavVelDelayed . vel . y ;
velPosObs [ 2 ] = extNavVelDelayed . vel . z ;
}
2016-05-31 03:02:52 -03:00
// we have GPS data to fuse and a request to align the yaw using the GPS course
if ( gpsYawResetRequest ) {
realignYawGPS ( ) ;
}
2015-11-12 04:07:52 -04:00
// Select height data to be fused from the available baro, range finder and GPS sources
2018-03-07 00:42:31 -04:00
2015-11-12 04:07:52 -04:00
selectHeightForFusion ( ) ;
2015-10-05 23:30:07 -03:00
2017-01-28 07:08:46 -04:00
// if we are using GPS, check for a change in receiver and reset position and height
if ( gpsDataToFuse & & PV_AidingMode = = AID_ABSOLUTE & & gpsDataDelayed . sensor_idx ! = last_gps_idx ) {
// record the ID of the GPS that we are using for the reset
last_gps_idx = gpsDataDelayed . sensor_idx ;
// Store the position before the reset so that we can record the reset delta
posResetNE . x = stateStruct . position . x ;
posResetNE . y = stateStruct . position . y ;
// Set the position states to the position from the new GPS
2020-01-26 02:06:58 -04:00
stateStruct . position . x = gpsDataDelayed . pos . x ;
stateStruct . position . y = gpsDataDelayed . pos . y ;
2017-01-28 07:08:46 -04:00
// Calculate the position offset due to the reset
posResetNE . x = stateStruct . position . x - posResetNE . x ;
posResetNE . y = stateStruct . position . y - posResetNE . y ;
// Add the offset to the output observer states
for ( uint8_t i = 0 ; i < imu_buffer_length ; i + + ) {
storedOutput [ i ] . position . x + = posResetNE . x ;
storedOutput [ i ] . position . y + = posResetNE . y ;
}
outputDataNew . position . x + = posResetNE . x ;
outputDataNew . position . y + = posResetNE . y ;
outputDataDelayed . position . x + = posResetNE . x ;
outputDataDelayed . position . y + = posResetNE . y ;
// store the time of the reset
lastPosReset_ms = imuSampleTime_ms ;
2019-02-21 13:33:38 -04:00
// If we are also using GPS as the height reference, reset the height
2017-01-28 07:08:46 -04:00
if ( activeHgtSource = = HGT_SOURCE_GPS ) {
// Store the position before the reset so that we can record the reset delta
posResetD = stateStruct . position . z ;
// write to the state vector
stateStruct . position . z = - hgtMea ;
// Calculate the position jump due to the reset
posResetD = stateStruct . position . z - posResetD ;
// Add the offset to the output observer states
outputDataNew . position . z + = posResetD ;
2019-09-22 02:09:58 -03:00
vertCompFiltState . pos = outputDataNew . position . z ;
2017-01-28 07:08:46 -04:00
outputDataDelayed . position . z + = posResetD ;
for ( uint8_t i = 0 ; i < imu_buffer_length ; i + + ) {
storedOutput [ i ] . position . z + = posResetD ;
}
// store the time of the reset
lastPosResetD_ms = imuSampleTime_ms ;
}
}
2020-04-17 23:10:09 -03:00
// check for external nav position reset
if ( extNavDataToFuse & & ( PV_AidingMode = = AID_ABSOLUTE ) & & ( frontend - > _fusionModeGPS = = 3 ) & & extNavDataDelayed . posReset ) {
ResetPositionNE ( extNavDataDelayed . pos . x , extNavDataDelayed . pos . y ) ;
if ( activeHgtSource = = HGT_SOURCE_EXTNAV ) {
ResetPositionD ( - hgtMea ) ;
}
}
2016-01-19 23:07:10 -04:00
// If we are operating without any aiding, fuse in the last known position
2015-10-21 02:20:52 -03:00
// to constrain tilt drift. This assumes a non-manoeuvring vehicle
// Do this to coincide with the height fusion
if ( fuseHgtData & & PV_AidingMode = = AID_NONE ) {
2018-03-07 00:42:31 -04:00
velPosObs [ 3 ] = lastKnownPositionNE . x ;
velPosObs [ 4 ] = lastKnownPositionNE . y ;
2016-01-23 17:47:32 -04:00
fusePosData = true ;
2016-01-19 23:07:10 -04:00
fuseVelData = false ;
2015-10-21 02:20:52 -03:00
}
2015-10-05 23:30:07 -03:00
// perform fusion
if ( fuseVelData | | fusePosData | | fuseHgtData ) {
FuseVelPosNED ( ) ;
2015-10-21 02:20:52 -03:00
// clear the flags to prevent repeated fusion of the same data
fuseVelData = false ;
fuseHgtData = false ;
fusePosData = false ;
2015-10-05 23:30:07 -03:00
}
}
// fuse selected position, velocity and height measurements
void NavEKF2_core : : FuseVelPosNED ( )
{
// health is set bad until test passed
2020-11-21 23:48:23 -04:00
bool velHealth = false ; // boolean true if velocity measurements have passed innovation consistency check
bool posHealth = false ; // boolean true if position measurements have passed innovation consistency check
bool hgtHealth = false ; // boolean true if height measurements have passed innovation consistency check
2015-10-05 23:30:07 -03:00
// declare variables used to check measurement errors
2021-05-04 08:12:23 -03:00
Vector3F velInnov ;
2015-10-05 23:30:07 -03:00
// declare variables used to control access to arrays
bool fuseData [ 6 ] = { false , false , false , false , false , false } ;
uint8_t stateIndex ;
uint8_t obsIndex ;
// declare variables used by state and covariance update calculations
Vector6 R_OBS ; // Measurement variances used for fusion
Vector6 R_OBS_DATA_CHECKS ; // Measurement variances used for data checks only
2021-05-04 08:12:23 -03:00
ftype SK ;
2015-10-05 23:30:07 -03: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
if ( fuseVelData | | fusePosData | | fuseHgtData ) {
// calculate additional error in GPS position caused by manoeuvring
2021-05-04 08:12:23 -03:00
ftype posErr = frontend - > gpsPosVarAccScale * accNavMag ;
2015-10-05 23:30:07 -03:00
// estimate the GPS Velocity, GPS horiz position and height measurement variances.
2016-01-19 23:07:10 -04:00
// Use different errors if operating without external aiding using an assumed position or velocity of zero
2016-01-09 17:20:49 -04:00
if ( PV_AidingMode = = AID_NONE ) {
if ( tiltAlignComplete & & motorsArmed ) {
// This is a compromise between corrections for gyro errors and reducing effect of manoeuvre accelerations on tilt estimate
2021-05-04 08:12:23 -03:00
R_OBS [ 0 ] = sq ( constrain_ftype ( frontend - > _noaidHorizNoise , 0.5f , 50.0f ) ) ;
2016-01-09 17:20:49 -04:00
} else {
// Use a smaller value to give faster initial alignment
R_OBS [ 0 ] = sq ( 0.5f ) ;
}
2015-10-22 23:41:30 -03:00
R_OBS [ 1 ] = R_OBS [ 0 ] ;
R_OBS [ 2 ] = R_OBS [ 0 ] ;
2016-01-19 23:07:10 -04:00
R_OBS [ 3 ] = R_OBS [ 0 ] ;
R_OBS [ 4 ] = R_OBS [ 0 ] ;
2016-01-09 17:20:49 -04:00
for ( uint8_t i = 0 ; i < = 2 ; i + + ) R_OBS_DATA_CHECKS [ i ] = R_OBS [ i ] ;
2015-10-05 23:30:07 -03:00
} else {
2015-10-22 23:41:30 -03:00
if ( gpsSpdAccuracy > 0.0f ) {
2016-05-06 19:49:36 -03:00
// use GPS receivers reported speed accuracy if available and floor at value set by GPS velocity noise parameter
2021-05-04 08:12:23 -03:00
R_OBS [ 0 ] = sq ( constrain_ftype ( gpsSpdAccuracy , frontend - > _gpsHorizVelNoise , 50.0f ) ) ;
R_OBS [ 2 ] = sq ( constrain_ftype ( gpsSpdAccuracy , frontend - > _gpsVertVelNoise , 50.0f ) ) ;
2018-10-03 23:43:13 -03:00
} else if ( extNavVelToFuse ) {
2021-05-04 08:12:23 -03:00
R_OBS [ 2 ] = R_OBS [ 0 ] = sq ( constrain_ftype ( extNavVelDelayed . err , 0.05f , 5.0f ) ) ;
2015-10-22 23:41:30 -03:00
} else {
// calculate additional error in GPS velocity caused by manoeuvring
2021-05-04 08:12:23 -03:00
R_OBS [ 0 ] = sq ( constrain_ftype ( frontend - > _gpsHorizVelNoise , 0.05f , 5.0f ) ) + sq ( frontend - > gpsNEVelVarAccScale * accNavMag ) ;
R_OBS [ 2 ] = sq ( constrain_ftype ( frontend - > _gpsVertVelNoise , 0.05f , 5.0f ) ) + sq ( frontend - > gpsDVelVarAccScale * accNavMag ) ;
2015-10-22 23:41:30 -03:00
}
R_OBS [ 1 ] = R_OBS [ 0 ] ;
2016-05-06 19:49:36 -03:00
// Use GPS reported position accuracy if available and floor at value set by GPS position noise parameter
if ( gpsPosAccuracy > 0.0f ) {
2021-05-04 08:12:23 -03:00
R_OBS [ 3 ] = sq ( constrain_ftype ( gpsPosAccuracy , frontend - > _gpsHorizPosNoise , 100.0f ) ) ;
2018-09-28 05:09:12 -03:00
} else if ( extNavUsedForPos ) {
2021-05-04 08:12:23 -03:00
R_OBS [ 3 ] = sq ( constrain_ftype ( extNavDataDelayed . posErr , 0.01f , 10.0f ) ) ;
2016-05-06 19:49:36 -03:00
} else {
2021-05-04 08:12:23 -03:00
R_OBS [ 3 ] = sq ( constrain_ftype ( frontend - > _gpsHorizPosNoise , 0.1f , 10.0f ) ) + sq ( posErr ) ;
2016-05-06 19:49:36 -03:00
}
R_OBS [ 4 ] = R_OBS [ 3 ] ;
2016-01-06 04:58:15 -04:00
// For data integrity checks we use the same measurement variances as used to calculate the Kalman gains for all measurements except GPS horizontal velocity
2019-02-21 13:33:38 -04:00
// For horizontal GPS velocity we don't want the acceptance radius to increase with reported GPS accuracy so we use a value based on best GPS perfomrance
2016-01-06 04:58:15 -04:00
// plus a margin for manoeuvres. It is better to reject GPS horizontal velocity errors early
2021-05-04 08:12:23 -03:00
ftype obs_data_chk ;
2018-10-03 23:43:13 -03:00
if ( extNavVelToFuse ) {
2021-05-04 08:12:23 -03:00
obs_data_chk = sq ( constrain_ftype ( extNavVelDelayed . err , 0.05f , 5.0f ) ) + sq ( frontend - > extNavVelVarAccScale * accNavMag ) ;
2018-10-03 23:43:13 -03:00
} else {
2021-05-04 08:12:23 -03:00
obs_data_chk = sq ( constrain_ftype ( frontend - > _gpsHorizVelNoise , 0.05f , 5.0f ) ) + sq ( frontend - > gpsNEVelVarAccScale * accNavMag ) ;
2018-10-03 23:43:13 -03:00
}
R_OBS_DATA_CHECKS [ 0 ] = R_OBS_DATA_CHECKS [ 1 ] = R_OBS_DATA_CHECKS [ 2 ] = obs_data_chk ;
2015-10-05 23:30:07 -03:00
}
2016-01-09 17:20:49 -04:00
R_OBS [ 5 ] = posDownObsNoise ;
for ( uint8_t i = 3 ; i < = 5 ; i + + ) R_OBS_DATA_CHECKS [ i ] = R_OBS [ i ] ;
2015-10-05 23:30:07 -03:00
2016-05-12 14:04:56 -03:00
// if vertical GPS velocity data and an independent height source is being used, check to see if the GPS vertical velocity and altimeter
2015-10-05 23:30:07 -03:00
// innovations have the same sign and are outside limits. If so, then it is likely aliasing is affecting
// the accelerometers and we should disable the GPS and barometer innovation consistency checks.
2015-11-12 04:07:52 -04:00
if ( useGpsVertVel & & fuseVelData & & ( frontend - > _altSource ! = 2 ) ) {
2015-10-05 23:30:07 -03:00
// calculate innovations for height and vertical GPS vel measurements
2021-05-04 08:12:23 -03:00
ftype hgtErr = stateStruct . position . z - velPosObs [ 5 ] ;
ftype velDErr = stateStruct . velocity . z - velPosObs [ 2 ] ;
2015-10-05 23:30:07 -03:00
// check if they are the same sign and both more than 3-sigma out of bounds
if ( ( hgtErr * velDErr > 0.0f ) & & ( sq ( hgtErr ) > 9.0f * ( P [ 8 ] [ 8 ] + R_OBS_DATA_CHECKS [ 5 ] ) ) & & ( sq ( velDErr ) > 9.0f * ( P [ 5 ] [ 5 ] + R_OBS_DATA_CHECKS [ 2 ] ) ) ) {
badIMUdata = true ;
} else {
badIMUdata = false ;
}
}
// calculate innovations and check GPS data validity using an innovation consistency check
// test position measurements
if ( fusePosData ) {
// test horizontal position measurements
2018-03-07 00:42:31 -04:00
innovVelPos [ 3 ] = stateStruct . position . x - velPosObs [ 3 ] ;
innovVelPos [ 4 ] = stateStruct . position . y - velPosObs [ 4 ] ;
2015-10-05 23:30:07 -03:00
varInnovVelPos [ 3 ] = P [ 6 ] [ 6 ] + R_OBS_DATA_CHECKS [ 3 ] ;
varInnovVelPos [ 4 ] = P [ 7 ] [ 7 ] + R_OBS_DATA_CHECKS [ 4 ] ;
// apply an innovation consistency threshold test, but don't fail if bad IMU data
2021-05-04 08:12:23 -03:00
ftype maxPosInnov2 = sq ( MAX ( 0.01f * ( ftype ) frontend - > _gpsPosInnovGate , 1.0f ) ) * ( varInnovVelPos [ 3 ] + varInnovVelPos [ 4 ] ) ;
2015-10-05 23:30:07 -03:00
posTestRatio = ( sq ( innovVelPos [ 3 ] ) + sq ( innovVelPos [ 4 ] ) ) / maxPosInnov2 ;
posHealth = ( ( posTestRatio < 1.0f ) | | badIMUdata ) ;
2016-01-09 17:20:49 -04:00
// use position data if healthy or timed out
2016-01-19 23:07:10 -04:00
if ( PV_AidingMode = = AID_NONE ) {
posHealth = true ;
lastPosPassTime_ms = imuSampleTime_ms ;
} else if ( posHealth | | posTimeout ) {
2015-10-05 23:30:07 -03:00
posHealth = true ;
2016-01-09 17:20:49 -04:00
lastPosPassTime_ms = imuSampleTime_ms ;
// if timed out or outside the specified uncertainty radius, reset to the GPS
if ( posTimeout | | ( ( P [ 6 ] [ 6 ] + P [ 7 ] [ 7 ] ) > sq ( float ( frontend - > _gpsGlitchRadiusMax ) ) ) ) {
// reset the position to the current GPS position
ResetPosition ( ) ;
// reset the velocity to the GPS velocity
ResetVelocity ( ) ;
// don't fuse GPS data on this time step
fusePosData = false ;
fuseVelData = false ;
// Reset the position variances and corresponding covariances to a value that will pass the checks
zeroRows ( P , 6 , 7 ) ;
zeroCols ( P , 6 , 7 ) ;
P [ 6 ] [ 6 ] = sq ( float ( 0.5f * frontend - > _gpsGlitchRadiusMax ) ) ;
P [ 7 ] [ 7 ] = P [ 6 ] [ 6 ] ;
// Reset the normalised innovation to avoid failing the bad fusion tests
posTestRatio = 0.0f ;
velTestRatio = 0.0f ;
2015-10-05 23:30:07 -03:00
}
}
}
// test velocity measurements
if ( fuseVelData ) {
// test velocity measurements
uint8_t imax = 2 ;
2015-10-22 23:41:30 -03:00
// Don't fuse vertical velocity observations if inhibited by the user or if we are using synthetic data
2020-11-15 05:38:05 -04:00
if ( ! useExtNavVel & & ( frontend - > _fusionModeGPS > 0 | | PV_AidingMode ! = AID_ABSOLUTE | |
2020-11-20 15:38:49 -04:00
! dal . gps ( ) . have_vertical_velocity ( ) ) ) {
2015-10-05 23:30:07 -03:00
imax = 1 ;
}
2021-05-04 08:12:23 -03:00
ftype innovVelSumSq = 0 ; // sum of squares of velocity innovations
ftype varVelSum = 0 ; // sum of velocity innovation variances
2015-10-05 23:30:07 -03:00
for ( uint8_t i = 0 ; i < = imax ; i + + ) {
// velocity states start at index 3
stateIndex = i + 3 ;
// calculate innovations using blended and single IMU predicted states
2018-03-07 00:42:31 -04:00
velInnov [ i ] = stateStruct . velocity [ i ] - velPosObs [ i ] ; // blended
2015-10-05 23:30:07 -03:00
// calculate innovation variance
varInnovVelPos [ i ] = P [ stateIndex ] [ stateIndex ] + R_OBS_DATA_CHECKS [ i ] ;
// sum the innovation and innovation variances
innovVelSumSq + = sq ( velInnov [ i ] ) ;
varVelSum + = varInnovVelPos [ i ] ;
}
// apply an innovation consistency threshold test, but don't fail if bad IMU data
// calculate the test ratio
2021-05-04 08:12:23 -03:00
velTestRatio = innovVelSumSq / ( varVelSum * sq ( MAX ( 0.01f * ( ftype ) frontend - > _gpsVelInnovGate , 1.0f ) ) ) ;
2015-10-05 23:30:07 -03:00
// fail if the ratio is greater than 1
velHealth = ( ( velTestRatio < 1.0f ) | | badIMUdata ) ;
2015-10-29 07:46:26 -03:00
// use velocity data if healthy, timed out, or in constant position mode
2015-10-30 00:52:49 -03:00
if ( velHealth | | velTimeout ) {
2015-10-05 23:30:07 -03:00
velHealth = true ;
// restart the timeout count
lastVelPassTime_ms = imuSampleTime_ms ;
2015-10-29 07:46:26 -03:00
// If we are doing full aiding and velocity fusion times out, reset to the GPS velocity
if ( PV_AidingMode = = AID_ABSOLUTE & & velTimeout ) {
// reset the velocity to the GPS velocity
ResetVelocity ( ) ;
// don't fuse GPS velocity data on this time step
fuseVelData = false ;
// Reset the normalised innovation to avoid failing the bad fusion tests
velTestRatio = 0.0f ;
}
2015-10-05 23:30:07 -03:00
}
}
// test height measurements
if ( fuseHgtData ) {
// calculate height innovations
2018-03-07 00:42:31 -04:00
innovVelPos [ 5 ] = stateStruct . position . z - velPosObs [ 5 ] ;
2015-10-05 23:30:07 -03:00
varInnovVelPos [ 5 ] = P [ 8 ] [ 8 ] + R_OBS_DATA_CHECKS [ 5 ] ;
// calculate the innovation consistency test ratio
2021-05-04 08:12:23 -03:00
hgtTestRatio = sq ( innovVelPos [ 5 ] ) / ( sq ( MAX ( 0.01f * ( ftype ) frontend - > _hgtInnovGate , 1.0f ) ) * varInnovVelPos [ 5 ] ) ;
2019-07-29 18:50:39 -03:00
// when on ground we accept a larger test ratio to allow
// the filter to handle large switch on IMU bias errors
// without rejecting the height sensor
2021-05-04 08:12:23 -03:00
const ftype maxTestRatio = ( PV_AidingMode = = AID_NONE & & onGround ) ? 3.0 : 1.0 ;
2019-07-29 18:50:39 -03:00
// fail if the ratio is > maxTestRatio, but don't fail if bad IMU data
hgtHealth = ( hgtTestRatio < maxTestRatio ) | | badIMUdata ;
2015-10-05 23:30:07 -03:00
// Fuse height data if healthy or timed out or in constant position mode
2019-07-29 18:50:39 -03:00
if ( hgtHealth | | hgtTimeout ) {
2015-11-05 21:12:08 -04:00
// Calculate a filtered value to be used by pre-flight health checks
// We need to filter because wind gusts can generate significant baro noise and we want to be able to detect bias errors in the inertial solution
if ( onGround ) {
2021-05-04 08:12:23 -03:00
ftype dtBaro = ( imuSampleTime_ms - lastHgtPassTime_ms ) * 1.0e-3 f ;
const ftype hgtInnovFiltTC = 2.0f ;
ftype alpha = constrain_ftype ( dtBaro / ( dtBaro + hgtInnovFiltTC ) , 0.0f , 1.0f ) ;
2015-11-05 21:12:08 -04:00
hgtInnovFiltState + = ( innovVelPos [ 5 ] - hgtInnovFiltState ) * alpha ;
} else {
hgtInnovFiltState = 0.0f ;
}
2015-11-12 04:07:52 -04:00
// if timed out, reset the height
2015-10-05 23:30:07 -03:00
if ( hgtTimeout ) {
ResetHeight ( ) ;
}
2015-11-12 04:07:52 -04:00
// If we have got this far then declare the height data as healthy and reset the timeout counter
hgtHealth = true ;
lastHgtPassTime_ms = imuSampleTime_ms ;
2015-10-05 23:30:07 -03:00
}
}
// set range for sequential fusion of velocity and position measurements depending on which data is available and its health
if ( fuseVelData & & velHealth ) {
fuseData [ 0 ] = true ;
fuseData [ 1 ] = true ;
2018-10-03 23:43:13 -03:00
if ( useGpsVertVel | | useExtNavVel ) {
2015-10-05 23:30:07 -03:00
fuseData [ 2 ] = true ;
}
tiltErrVec . zero ( ) ;
}
if ( fusePosData & & posHealth ) {
fuseData [ 3 ] = true ;
fuseData [ 4 ] = true ;
tiltErrVec . zero ( ) ;
}
if ( fuseHgtData & & hgtHealth ) {
fuseData [ 5 ] = true ;
}
// fuse measurements sequentially
for ( obsIndex = 0 ; obsIndex < = 5 ; obsIndex + + ) {
if ( fuseData [ obsIndex ] ) {
stateIndex = 3 + obsIndex ;
// calculate the measurement innovation, using states from a different time coordinate if fusing height data
// adjust scaling on GPS measurement noise variances if not enough satellites
if ( obsIndex < = 2 )
{
2018-03-07 00:42:31 -04:00
innovVelPos [ obsIndex ] = stateStruct . velocity [ obsIndex ] - velPosObs [ obsIndex ] ;
2015-10-05 23:30:07 -03:00
R_OBS [ obsIndex ] * = sq ( gpsNoiseScaler ) ;
}
else if ( obsIndex = = 3 | | obsIndex = = 4 ) {
2018-03-07 00:42:31 -04:00
innovVelPos [ obsIndex ] = stateStruct . position [ obsIndex - 3 ] - velPosObs [ obsIndex ] ;
2015-10-05 23:30:07 -03:00
R_OBS [ obsIndex ] * = sq ( gpsNoiseScaler ) ;
2015-11-12 04:07:52 -04:00
} else if ( obsIndex = = 5 ) {
2018-03-07 00:42:31 -04:00
innovVelPos [ obsIndex ] = stateStruct . position [ obsIndex - 3 ] - velPosObs [ obsIndex ] ;
2021-05-04 08:12:23 -03:00
const ftype gndMaxBaroErr = 4.0f ;
const ftype gndBaroInnovFloor = - 0.5f ;
2015-11-12 04:07:52 -04:00
2021-05-28 20:54:14 -03:00
if ( dal . get_touchdown_expected ( ) & & activeHgtSource = = HGT_SOURCE_BARO ) {
2015-11-12 04:07:52 -04:00
// when a touchdown is expected, floor the barometer innovation at gndBaroInnovFloor
// constrain the correction between 0 and gndBaroInnovFloor+gndMaxBaroErr
// this function looks like this:
// |/
//---------|---------
// ____/|
// / |
// / |
2021-05-04 08:12:23 -03:00
innovVelPos [ 5 ] + = constrain_ftype ( - innovVelPos [ 5 ] + gndBaroInnovFloor , 0.0f , gndBaroInnovFloor + gndMaxBaroErr ) ;
2015-10-05 23:30:07 -03:00
}
}
// calculate the Kalman gain and calculate innovation variances
varInnovVelPos [ obsIndex ] = P [ stateIndex ] [ stateIndex ] + R_OBS [ obsIndex ] ;
SK = 1.0f / varInnovVelPos [ obsIndex ] ;
for ( uint8_t i = 0 ; i < = 15 ; i + + ) {
Kfusion [ i ] = P [ i ] [ stateIndex ] * SK ;
}
// inhibit magnetic field state estimation by setting Kalman gains to zero
if ( ! inhibitMagStates ) {
for ( uint8_t i = 16 ; i < = 21 ; i + + ) {
Kfusion [ i ] = P [ i ] [ stateIndex ] * SK ;
}
} else {
for ( uint8_t i = 16 ; i < = 21 ; i + + ) {
Kfusion [ i ] = 0.0f ;
}
}
// inhibit wind state estimation by setting Kalman gains to zero
if ( ! inhibitWindStates ) {
Kfusion [ 22 ] = P [ 22 ] [ stateIndex ] * SK ;
Kfusion [ 23 ] = P [ 23 ] [ stateIndex ] * SK ;
} else {
Kfusion [ 22 ] = 0.0f ;
Kfusion [ 23 ] = 0.0f ;
}
// update the covariance - take advantage of direct observation of a single state at index = stateIndex to reduce computations
// this is a numerically optimised implementation of standard equation P = (I - K*H)*P;
for ( uint8_t i = 0 ; i < = stateIndexLim ; i + + ) {
for ( uint8_t j = 0 ; j < = stateIndexLim ; j + + )
{
KHP [ i ] [ j ] = Kfusion [ i ] * P [ stateIndex ] [ j ] ;
}
}
2016-05-10 04:03:53 -03:00
// Check that we are not going to drive any variances negative and skip the update if so
bool healthyFusion = true ;
2015-10-05 23:30:07 -03:00
for ( uint8_t i = 0 ; i < = stateIndexLim ; i + + ) {
2016-05-10 04:03:53 -03:00
if ( KHP [ i ] [ i ] > P [ i ] [ i ] ) {
healthyFusion = false ;
}
}
if ( healthyFusion ) {
// update the covariance matrix
for ( uint8_t i = 0 ; i < = stateIndexLim ; i + + ) {
for ( uint8_t j = 0 ; j < = stateIndexLim ; j + + ) {
P [ i ] [ j ] = P [ i ] [ j ] - KHP [ i ] [ j ] ;
}
}
2019-02-21 13:33:38 -04:00
// force the covariance matrix to be symmetrical and limit the variances to prevent ill-conditioning.
2016-05-10 04:03:53 -03:00
ForceSymmetry ( ) ;
ConstrainVariances ( ) ;
// update the states
2019-02-25 16:20:30 -04:00
// zero the attitude error state - by definition it is assumed to be zero before each observation fusion
2016-05-10 04:03:53 -03:00
stateStruct . angErr . zero ( ) ;
// calculate state corrections and re-normalise the quaternions for states predicted using the blended IMU data
for ( uint8_t i = 0 ; i < = stateIndexLim ; i + + ) {
statesArray [ i ] = statesArray [ i ] - Kfusion [ i ] * innovVelPos [ obsIndex ] ;
}
2021-03-10 17:43:16 -04:00
// the first 3 states represent the angular misalignment vector.
// This is used to correct the estimated quaternion
2016-05-10 04:03:53 -03:00
stateStruct . quat . rotate ( stateStruct . angErr ) ;
// sum the attitude error from velocity and position fusion only
// used as a metric for convergence monitoring
if ( obsIndex ! = 5 ) {
tiltErrVec + = stateStruct . angErr ;
}
// record good fusion status
if ( obsIndex = = 0 ) {
faultStatus . bad_nvel = false ;
} else if ( obsIndex = = 1 ) {
faultStatus . bad_evel = false ;
} else if ( obsIndex = = 2 ) {
faultStatus . bad_dvel = false ;
} else if ( obsIndex = = 3 ) {
faultStatus . bad_npos = false ;
} else if ( obsIndex = = 4 ) {
faultStatus . bad_epos = false ;
} else if ( obsIndex = = 5 ) {
faultStatus . bad_dpos = false ;
}
} else {
// record bad fusion status
if ( obsIndex = = 0 ) {
faultStatus . bad_nvel = true ;
} else if ( obsIndex = = 1 ) {
faultStatus . bad_evel = true ;
} else if ( obsIndex = = 2 ) {
faultStatus . bad_dvel = true ;
} else if ( obsIndex = = 3 ) {
faultStatus . bad_npos = true ;
} else if ( obsIndex = = 4 ) {
faultStatus . bad_epos = true ;
} else if ( obsIndex = = 5 ) {
faultStatus . bad_dpos = true ;
2015-10-05 23:30:07 -03:00
}
}
}
}
}
}
/********************************************************
* MISC FUNCTIONS *
* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */
2015-11-12 04:07:52 -04:00
// select the height measurement to be fused from the available baro, range finder and GPS sources
void NavEKF2_core : : selectHeightForFusion ( )
{
// Read range finder data and check for new data in the buffer
// This data is used by both height and optical flow fusion processing
readRangeFinder ( ) ;
2015-11-13 18:28:45 -04:00
rangeDataToFuse = storedRange . recall ( rangeDataDelayed , imuDataDelayed . time_ms ) ;
2015-11-12 04:07:52 -04:00
2016-10-11 19:26:51 -03:00
// correct range data for the body frame position offset relative to the IMU
// the corrected reading is the reading that would have been taken if the sensor was
// co-located with the IMU
2020-11-07 02:24:13 -04:00
const auto * _rng = dal . rangefinder ( ) ;
2019-11-26 02:43:24 -04:00
if ( _rng & & rangeDataToFuse ) {
2020-11-05 19:30:16 -04:00
const auto * sensor = _rng - > get_backend ( rangeDataDelayed . sensor_idx ) ;
2017-08-08 03:06:48 -03:00
if ( sensor ! = nullptr ) {
2021-05-04 08:12:23 -03:00
Vector3F posOffsetBody = sensor - > get_pos_offset ( ) . toftype ( ) - accelPosOffset ;
2017-08-08 03:06:48 -03:00
if ( ! posOffsetBody . is_zero ( ) ) {
2021-05-04 08:12:23 -03:00
Vector3F posOffsetEarth = prevTnb . mul_transpose ( posOffsetBody ) ;
2017-08-08 03:06:48 -03:00
rangeDataDelayed . rng + = posOffsetEarth . z / prevTnb . c . z ;
}
2016-10-14 19:18:25 -03:00
}
2016-10-11 19:26:51 -03:00
}
2015-11-12 04:07:52 -04:00
// read baro height data from the sensor and check for new data in the buffer
readBaroData ( ) ;
2015-11-13 18:28:45 -04:00
baroDataToFuse = storedBaro . recall ( baroDataDelayed , imuDataDelayed . time_ms ) ;
2015-11-12 04:07:52 -04:00
2020-05-19 07:51:40 -03:00
bool rangeFinderDataIsFresh = ( imuSampleTime_ms - rngValidMeaTime_ms < 500 ) ;
2016-07-12 05:56:58 -03:00
// select height source
2020-05-15 23:05:29 -03:00
if ( extNavUsedForPos ) {
2020-05-15 22:43:55 -03:00
// always use external navigation as the height source if using for position.
2020-04-17 23:03:57 -03:00
activeHgtSource = HGT_SOURCE_EXTNAV ;
2020-05-19 07:51:40 -03:00
} else if ( ( frontend - > _altSource = = 1 ) & & _rng & & rangeFinderDataIsFresh ) {
2020-05-15 22:43:55 -03:00
// user has specified the range finder as a primary height source
activeHgtSource = HGT_SOURCE_RNG ;
2020-05-19 07:51:40 -03:00
} else if ( ( frontend - > _useRngSwHgt > 0 ) & & ( ( frontend - > _altSource = = 0 ) | | ( frontend - > _altSource = = 2 ) ) & & _rng & & rangeFinderDataIsFresh ) {
2020-05-15 22:43:55 -03:00
// determine if we are above or below the height switch region
2021-05-04 08:12:23 -03:00
ftype rangeMaxUse = 1e-4 f * ( float ) _rng - > max_distance_cm_orient ( ROTATION_PITCH_270 ) * ( ftype ) frontend - > _useRngSwHgt ;
2020-05-15 22:43:55 -03:00
bool aboveUpperSwHgt = ( terrainState - stateStruct . position . z ) > rangeMaxUse ;
bool belowLowerSwHgt = ( terrainState - stateStruct . position . z ) < 0.7f * rangeMaxUse ;
// If the terrain height is consistent and we are moving slowly, then it can be
// used as a height reference in combination with a range finder
// apply a hysteresis to the speed check to prevent rapid switching
2021-09-11 07:33:42 -03:00
ftype horizSpeed = stateStruct . velocity . xy ( ) . length ( ) ;
2020-05-15 22:43:55 -03:00
bool dontTrustTerrain = ( ( horizSpeed > frontend - > _useRngSwSpd ) & & filterStatus . flags . horiz_vel ) | | ! terrainHgtStable ;
2021-05-04 08:12:23 -03:00
ftype trust_spd_trigger = MAX ( ( frontend - > _useRngSwSpd - 1.0f ) , ( frontend - > _useRngSwSpd * 0.5f ) ) ;
2020-05-15 22:43:55 -03:00
bool trustTerrain = ( horizSpeed < trust_spd_trigger ) & & terrainHgtStable ;
/*
* Switch between range finder and primary height source using height above ground and speed thresholds with
* hysteresis to avoid rapid switching . Using range finder for height requires a consistent terrain height
* which cannot be assumed if the vehicle is moving horizontally .
*/
if ( ( aboveUpperSwHgt | | dontTrustTerrain ) & & ( activeHgtSource = = HGT_SOURCE_RNG ) ) {
// cannot trust terrain or range finder so stop using range finder height
if ( frontend - > _altSource = = 0 ) {
activeHgtSource = HGT_SOURCE_BARO ;
} else if ( frontend - > _altSource = = 2 ) {
activeHgtSource = HGT_SOURCE_GPS ;
2016-07-12 05:56:58 -03:00
}
2020-05-15 22:43:55 -03:00
} else if ( belowLowerSwHgt & & trustTerrain & & ( prevTnb . c . z > = 0.7f ) ) {
// reliable terrain and range finder so start using range finder height
activeHgtSource = HGT_SOURCE_RNG ;
2016-07-12 05:56:58 -03:00
}
2020-05-15 22:43:55 -03:00
} else if ( frontend - > _altSource = = 0 ) {
activeHgtSource = HGT_SOURCE_BARO ;
2016-07-12 05:56:58 -03:00
} else if ( ( frontend - > _altSource = = 2 ) & & ( ( imuSampleTime_ms - lastTimeGpsReceived_ms ) < 500 ) & & validOrigin & & gpsAccuracyGood ) {
activeHgtSource = HGT_SOURCE_GPS ;
2016-10-25 17:54:29 -03:00
} else if ( ( frontend - > _altSource = = 3 ) & & validOrigin & & rngBcnGoodToAlign ) {
activeHgtSource = HGT_SOURCE_BCN ;
2016-07-12 05:56:58 -03:00
}
2020-05-19 07:51:40 -03:00
// Use Baro alt as a fallback if we lose range finder, GPS, external nav or Beacon
bool lostRngHgt = ( ( activeHgtSource = = HGT_SOURCE_RNG ) & & ( ! rangeFinderDataIsFresh ) ) ;
2016-07-12 05:56:58 -03:00
bool lostGpsHgt = ( ( activeHgtSource = = HGT_SOURCE_GPS ) & & ( ( imuSampleTime_ms - lastTimeGpsReceived_ms ) > 2000 ) ) ;
2020-04-17 23:03:57 -03:00
bool lostExtNavHgt = ( ( activeHgtSource = = HGT_SOURCE_EXTNAV ) & & ( ( imuSampleTime_ms - extNavMeasTime_ms ) > 2000 ) ) ;
2020-05-15 22:45:15 -03:00
bool lostRngBcnHgt = ( ( activeHgtSource = = HGT_SOURCE_BCN ) & & ( ( imuSampleTime_ms - rngBcnDataDelayed . time_ms ) > 2000 ) ) ;
if ( lostRngHgt | | lostGpsHgt | | lostExtNavHgt | | lostRngBcnHgt ) {
2016-07-12 05:56:58 -03:00
activeHgtSource = HGT_SOURCE_BARO ;
}
2015-11-12 04:07:52 -04:00
2016-07-12 05:56:58 -03:00
// if there is new baro data to fuse, calculate filtered baro data required by other processes
2015-11-12 04:07:52 -04:00
if ( baroDataToFuse ) {
2016-07-12 05:56:58 -03:00
// calculate offset to baro data that enables us to switch to Baro height use during operation
if ( activeHgtSource ! = HGT_SOURCE_BARO ) {
2015-11-12 04:07:52 -04:00
calcFiltBaroOffset ( ) ;
}
// filtered baro data used to provide a reference for takeoff
// it is is reset to last height measurement on disarming in performArmingChecks()
2021-05-28 20:54:14 -03:00
if ( ! dal . get_takeoff_expected ( ) ) {
2021-05-04 08:12:23 -03:00
const ftype gndHgtFiltTC = 0.5f ;
const ftype dtBaro = frontend - > hgtAvg_ms * 1.0e-3 ;
ftype alpha = constrain_ftype ( dtBaro / ( dtBaro + gndHgtFiltTC ) , 0.0f , 1.0f ) ;
2015-11-12 04:07:52 -04:00
meaHgtAtTakeOff + = ( baroDataDelayed . hgt - meaHgtAtTakeOff ) * alpha ;
}
}
2017-05-09 03:30:58 -03:00
// If we are not using GPS as the primary height sensor, correct EKF origin height so that
// combined local NED position height and origin height remains consistent with the GPS altitude
// This also enables the GPS height to be used as a backup height source
if ( gpsDataToFuse & &
( ( ( frontend - > _originHgtMode & ( 1 < < 0 ) ) & & ( activeHgtSource = = HGT_SOURCE_BARO ) ) | |
( ( frontend - > _originHgtMode & ( 1 < < 1 ) ) & & ( activeHgtSource = = HGT_SOURCE_RNG ) ) )
) {
correctEkfOriginHeight ( ) ;
2016-07-12 05:56:58 -03:00
}
2015-11-12 04:07:52 -04:00
// Select the height measurement source
2020-04-17 23:03:57 -03:00
if ( extNavDataToFuse & & ( activeHgtSource = = HGT_SOURCE_EXTNAV ) ) {
2018-03-07 00:42:31 -04:00
hgtMea = - extNavDataDelayed . pos . z ;
2021-05-04 08:12:23 -03:00
posDownObsNoise = sq ( constrain_ftype ( extNavDataDelayed . posErr , 0.01f , 10.0f ) ) ;
2018-03-07 00:42:31 -04:00
} else if ( rangeDataToFuse & & ( activeHgtSource = = HGT_SOURCE_RNG ) ) {
2015-11-12 04:07:52 -04:00
// using range finder data
// correct for tilt using a flat earth model
if ( prevTnb . c . z > = 0.7 ) {
2016-07-12 05:56:58 -03:00
// calculate height above ground
2015-11-27 13:11:58 -04:00
hgtMea = MAX ( rangeDataDelayed . rng * prevTnb . c . z , rngOnGnd ) ;
2016-07-12 05:56:58 -03:00
// correct for terrain position relative to datum
hgtMea - = terrainState ;
2015-11-12 04:07:52 -04:00
// enable fusion
fuseHgtData = true ;
2018-03-07 00:42:31 -04:00
velPosObs [ 5 ] = - hgtMea ;
2015-11-12 04:07:52 -04:00
// set the observation noise
2021-05-04 08:12:23 -03:00
posDownObsNoise = sq ( constrain_ftype ( frontend - > _rngNoise , 0.1f , 10.0f ) ) ;
2016-09-09 19:52:37 -03:00
// add uncertainty created by terrain gradient and vehicle tilt
posDownObsNoise + = sq ( rangeDataDelayed . rng * frontend - > _terrGradMax ) * MAX ( 0.0f , ( 1.0f - sq ( prevTnb . c . z ) ) ) ;
2015-11-12 04:07:52 -04:00
} else {
// disable fusion if tilted too far
fuseHgtData = false ;
}
2016-07-12 05:56:58 -03:00
} else if ( gpsDataToFuse & & ( activeHgtSource = = HGT_SOURCE_GPS ) ) {
2015-11-12 04:07:52 -04:00
// using GPS data
hgtMea = gpsDataDelayed . hgt ;
// enable fusion
2018-03-07 00:42:31 -04:00
velPosObs [ 5 ] = - hgtMea ;
2015-11-12 04:07:52 -04:00
fuseHgtData = true ;
2016-07-12 05:56:58 -03:00
// set the observation noise using receiver reported accuracy or the horizontal noise scaled for typical VDOP/HDOP ratio
if ( gpsHgtAccuracy > 0.0f ) {
2021-05-04 08:12:23 -03:00
posDownObsNoise = sq ( constrain_ftype ( gpsHgtAccuracy , 1.5f * frontend - > _gpsHorizPosNoise , 100.0f ) ) ;
2016-07-12 05:56:58 -03:00
} else {
2021-05-04 08:12:23 -03:00
posDownObsNoise = sq ( constrain_ftype ( 1.5f * frontend - > _gpsHorizPosNoise , 0.1f , 10.0f ) ) ;
2016-07-12 05:56:58 -03:00
}
} else if ( baroDataToFuse & & ( activeHgtSource = = HGT_SOURCE_BARO ) ) {
2015-11-12 04:07:52 -04:00
// using Baro data
hgtMea = baroDataDelayed . hgt - baroHgtOffset ;
// enable fusion
2018-03-07 00:42:31 -04:00
velPosObs [ 5 ] = - hgtMea ;
2015-11-12 04:07:52 -04:00
fuseHgtData = true ;
// set the observation noise
2021-05-04 08:12:23 -03:00
posDownObsNoise = sq ( constrain_ftype ( frontend - > _baroAltNoise , 0.1f , 10.0f ) ) ;
2015-11-12 04:07:52 -04:00
// reduce weighting (increase observation noise) on baro if we are likely to be in ground effect
2021-05-28 20:54:14 -03:00
if ( dal . get_takeoff_expected ( ) | | dal . get_touchdown_expected ( ) ) {
2015-11-12 04:07:52 -04:00
posDownObsNoise * = frontend - > gndEffectBaroScaler ;
}
2016-03-31 01:00:45 -03:00
// If we are in takeoff mode, the height measurement is limited to be no less than the measurement at start of takeoff
// This prevents negative baro disturbances due to copter downwash corrupting the EKF altitude during initial ascent
2021-05-28 23:01:16 -03:00
if ( motorsArmed & & dal . get_takeoff_expected ( ) & & ! assume_zero_sideslip ( ) ) {
2016-03-31 01:00:45 -03:00
hgtMea = MAX ( hgtMea , meaHgtAtTakeOff ) ;
}
2015-11-12 04:07:52 -04:00
} else {
fuseHgtData = false ;
}
// If we haven't fused height data for a while, then declare the height data as being timed out
// set timeout period based on whether we have vertical GPS velocity available to constrain drift
2018-10-03 23:43:13 -03:00
hgtRetryTime_ms = ( ( useGpsVertVel | | useExtNavVel ) & & ! velTimeout ) ? frontend - > hgtRetryTimeMode0_ms : frontend - > hgtRetryTimeMode12_ms ;
2015-11-12 04:07:52 -04:00
if ( imuSampleTime_ms - lastHgtPassTime_ms > hgtRetryTime_ms ) {
hgtTimeout = true ;
} else {
hgtTimeout = false ;
}
}