123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974 |
- #include <AP_HAL/AP_HAL.h>
- #include "AP_NavEKF2.h"
- #include "AP_NavEKF2_core.h"
- #include <AP_AHRS/AP_AHRS.h>
- #include <AP_Vehicle/AP_Vehicle.h>
- #include <AP_RangeFinder/RangeFinder_Backend.h>
- #include <AP_GPS/AP_GPS.h>
- #include <AP_Baro/AP_Baro.h>
- #include <stdio.h>
- extern const AP_HAL::HAL& hal;
- void NavEKF2_core::ResetVelocity(void)
- {
-
- velResetNE.x = stateStruct.velocity.x;
- velResetNE.y = stateStruct.velocity.y;
-
- zeroRows(P,3,4);
- zeroCols(P,3,4);
- if (PV_AidingMode != AID_ABSOLUTE) {
- stateStruct.velocity.zero();
-
- P[4][4] = P[3][3] = sq(frontend->_gpsHorizVelNoise);
- } else {
-
- if (imuSampleTime_ms - lastTimeGpsReceived_ms < 250) {
- stateStruct.velocity.x = gpsDataNew.vel.x;
- stateStruct.velocity.y = gpsDataNew.vel.y;
-
- P[4][4] = P[3][3] = sq(MAX(frontend->_gpsHorizVelNoise,gpsSpdAccuracy));
-
- velTimeout = false;
- lastVelPassTime_ms = imuSampleTime_ms;
- } else {
- stateStruct.velocity.x = 0.0f;
- stateStruct.velocity.y = 0.0f;
-
- P[4][4] = P[3][3] = sq(25.0f);
-
- velTimeout = false;
- lastVelPassTime_ms = imuSampleTime_ms;
- }
- }
- for (uint8_t i=0; i<imu_buffer_length; i++) {
- 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;
-
- velResetNE.x = stateStruct.velocity.x - velResetNE.x;
- velResetNE.y = stateStruct.velocity.y - velResetNE.y;
-
- lastVelReset_ms = imuSampleTime_ms;
- }
- void NavEKF2_core::ResetPosition(void)
- {
-
- posResetNE.x = stateStruct.position.x;
- posResetNE.y = stateStruct.position.y;
-
- zeroRows(P,6,7);
- zeroCols(P,6,7);
- if (PV_AidingMode != AID_ABSOLUTE) {
-
- stateStruct.position.x = lastKnownPositionNE.x;
- stateStruct.position.y = lastKnownPositionNE.y;
-
- P[6][6] = P[7][7] = sq(frontend->_gpsHorizPosNoise);
- } else {
-
- if (imuSampleTime_ms - lastTimeGpsReceived_ms < 250) {
-
- last_gps_idx = gpsDataNew.sensor_idx;
-
- stateStruct.position.x = gpsDataNew.pos.x + 0.001f*gpsDataNew.vel.x*(float(imuDataDelayed.time_ms) - float(gpsDataNew.time_ms));
- stateStruct.position.y = gpsDataNew.pos.y + 0.001f*gpsDataNew.vel.y*(float(imuDataDelayed.time_ms) - float(gpsDataNew.time_ms));
-
- P[6][6] = P[7][7] = sq(MAX(gpsPosAccuracy,frontend->_gpsHorizPosNoise));
-
- posTimeout = false;
- lastPosPassTime_ms = imuSampleTime_ms;
- } else if (imuSampleTime_ms - rngBcnLast3DmeasTime_ms < 250) {
-
- stateStruct.position.x = receiverPos.x;
- stateStruct.position.y = receiverPos.y;
-
- P[6][6] = receiverPosCov[0][0];
- P[7][7] = receiverPosCov[1][1];
-
- rngBcnTimeout = false;
- lastRngBcnPassTime_ms = imuSampleTime_ms;
- } else if (imuSampleTime_ms - extNavDataDelayed.time_ms < 250) {
-
- stateStruct.position.x = extNavDataDelayed.pos.x;
- stateStruct.position.y = extNavDataDelayed.pos.y;
-
- P[7][7] = P[6][6] = sq(extNavDataDelayed.posErr);
- }
- }
- for (uint8_t i=0; i<imu_buffer_length; i++) {
- 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;
-
- posResetNE.x = stateStruct.position.x - posResetNE.x;
- posResetNE.y = stateStruct.position.y - posResetNE.y;
-
- lastPosReset_ms = imuSampleTime_ms;
- }
- void NavEKF2_core::ResetHeight(void)
- {
-
- posResetD = stateStruct.position.z;
-
- stateStruct.position.z = -hgtMea;
- outputDataNew.position.z = stateStruct.position.z;
- outputDataDelayed.position.z = stateStruct.position.z;
-
- if (onGround) {
-
- terrainState = stateStruct.position.z + rngOnGnd;
- } else {
-
- terrainState = MAX(stateStruct.position.z + rngOnGnd , terrainState);
- }
- for (uint8_t i=0; i<imu_buffer_length; i++) {
- storedOutput[i].position.z = stateStruct.position.z;
- }
-
- posResetD = stateStruct.position.z - posResetD;
-
- lastPosResetD_ms = imuSampleTime_ms;
-
- hgtTimeout = false;
- lastHgtPassTime_ms = imuSampleTime_ms;
-
- zeroRows(P,8,8);
- zeroCols(P,8,8);
-
- P[8][8] = posDownObsNoise;
-
-
- if (inFlight && !gpsNotAvailable && frontend->_fusionModeGPS == 0 && !frontend->inhibitGpsVertVelUse) {
- stateStruct.velocity.z = gpsDataNew.vel.z;
- } else if (onGround) {
- stateStruct.velocity.z = 0.0f;
- }
- for (uint8_t i=0; i<imu_buffer_length; i++) {
- storedOutput[i].velocity.z = stateStruct.velocity.z;
- }
- outputDataNew.velocity.z = stateStruct.velocity.z;
- outputDataDelayed.velocity.z = stateStruct.velocity.z;
-
- zeroRows(P,5,5);
- zeroCols(P,5,5);
-
- P[5][5] = sq(frontend->_gpsVertVelNoise);
- }
- bool NavEKF2_core::resetHeightDatum(void)
- {
- if (activeHgtSource == HGT_SOURCE_RNG || !onGround) {
-
-
-
- return false;
- }
-
- float oldHgt = -stateStruct.position.z;
-
- AP::baro().update_calibration();
-
- stateStruct.position.z = 0.0f;
-
- if (validOrigin) {
- if (!gpsGoodToAlign) {
-
-
-
- EKF_origin.alt += (int32_t)(100.0f * oldHgt);
- } else {
-
-
-
-
- EKF_origin.alt = AP::gps().location().alt;
- }
- ekfGpsRefHgt = (double)0.01 * (double)EKF_origin.alt;
- }
-
-
- terrainState = 0;
- return true;
- }
- void NavEKF2_core::SelectVelPosFusion()
- {
-
-
-
- if (magFusePerformed && dtIMUavg < 0.005f && !posVelFusionDelayed) {
- posVelFusionDelayed = true;
- return;
- } else {
- posVelFusionDelayed = false;
- }
-
- extNavDataToFuse = storedExtNav.recall(extNavDataDelayed, imuDataDelayed.time_ms);
-
- readGpsData();
- gpsDataToFuse = storedGPS.recall(gpsDataDelayed,imuDataDelayed.time_ms);
-
- if (gpsDataToFuse && PV_AidingMode == AID_ABSOLUTE) {
-
- if (frontend->_fusionModeGPS <= 1) {
- fuseVelData = true;
- } else {
- fuseVelData = false;
- }
- fusePosData = true;
- extNavUsedForPos = false;
-
- Vector3f posOffsetBody = AP::gps().get_antenna_offset(gpsDataDelayed.sensor_idx) - accelPosOffset;
- if (!posOffsetBody.is_zero()) {
-
- if (fuseVelData) {
-
- Vector3f angRate = imuDataDelayed.delAng * (1.0f/imuDataDelayed.delAngDT);
- Vector3f velOffsetBody = angRate % posOffsetBody;
- Vector3f velOffsetEarth = prevTnb.mul_transpose(velOffsetBody);
- gpsDataDelayed.vel.x -= velOffsetEarth.x;
- gpsDataDelayed.vel.y -= velOffsetEarth.y;
- gpsDataDelayed.vel.z -= velOffsetEarth.z;
- }
- Vector3f posOffsetEarth = prevTnb.mul_transpose(posOffsetBody);
- gpsDataDelayed.pos.x -= posOffsetEarth.x;
- gpsDataDelayed.pos.y -= posOffsetEarth.y;
- gpsDataDelayed.hgt += posOffsetEarth.z;
- }
-
- 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;
- } else if (extNavDataToFuse && PV_AidingMode == AID_ABSOLUTE) {
-
- extNavUsedForPos = true;
- activeHgtSource = HGT_SOURCE_EV;
- fuseVelData = false;
- fuseHgtData = true;
- fusePosData = true;
- velPosObs[3] = extNavDataDelayed.pos.x;
- velPosObs[4] = extNavDataDelayed.pos.y;
- velPosObs[5] = extNavDataDelayed.pos.z;
-
- if (!use_compass()) {
- extNavUsedForYaw = true;
- if (!yawAlignComplete) {
- extNavYawResetRequest = true;
- magYawResetRequest = false;
- gpsYawResetRequest = false;
- controlMagYawReset();
- finalInflightYawInit = true;
- } else {
- fuseEulerYaw();
- }
- } else {
- extNavUsedForYaw = false;
- }
- } else {
- fuseVelData = false;
- fusePosData = false;
- }
-
- if (gpsYawResetRequest) {
- realignYawGPS();
- }
-
- selectHeightForFusion();
-
- if (gpsDataToFuse && PV_AidingMode == AID_ABSOLUTE && gpsDataDelayed.sensor_idx != last_gps_idx) {
-
- last_gps_idx = gpsDataDelayed.sensor_idx;
-
- posResetNE.x = stateStruct.position.x;
- posResetNE.y = stateStruct.position.y;
-
- stateStruct.position.x = gpsDataNew.pos.x;
- stateStruct.position.y = gpsDataNew.pos.y;
-
- posResetNE.x = stateStruct.position.x - posResetNE.x;
- posResetNE.y = stateStruct.position.y - posResetNE.y;
-
- 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;
-
- lastPosReset_ms = imuSampleTime_ms;
-
- if (activeHgtSource == HGT_SOURCE_GPS) {
-
- posResetD = stateStruct.position.z;
-
- stateStruct.position.z = -hgtMea;
-
- posResetD = stateStruct.position.z - posResetD;
-
- outputDataNew.position.z += posResetD;
- outputDataDelayed.position.z += posResetD;
- for (uint8_t i=0; i<imu_buffer_length; i++) {
- storedOutput[i].position.z += posResetD;
- }
-
- lastPosResetD_ms = imuSampleTime_ms;
- }
- }
-
-
-
- if (fuseHgtData && PV_AidingMode == AID_NONE) {
- velPosObs[3] = lastKnownPositionNE.x;
- velPosObs[4] = lastKnownPositionNE.y;
- fusePosData = true;
- fuseVelData = false;
- }
-
- if (fuseVelData || fusePosData || fuseHgtData) {
- FuseVelPosNED();
-
- fuseVelData = false;
- fuseHgtData = false;
- fusePosData = false;
- }
- }
- void NavEKF2_core::FuseVelPosNED()
- {
-
- hal.util->perf_begin(_perf_FuseVelPosNED);
-
- velHealth = false;
- posHealth = false;
- hgtHealth = false;
-
- Vector3f velInnov;
-
- bool fuseData[6] = {false,false,false,false,false,false};
- uint8_t stateIndex;
- uint8_t obsIndex;
-
- Vector6 R_OBS;
- Vector6 R_OBS_DATA_CHECKS;
- float SK;
-
-
-
-
-
-
- if (fuseVelData || fusePosData || fuseHgtData) {
-
- float posErr = frontend->gpsPosVarAccScale * accNavMag;
-
-
- if (PV_AidingMode == AID_NONE) {
- if (tiltAlignComplete && motorsArmed) {
-
- R_OBS[0] = sq(constrain_float(frontend->_noaidHorizNoise, 0.5f, 50.0f));
- } else {
-
- R_OBS[0] = sq(0.5f);
- }
- R_OBS[1] = R_OBS[0];
- R_OBS[2] = R_OBS[0];
- R_OBS[3] = R_OBS[0];
- R_OBS[4] = R_OBS[0];
- for (uint8_t i=0; i<=2; i++) R_OBS_DATA_CHECKS[i] = R_OBS[i];
- } else {
- if (gpsSpdAccuracy > 0.0f) {
-
- R_OBS[0] = sq(constrain_float(gpsSpdAccuracy, frontend->_gpsHorizVelNoise, 50.0f));
- R_OBS[2] = sq(constrain_float(gpsSpdAccuracy, frontend->_gpsVertVelNoise, 50.0f));
- } else {
-
- R_OBS[0] = sq(constrain_float(frontend->_gpsHorizVelNoise, 0.05f, 5.0f)) + sq(frontend->gpsNEVelVarAccScale * accNavMag);
- R_OBS[2] = sq(constrain_float(frontend->_gpsVertVelNoise, 0.05f, 5.0f)) + sq(frontend->gpsDVelVarAccScale * accNavMag);
- }
- R_OBS[1] = R_OBS[0];
-
- if (gpsPosAccuracy > 0.0f) {
- R_OBS[3] = sq(constrain_float(gpsPosAccuracy, frontend->_gpsHorizPosNoise, 100.0f));
- } else if (extNavUsedForPos) {
- R_OBS[3] = sq(constrain_float(extNavDataDelayed.posErr, 0.01f, 10.0f));
- } else {
- R_OBS[3] = sq(constrain_float(frontend->_gpsHorizPosNoise, 0.1f, 10.0f)) + sq(posErr);
- }
- R_OBS[4] = R_OBS[3];
-
-
-
- for (uint8_t i=0; i<=2; i++) R_OBS_DATA_CHECKS[i] = sq(constrain_float(frontend->_gpsHorizVelNoise, 0.05f, 5.0f)) + sq(frontend->gpsNEVelVarAccScale * accNavMag);
- }
- R_OBS[5] = posDownObsNoise;
- for (uint8_t i=3; i<=5; i++) R_OBS_DATA_CHECKS[i] = R_OBS[i];
-
-
-
- if (useGpsVertVel && fuseVelData && (frontend->_altSource != 2)) {
-
- float hgtErr = stateStruct.position.z - velPosObs[5];
- float velDErr = stateStruct.velocity.z - velPosObs[2];
-
- 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;
- }
- }
-
-
- if (fusePosData) {
-
- innovVelPos[3] = stateStruct.position.x - velPosObs[3];
- innovVelPos[4] = stateStruct.position.y - velPosObs[4];
- varInnovVelPos[3] = P[6][6] + R_OBS_DATA_CHECKS[3];
- varInnovVelPos[4] = P[7][7] + R_OBS_DATA_CHECKS[4];
-
- float maxPosInnov2 = sq(MAX(0.01f * (float)frontend->_gpsPosInnovGate, 1.0f))*(varInnovVelPos[3] + varInnovVelPos[4]);
- posTestRatio = (sq(innovVelPos[3]) + sq(innovVelPos[4])) / maxPosInnov2;
- posHealth = ((posTestRatio < 1.0f) || badIMUdata);
-
- if (PV_AidingMode == AID_NONE) {
- posHealth = true;
- lastPosPassTime_ms = imuSampleTime_ms;
- } else if (posHealth || posTimeout) {
- posHealth = true;
- lastPosPassTime_ms = imuSampleTime_ms;
-
- if (posTimeout || ((P[6][6] + P[7][7]) > sq(float(frontend->_gpsGlitchRadiusMax)))) {
-
- ResetPosition();
-
- ResetVelocity();
-
- fusePosData = false;
- fuseVelData = false;
-
- zeroRows(P,6,7);
- zeroCols(P,6,7);
- P[6][6] = sq(float(0.5f*frontend->_gpsGlitchRadiusMax));
- P[7][7] = P[6][6];
-
- posTestRatio = 0.0f;
- velTestRatio = 0.0f;
- }
- } else {
- posHealth = false;
- }
- }
-
- if (fuseVelData) {
-
- uint8_t imax = 2;
-
- if (frontend->_fusionModeGPS > 0 || PV_AidingMode != AID_ABSOLUTE || frontend->inhibitGpsVertVelUse) {
- imax = 1;
- }
- float innovVelSumSq = 0;
- float varVelSum = 0;
- for (uint8_t i = 0; i<=imax; i++) {
-
- stateIndex = i + 3;
-
- velInnov[i] = stateStruct.velocity[i] - velPosObs[i];
-
- varInnovVelPos[i] = P[stateIndex][stateIndex] + R_OBS_DATA_CHECKS[i];
-
- innovVelSumSq += sq(velInnov[i]);
- varVelSum += varInnovVelPos[i];
- }
-
-
- velTestRatio = innovVelSumSq / (varVelSum * sq(MAX(0.01f * (float)frontend->_gpsVelInnovGate, 1.0f)));
-
- velHealth = ((velTestRatio < 1.0f) || badIMUdata);
-
- if (velHealth || velTimeout) {
- velHealth = true;
-
- lastVelPassTime_ms = imuSampleTime_ms;
-
- if (PV_AidingMode == AID_ABSOLUTE && velTimeout) {
-
- ResetVelocity();
-
- fuseVelData = false;
-
- velTestRatio = 0.0f;
- }
- } else {
- velHealth = false;
- }
- }
-
- if (fuseHgtData) {
-
- innovVelPos[5] = stateStruct.position.z - velPosObs[5];
- varInnovVelPos[5] = P[8][8] + R_OBS_DATA_CHECKS[5];
-
- hgtTestRatio = sq(innovVelPos[5]) / (sq(MAX(0.01f * (float)frontend->_hgtInnovGate, 1.0f)) * varInnovVelPos[5]);
-
-
-
- const float maxTestRatio = (PV_AidingMode == AID_NONE && onGround)? 3.0 : 1.0;
-
- hgtHealth = (hgtTestRatio < maxTestRatio) || badIMUdata;
-
- if (hgtHealth || hgtTimeout) {
-
-
- if (onGround) {
- float dtBaro = (imuSampleTime_ms - lastHgtPassTime_ms)*1.0e-3f;
- const float hgtInnovFiltTC = 2.0f;
- float alpha = constrain_float(dtBaro/(dtBaro+hgtInnovFiltTC),0.0f,1.0f);
- hgtInnovFiltState += (innovVelPos[5]-hgtInnovFiltState)*alpha;
- } else {
- hgtInnovFiltState = 0.0f;
- }
-
- if (hgtTimeout) {
- ResetHeight();
- }
-
- hgtHealth = true;
- lastHgtPassTime_ms = imuSampleTime_ms;
- }
- }
-
- if (fuseVelData && velHealth) {
- fuseData[0] = true;
- fuseData[1] = true;
- if (useGpsVertVel) {
- fuseData[2] = true;
- }
- tiltErrVec.zero();
- }
- if (fusePosData && posHealth) {
- fuseData[3] = true;
- fuseData[4] = true;
- tiltErrVec.zero();
- }
- if (fuseHgtData && hgtHealth) {
- fuseData[5] = true;
- }
-
- for (obsIndex=0; obsIndex<=5; obsIndex++) {
- if (fuseData[obsIndex]) {
- stateIndex = 3 + obsIndex;
-
-
- if (obsIndex <= 2)
- {
- innovVelPos[obsIndex] = stateStruct.velocity[obsIndex] - velPosObs[obsIndex];
- R_OBS[obsIndex] *= sq(gpsNoiseScaler);
- }
- else if (obsIndex == 3 || obsIndex == 4) {
- innovVelPos[obsIndex] = stateStruct.position[obsIndex-3] - velPosObs[obsIndex];
- R_OBS[obsIndex] *= sq(gpsNoiseScaler);
- } else if (obsIndex == 5) {
- innovVelPos[obsIndex] = stateStruct.position[obsIndex-3] - velPosObs[obsIndex];
- const float gndMaxBaroErr = 4.0f;
- const float gndBaroInnovFloor = -0.5f;
- if(getTouchdownExpected() && activeHgtSource == HGT_SOURCE_BARO) {
-
-
-
-
-
-
-
-
- innovVelPos[5] += constrain_float(-innovVelPos[5]+gndBaroInnovFloor, 0.0f, gndBaroInnovFloor+gndMaxBaroErr);
- }
- }
-
- 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;
- }
-
- 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;
- }
- }
-
- if (!inhibitWindStates) {
- Kfusion[22] = P[22][stateIndex]*SK;
- Kfusion[23] = P[23][stateIndex]*SK;
- } else {
- Kfusion[22] = 0.0f;
- Kfusion[23] = 0.0f;
- }
-
-
- for (uint8_t i= 0; i<=stateIndexLim; i++) {
- for (uint8_t j= 0; j<=stateIndexLim; j++)
- {
- KHP[i][j] = Kfusion[i] * P[stateIndex][j];
- }
- }
-
- bool healthyFusion = true;
- for (uint8_t i= 0; i<=stateIndexLim; i++) {
- if (KHP[i][i] > P[i][i]) {
- healthyFusion = false;
- }
- }
- if (healthyFusion) {
-
- 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];
- }
- }
-
- ForceSymmetry();
- ConstrainVariances();
-
-
- stateStruct.angErr.zero();
-
- for (uint8_t i = 0; i<=stateIndexLim; i++) {
- statesArray[i] = statesArray[i] - Kfusion[i] * innovVelPos[obsIndex];
- }
-
-
- stateStruct.quat.rotate(stateStruct.angErr);
-
-
- if (obsIndex != 5) {
- tiltErrVec += stateStruct.angErr;
- }
-
- 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 {
-
- 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;
- }
- }
- }
- }
- }
-
- hal.util->perf_end(_perf_FuseVelPosNED);
- }
- void NavEKF2_core::selectHeightForFusion()
- {
-
-
- readRangeFinder();
- rangeDataToFuse = storedRange.recall(rangeDataDelayed,imuDataDelayed.time_ms);
-
-
-
- if (rangeDataToFuse) {
- AP_RangeFinder_Backend *sensor = frontend->_rng.get_backend(rangeDataDelayed.sensor_idx);
- if (sensor != nullptr) {
- Vector3f posOffsetBody = sensor->get_pos_offset() - accelPosOffset;
- if (!posOffsetBody.is_zero()) {
- Vector3f posOffsetEarth = prevTnb.mul_transpose(posOffsetBody);
- rangeDataDelayed.rng += posOffsetEarth.z / prevTnb.c.z;
- }
- }
- }
-
- readBaroData();
- baroDataToFuse = storedBaro.recall(baroDataDelayed, imuDataDelayed.time_ms);
-
- if (extNavUsedForPos) {
-
- activeHgtSource = HGT_SOURCE_EV;
- } else if (((frontend->_useRngSwHgt > 0) && (frontend->_altSource == 1)) && (imuSampleTime_ms - rngValidMeaTime_ms < 500)) {
- if (frontend->_altSource == 1) {
-
- activeHgtSource = HGT_SOURCE_RNG;
- } else {
-
- float rangeMaxUse = 1e-4f * (float)frontend->_rng.max_distance_cm_orient(ROTATION_PITCH_270) * (float)frontend->_useRngSwHgt;
- bool aboveUpperSwHgt = (terrainState - stateStruct.position.z) > rangeMaxUse;
- bool belowLowerSwHgt = (terrainState - stateStruct.position.z) < 0.7f * rangeMaxUse;
-
-
-
- float horizSpeed = norm(stateStruct.velocity.x, stateStruct.velocity.y);
- bool dontTrustTerrain = ((horizSpeed > frontend->_useRngSwSpd) && filterStatus.flags.horiz_vel) || !terrainHgtStable;
- float trust_spd_trigger = MAX((frontend->_useRngSwSpd - 1.0f),(frontend->_useRngSwSpd * 0.5f));
- bool trustTerrain = (horizSpeed < trust_spd_trigger) && terrainHgtStable;
-
- if ((aboveUpperSwHgt || dontTrustTerrain) && (activeHgtSource == HGT_SOURCE_RNG)) {
-
- if (frontend->_altSource == 0) {
- activeHgtSource = HGT_SOURCE_BARO;
- } else if (frontend->_altSource == 2) {
- activeHgtSource = HGT_SOURCE_GPS;
- }
- } else if (belowLowerSwHgt && trustTerrain && (activeHgtSource != HGT_SOURCE_RNG)) {
-
- activeHgtSource = HGT_SOURCE_RNG;
- }
- }
- } else if ((frontend->_altSource == 2) && ((imuSampleTime_ms - lastTimeGpsReceived_ms) < 500) && validOrigin && gpsAccuracyGood) {
- activeHgtSource = HGT_SOURCE_GPS;
- } else if ((frontend->_altSource == 3) && validOrigin && rngBcnGoodToAlign) {
- activeHgtSource = HGT_SOURCE_BCN;
- } else {
- activeHgtSource = HGT_SOURCE_BARO;
- }
-
- bool lostRngHgt = ((activeHgtSource == HGT_SOURCE_RNG) && ((imuSampleTime_ms - rngValidMeaTime_ms) > 500));
- bool lostGpsHgt = ((activeHgtSource == HGT_SOURCE_GPS) && ((imuSampleTime_ms - lastTimeGpsReceived_ms) > 2000));
- bool lostExtNavHgt = ((activeHgtSource == HGT_SOURCE_EV) && ((imuSampleTime_ms - extNavMeasTime_ms) > 2000));
- if (lostRngHgt || lostGpsHgt || lostExtNavHgt) {
- activeHgtSource = HGT_SOURCE_BARO;
- }
-
- if (baroDataToFuse) {
-
- if (activeHgtSource != HGT_SOURCE_BARO) {
- calcFiltBaroOffset();
- }
-
-
- if (!getTakeoffExpected()) {
- const float gndHgtFiltTC = 0.5f;
- const float dtBaro = frontend->hgtAvg_ms*1.0e-3f;
- float alpha = constrain_float(dtBaro / (dtBaro+gndHgtFiltTC),0.0f,1.0f);
- meaHgtAtTakeOff += (baroDataDelayed.hgt-meaHgtAtTakeOff)*alpha;
- }
- }
-
-
-
- if (gpsDataToFuse &&
- (((frontend->_originHgtMode & (1 << 0)) && (activeHgtSource == HGT_SOURCE_BARO)) ||
- ((frontend->_originHgtMode & (1 << 1)) && (activeHgtSource == HGT_SOURCE_RNG)))
- ) {
- correctEkfOriginHeight();
- }
-
- if (extNavDataToFuse && (activeHgtSource == HGT_SOURCE_EV)) {
- hgtMea = -extNavDataDelayed.pos.z;
- posDownObsNoise = sq(constrain_float(extNavDataDelayed.posErr, 0.01f, 10.0f));
- } else if (rangeDataToFuse && (activeHgtSource == HGT_SOURCE_RNG)) {
-
-
- if (prevTnb.c.z >= 0.7) {
-
- hgtMea = MAX(rangeDataDelayed.rng * prevTnb.c.z, rngOnGnd);
-
- hgtMea -= terrainState;
-
- fuseHgtData = true;
- velPosObs[5] = -hgtMea;
-
- posDownObsNoise = sq(constrain_float(frontend->_rngNoise, 0.1f, 10.0f));
-
- posDownObsNoise += sq(rangeDataDelayed.rng * frontend->_terrGradMax) * MAX(0.0f , (1.0f - sq(prevTnb.c.z)));
- } else {
-
- fuseHgtData = false;
- }
- } else if (gpsDataToFuse && (activeHgtSource == HGT_SOURCE_GPS)) {
-
- hgtMea = gpsDataDelayed.hgt;
-
- velPosObs[5] = -hgtMea;
- fuseHgtData = true;
-
- if (gpsHgtAccuracy > 0.0f) {
- posDownObsNoise = sq(constrain_float(gpsHgtAccuracy, 1.5f * frontend->_gpsHorizPosNoise, 100.0f));
- } else {
- posDownObsNoise = sq(constrain_float(1.5f * frontend->_gpsHorizPosNoise, 0.1f, 10.0f));
- }
- } else if (baroDataToFuse && (activeHgtSource == HGT_SOURCE_BARO)) {
-
- hgtMea = baroDataDelayed.hgt - baroHgtOffset;
-
- velPosObs[5] = -hgtMea;
- fuseHgtData = true;
-
- posDownObsNoise = sq(constrain_float(frontend->_baroAltNoise, 0.1f, 10.0f));
-
- if (getTakeoffExpected() || getTouchdownExpected()) {
- posDownObsNoise *= frontend->gndEffectBaroScaler;
- }
-
-
- if (motorsArmed && getTakeoffExpected()) {
- hgtMea = MAX(hgtMea, meaHgtAtTakeOff);
- }
- } else {
- fuseHgtData = false;
- }
-
-
- hgtRetryTime_ms = (useGpsVertVel && !velTimeout) ? frontend->hgtRetryTimeMode0_ms : frontend->hgtRetryTimeMode12_ms;
- if (imuSampleTime_ms - lastHgtPassTime_ms > hgtRetryTime_ms) {
- hgtTimeout = true;
- } else {
- hgtTimeout = false;
- }
- }
|