1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495969798991001011021031041051061071081091101111121131141151161171181191201211221231241251261271281291301311321331341351361371381391401411421431441451461471481491501511521531541551561571581591601611621631641651661671681691701711721731741751761771781791801811821831841851861871881891901911921931941951961971981992002012022032042052062072082092102112122132142152162172182192202212222232242252262272282292302312322332342352362372382392402412422432442452462472482492502512522532542552562572582592602612622632642652662672682692702712722732742752762772782792802812822832842852862872882892902912922932942952962972982993003013023033043053063073083093103113123133143153163173183193203213223233243253263273283293303313323333343353363373383393403413423433443453463473483493503513523533543553563573583593603613623633643653663673683693703713723733743753763773783793803813823833843853863873883893903913923933943953963973983994004014024034044054064074084094104114124134144154164174184194204214224234244254264274284294304314324334344354364374384394404414424434444454464474484494504514524534544554564574584594604614624634644654664674684694704714724734744754764774784794804814824834844854864874884894904914924934944954964974984995005015025035045055065075085095105115125135145155165175185195205215225235245255265275285295305315325335345355365375385395405415425435445455465475485495505515525535545555565575585595605615625635645655665675685695705715725735745755765775785795805815825835845855865875885895905915925935945955965975985996006016026036046056066076086096106116126136146156166176186196206216226236246256266276286296306316326336346356366376386396406416426436446456466476486496506516526536546556566576586596606616626636646656666676686696706716726736746756766776786796806816826836846856866876886896906916926936946956966976986997007017027037047057067077087097107117127137147157167177187197207217227237247257267277287297307317327337347357367377387397407417427437447457467477487497507517527537547557567577587597607617627637647657667677687697707717727737747757767777787797807817827837847857867877887897907917927937947957967977987998008018028038048058068078088098108118128138148158168178188198208218228238248258268278288298308318328338348358368378388398408418428438448458468478488498508518528538548558568578588598608618628638648658668678688698708718728738748758768778788798808818828838848858868878888898908918928938948958968978988999009019029039049059069079089099109119129139149159169179189199209219229239249259269279289299309319329339349359369379389399409419429439449459469479489499509519529539549559569579589599609619629639649659669679689699709719729739749759769779789799809819829839849859869879889899909919929939949959969979989991000100110021003 |
- #include <AP_HAL/AP_HAL.h>
- #include "AP_NavEKF3.h"
- #include "AP_NavEKF3_core.h"
- #include <AP_AHRS/AP_AHRS.h>
- #include <AP_Vehicle/AP_Vehicle.h>
- #include <GCS_MAVLink/GCS.h>
- #include <AP_RangeFinder/RangeFinder_Backend.h>
- #include <AP_GPS/AP_GPS.h>
- #include <AP_Baro/AP_Baro.h>
- extern const AP_HAL::HAL& hal;
- void NavEKF3_core::readRangeFinder(void)
- {
- uint8_t midIndex;
- uint8_t maxIndex;
- uint8_t minIndex;
-
-
- rngOnGnd = MAX(frontend->_rng.ground_clearance_cm_orient(ROTATION_PITCH_270) * 0.01f, 0.05f);
-
- if ((imuSampleTime_ms - lastRngMeasTime_ms) > frontend->sensorIntervalMin_ms) {
-
- lastRngMeasTime_ms = imuSampleTime_ms;
-
-
- for (uint8_t sensorIndex = 0; sensorIndex <= 1; sensorIndex++) {
- AP_RangeFinder_Backend *sensor = frontend->_rng.get_backend(sensorIndex);
- if (sensor == nullptr) {
- continue;
- }
- if ((sensor->orientation() == ROTATION_PITCH_270) && (sensor->status() == RangeFinder::RangeFinder_Good)) {
- rngMeasIndex[sensorIndex] ++;
- if (rngMeasIndex[sensorIndex] > 2) {
- rngMeasIndex[sensorIndex] = 0;
- }
- storedRngMeasTime_ms[sensorIndex][rngMeasIndex[sensorIndex]] = imuSampleTime_ms - 25;
- storedRngMeas[sensorIndex][rngMeasIndex[sensorIndex]] = sensor->distance_cm() * 0.01f;
- }
-
- bool sampleFresh[2][3] = {};
- for (uint8_t index = 0; index <= 2; index++) {
- sampleFresh[sensorIndex][index] = (imuSampleTime_ms - storedRngMeasTime_ms[sensorIndex][index]) < 500;
- }
-
- if (sampleFresh[sensorIndex][0] && sampleFresh[sensorIndex][1] && sampleFresh[sensorIndex][2]) {
- if (storedRngMeas[sensorIndex][0] > storedRngMeas[sensorIndex][1]) {
- minIndex = 1;
- maxIndex = 0;
- } else {
- minIndex = 0;
- maxIndex = 1;
- }
- if (storedRngMeas[sensorIndex][2] > storedRngMeas[sensorIndex][maxIndex]) {
- midIndex = maxIndex;
- } else if (storedRngMeas[sensorIndex][2] < storedRngMeas[sensorIndex][minIndex]) {
- midIndex = minIndex;
- } else {
- midIndex = 2;
- }
-
- if (storedRngMeasTime_ms[sensorIndex][midIndex] > rangeDataNew.time_ms) {
- rangeDataNew.time_ms = storedRngMeasTime_ms[sensorIndex][midIndex];
- }
-
- rangeDataNew.rng = MAX(storedRngMeas[sensorIndex][midIndex],rngOnGnd);
-
- rangeDataNew.sensor_idx = sensorIndex;
-
- storedRange.push(rangeDataNew);
-
- rngValidMeaTime_ms = imuSampleTime_ms;
- } else if (!takeOffDetected && ((imuSampleTime_ms - rngValidMeaTime_ms) > 200)) {
-
- rangeDataNew.time_ms = imuSampleTime_ms;
- rangeDataNew.rng = rngOnGnd;
- rangeDataNew.time_ms = imuSampleTime_ms;
-
- if (imuSampleTime_ms > rangeDataNew.time_ms) {
- rangeDataNew.time_ms = imuSampleTime_ms;
- }
-
- storedRange.push(rangeDataNew);
-
- rngValidMeaTime_ms = imuSampleTime_ms;
- }
- }
- }
- }
- void NavEKF3_core::writeBodyFrameOdom(float quality, const Vector3f &delPos, const Vector3f &delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset)
- {
-
-
- if (((timeStamp_ms - bodyOdmMeasTime_ms) < frontend->sensorIntervalMin_ms) || (delTime < dtEkfAvg) || !statesInitialised) {
- return;
- }
- bodyOdmDataNew.body_offset = &posOffset;
- bodyOdmDataNew.vel = delPos * (1.0f/delTime);
- bodyOdmDataNew.time_ms = timeStamp_ms;
- bodyOdmDataNew.angRate = delAng * (1.0f/delTime);
- bodyOdmMeasTime_ms = timeStamp_ms;
-
-
- bodyOdmDataNew.velErr = frontend->_visOdmVelErrMin + (frontend->_visOdmVelErrMax - frontend->_visOdmVelErrMin) * (1.0f - 0.01f * quality);
- storedBodyOdm.push(bodyOdmDataNew);
- }
- void NavEKF3_core::writeWheelOdom(float delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset, float radius)
- {
-
-
-
-
-
- if (((timeStamp_ms - wheelOdmMeasTime_ms) < frontend->sensorIntervalMin_ms) || (delTime < dtEkfAvg) || !statesInitialised) {
- return;
- }
- wheelOdmDataNew.hub_offset = &posOffset;
- wheelOdmDataNew.delAng = delAng;
- wheelOdmDataNew.radius = radius;
- wheelOdmDataNew.delTime = delTime;
- wheelOdmMeasTime_ms = timeStamp_ms;
-
-
- wheelOdmDataNew.time_ms = timeStamp_ms - (uint32_t)(500.0f * delTime);
- storedWheelOdm.push(wheelOdmDataNew);
- }
- void NavEKF3_core::writeOptFlowMeas(const uint8_t rawFlowQuality, const Vector2f &rawFlowRates, const Vector2f &rawGyroRates, const uint32_t msecFlowMeas, const Vector3f &posOffset)
- {
-
- if ((imuSampleTime_ms - flowMeaTime_ms) < frontend->sensorIntervalMin_ms) {
- return;
- }
-
-
-
-
-
-
- flowMeaTime_ms = imuSampleTime_ms;
-
-
-
- if (delTimeOF > 0.01f) {
- flowGyroBias.x = 0.99f * flowGyroBias.x + 0.01f * constrain_float((rawGyroRates.x - delAngBodyOF.x/delTimeOF),-0.1f,0.1f);
- flowGyroBias.y = 0.99f * flowGyroBias.y + 0.01f * constrain_float((rawGyroRates.y - delAngBodyOF.y/delTimeOF),-0.1f,0.1f);
- delAngBodyOF.zero();
- delTimeOF = 0.0f;
- }
-
-
- detectOptFlowTakeoff();
-
- stateStruct.quat.rotation_matrix(Tbn_flow);
-
- if ((rawFlowQuality > 0) && rawFlowRates.length() < 4.2f && rawGyroRates.length() < 4.2f) {
-
- ofDataNew.bodyRadXYZ.x = rawGyroRates.x - flowGyroBias.x;
- ofDataNew.bodyRadXYZ.y = rawGyroRates.y - flowGyroBias.y;
-
- if (delTimeOF > 0.001f) {
-
- ofDataNew.bodyRadXYZ.z = delAngBodyOF.z / delTimeOF;
- } else if (imuDataNew.delAngDT > 0.001f){
-
- ofDataNew.bodyRadXYZ.z = imuDataNew.delAng.z / imuDataNew.delAngDT;
- } else {
-
- ofDataNew.bodyRadXYZ.z = 0.0f;
- }
-
-
- ofDataNew.flowRadXY = - rawFlowRates;
-
- ofDataNew.body_offset = &posOffset;
-
- ofDataNew.flowRadXYcomp.x = ofDataNew.flowRadXY.x + ofDataNew.bodyRadXYZ.x;
- ofDataNew.flowRadXYcomp.y = ofDataNew.flowRadXY.y + ofDataNew.bodyRadXYZ.y;
-
- flowValidMeaTime_ms = imuSampleTime_ms;
-
- ofDataNew.time_ms = imuSampleTime_ms - frontend->_flowDelay_ms - frontend->flowTimeDeltaAvg_ms/2;
-
- ofDataNew.time_ms -= localFilterTimeStep_ms/2;
-
- ofDataNew.time_ms = MAX(ofDataNew.time_ms,imuDataDelayed.time_ms);
-
- storedOF.push(ofDataNew);
- }
- }
- void NavEKF3_core::readMagData()
- {
- if (!_ahrs->get_compass()) {
- allMagSensorsFailed = true;
- return;
- }
-
-
- uint8_t maxCount = _ahrs->get_compass()->get_count();
- if (allMagSensorsFailed || (magTimeout && assume_zero_sideslip() && magSelectIndex >= maxCount-1 && inFlight)) {
- allMagSensorsFailed = true;
- return;
- }
- if (_ahrs->get_compass()->learn_offsets_enabled()) {
-
- InitialiseVariablesMag();
- wasLearningCompass_ms = imuSampleTime_ms;
- } else if (wasLearningCompass_ms != 0 && imuSampleTime_ms - wasLearningCompass_ms > 1000) {
- wasLearningCompass_ms = 0;
-
-
- yawAlignComplete = false;
- InitialiseVariablesMag();
- }
-
-
- if (use_compass() && ((_ahrs->get_compass()->last_update_usec() - lastMagUpdate_us) > 1000 * frontend->sensorIntervalMin_ms)) {
- frontend->logging.log_compass = true;
-
-
-
- if (magTimeout && (maxCount > 1) && !onGround && imuSampleTime_ms - ekfStartTime_ms > 30000) {
-
- for (uint8_t i=1; i<maxCount; i++) {
- uint8_t tempIndex = magSelectIndex + i;
-
- if (tempIndex >= maxCount) {
- tempIndex -= maxCount;
- }
-
- if (_ahrs->get_compass()->use_for_yaw(tempIndex) && tempIndex != magSelectIndex) {
- magSelectIndex = tempIndex;
- gcs().send_text(MAV_SEVERITY_INFO, "EKF3 IMU%u switching to compass %u",(unsigned)imu_index,magSelectIndex);
-
- magTimeout = false;
- lastHealthyMagTime_ms = imuSampleTime_ms;
-
- stateStruct.body_magfield.zero();
-
- storedMag.reset();
-
- magDataToFuse = false;
-
- magStateResetRequest = true;
-
- magFieldLearned = false;
- break;
- }
- }
- }
-
- Vector3f nowMagOffsets = _ahrs->get_compass()->get_offsets(magSelectIndex);
- bool changeDetected = lastMagOffsetsValid && (nowMagOffsets != lastMagOffsets);
- if (changeDetected) {
-
- stateStruct.body_magfield.zero();
-
- storedMag.reset();
- }
- lastMagOffsets = nowMagOffsets;
- lastMagOffsetsValid = true;
-
- lastMagUpdate_us = _ahrs->get_compass()->last_update_usec(magSelectIndex);
-
- magDataNew.time_ms = imuSampleTime_ms - frontend->magDelay_ms;
-
- magDataNew.time_ms -= localFilterTimeStep_ms/2;
-
- magDataNew.mag = _ahrs->get_compass()->get_field(magSelectIndex) * 0.001f;
-
- consistentMagData = _ahrs->get_compass()->consistent();
-
- storedMag.push(magDataNew);
- }
- }
- void NavEKF3_core::readIMUData()
- {
- const AP_InertialSensor &ins = AP::ins();
-
- dtIMUavg = 0.02f * constrain_float(ins.get_loop_delta_t(),0.5f * dtIMUavg, 2.0f * dtIMUavg) + 0.98f * dtIMUavg;
-
- imuSampleTime_ms = frontend->imuSampleTime_us / 1000;
- uint8_t accel_active, gyro_active;
- if (ins.use_accel(imu_index)) {
- accel_active = imu_index;
- } else {
- accel_active = ins.get_primary_accel();
- }
- if (ins.use_gyro(imu_index)) {
- gyro_active = imu_index;
- } else {
- gyro_active = ins.get_primary_gyro();
- }
- if (gyro_active != gyro_index_active) {
-
-
-
-
- stateStruct.gyro_bias = inactiveBias[gyro_active].gyro_bias;
- gyro_index_active = gyro_active;
- }
- if (accel_active != accel_index_active) {
-
- stateStruct.accel_bias = inactiveBias[accel_active].accel_bias;
- accel_index_active = accel_active;
- }
-
- learnInactiveBiases();
- readDeltaVelocity(accel_index_active, imuDataNew.delVel, imuDataNew.delVelDT);
- accelPosOffset = ins.get_imu_pos_offset(accel_index_active);
- imuDataNew.accel_index = accel_index_active;
-
-
- readDeltaAngle(gyro_index_active, imuDataNew.delAng);
- imuDataNew.delAngDT = MAX(ins.get_delta_angle_dt(gyro_index_active),1.0e-4f);
- imuDataNew.gyro_index = gyro_index_active;
-
- imuDataNew.time_ms = imuSampleTime_ms;
-
- imuDataDownSampledNew.delAngDT += imuDataNew.delAngDT;
- imuDataDownSampledNew.delVelDT += imuDataNew.delVelDT;
-
-
-
- imuDataDownSampledNew.gyro_index = imuDataNew.gyro_index;
- imuDataDownSampledNew.accel_index = imuDataNew.accel_index;
-
-
- imuQuatDownSampleNew.rotate(imuDataNew.delAng);
- imuQuatDownSampleNew.normalize();
-
- Matrix3f deltaRotMat;
- imuQuatDownSampleNew.rotation_matrix(deltaRotMat);
-
- imuDataDownSampledNew.delVel += deltaRotMat*imuDataNew.delVel;
-
- framesSincePredict++;
-
- if ((imuDataDownSampledNew.delAngDT >= (EKF_TARGET_DT-(dtIMUavg*0.5f)) && startPredictEnabled) ||
- (imuDataDownSampledNew.delAngDT >= 2.0f*EKF_TARGET_DT)) {
-
- imuQuatDownSampleNew.to_axis_angle(imuDataDownSampledNew.delAng);
-
- imuDataDownSampledNew.time_ms = imuSampleTime_ms;
-
- storedIMU.push_youngest_element(imuDataDownSampledNew);
-
- float dtNow = constrain_float(0.5f*(imuDataDownSampledNew.delAngDT+imuDataDownSampledNew.delVelDT),0.5f * dtEkfAvg, 2.0f * dtEkfAvg);
- dtEkfAvg = 0.98f * dtEkfAvg + 0.02f * dtNow;
-
- imuDataDownSampledNew.delAng.zero();
- imuDataDownSampledNew.delVel.zero();
- imuDataDownSampledNew.delAngDT = 0.0f;
- imuDataDownSampledNew.delVelDT = 0.0f;
- imuQuatDownSampleNew[0] = 1.0f;
- imuQuatDownSampleNew[3] = imuQuatDownSampleNew[2] = imuQuatDownSampleNew[1] = 0.0f;
-
- framesSincePredict = 0;
-
- runUpdates = true;
-
- imuDataDelayed = storedIMU.pop_oldest_element();
-
- float minDT = 0.1f * dtEkfAvg;
- imuDataDelayed.delAngDT = MAX(imuDataDelayed.delAngDT,minDT);
- imuDataDelayed.delVelDT = MAX(imuDataDelayed.delVelDT,minDT);
- updateTimingStatistics();
-
-
- delAngCorrected = imuDataDelayed.delAng;
- delVelCorrected = imuDataDelayed.delVel;
- correctDeltaAngle(delAngCorrected, imuDataDelayed.delAngDT, imuDataDelayed.gyro_index);
- correctDeltaVelocity(delVelCorrected, imuDataDelayed.delVelDT, imuDataDelayed.accel_index);
- } else {
-
- runUpdates = false;
- }
- }
- bool NavEKF3_core::readDeltaVelocity(uint8_t ins_index, Vector3f &dVel, float &dVel_dt) {
- const AP_InertialSensor &ins = AP::ins();
- if (ins_index < ins.get_accel_count()) {
- ins.get_delta_velocity(ins_index,dVel);
- dVel_dt = MAX(ins.get_delta_velocity_dt(ins_index),1.0e-4f);
- return true;
- }
- return false;
- }
- void NavEKF3_core::readGpsData()
- {
-
-
- const AP_GPS &gps = AP::gps();
- if (gps.last_message_time_ms() - lastTimeGpsReceived_ms > frontend->sensorIntervalMin_ms) {
- if (gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
-
- gpsCheckStatus.bad_fix = false;
-
- secondLastGpsTime_ms = lastTimeGpsReceived_ms;
-
- lastTimeGpsReceived_ms = gps.last_message_time_ms();
-
-
-
- float gps_delay_sec = 0;
- gps.get_lag(gps_delay_sec);
- gpsDataNew.time_ms = lastTimeGpsReceived_ms - (uint32_t)(gps_delay_sec * 1000.0f);
-
- gpsDataNew.time_ms -= localFilterTimeStep_ms/2;
-
- gpsDataNew.time_ms = MIN(MAX(gpsDataNew.time_ms,imuDataDelayed.time_ms),imuDataDownSampledNew.time_ms);
-
- gpsDataNew.sensor_idx = gps.primary_sensor();
-
- gpsDataNew.vel = gps.velocity();
-
-
- float alpha = constrain_float(0.0002f * (lastTimeGpsReceived_ms - secondLastGpsTime_ms),0.0f,1.0f);
- gpsSpdAccuracy *= (1.0f - alpha);
- float gpsSpdAccRaw;
- if (!gps.speed_accuracy(gpsSpdAccRaw)) {
- gpsSpdAccuracy = 0.0f;
- } else {
- gpsSpdAccuracy = MAX(gpsSpdAccuracy,gpsSpdAccRaw);
- gpsSpdAccuracy = MIN(gpsSpdAccuracy,50.0f);
- }
- gpsPosAccuracy *= (1.0f - alpha);
- float gpsPosAccRaw;
- if (!gps.horizontal_accuracy(gpsPosAccRaw)) {
- gpsPosAccuracy = 0.0f;
- } else {
- gpsPosAccuracy = MAX(gpsPosAccuracy,gpsPosAccRaw);
- gpsPosAccuracy = MIN(gpsPosAccuracy,100.0f);
- }
- gpsHgtAccuracy *= (1.0f - alpha);
- float gpsHgtAccRaw;
- if (!gps.vertical_accuracy(gpsHgtAccRaw)) {
- gpsHgtAccuracy = 0.0f;
- } else {
- gpsHgtAccuracy = MAX(gpsHgtAccuracy,gpsHgtAccRaw);
- gpsHgtAccuracy = MIN(gpsHgtAccuracy,100.0f);
- }
-
- if (gps.num_sats() >= 6 && (PV_AidingMode == AID_ABSOLUTE)) {
- gpsNoiseScaler = 1.0f;
- } else if (gps.num_sats() == 5 && (PV_AidingMode == AID_ABSOLUTE)) {
- gpsNoiseScaler = 1.4f;
- } else {
- gpsNoiseScaler = 2.0f;
- }
-
- if (gps.have_vertical_velocity() && (frontend->_fusionModeGPS == 0) && !frontend->inhibitGpsVertVelUse) {
- useGpsVertVel = true;
- } else {
- useGpsVertVel = false;
- }
-
- calcGpsGoodToAlign();
-
- calcGpsGoodForFlight();
-
- if (!validOrigin && frontend->common_origin_valid) {
- setOrigin(frontend->common_EKF_origin);
- }
-
- const struct Location &gpsloc = gps.location();
-
- if (gpsGoodToAlign && !validOrigin) {
- setOrigin(gpsloc);
-
-
- alignMagStateDeclination();
-
- ekfGpsRefHgt = (double)0.01 * (double)gpsloc.alt + (double)outputDataNew.position.z;
-
- ekfOriginHgtVar = sq(gpsHgtAccuracy);
- }
-
- if (validOrigin) {
- gpsDataNew.pos = EKF_origin.get_distance_NE(gpsloc);
- if ((frontend->_originHgtMode & (1<<2)) == 0) {
- gpsDataNew.hgt = (float)((double)0.01 * (double)gpsloc.alt - ekfGpsRefHgt);
- } else {
- gpsDataNew.hgt = 0.01 * (gpsloc.alt - EKF_origin.alt);
- }
- storedGPS.push(gpsDataNew);
-
- gpsNotAvailable = false;
- }
-
- float yaw_deg, yaw_accuracy_deg;
- if (AP::gps().gps_yaw_deg(yaw_deg, yaw_accuracy_deg)) {
- writeEulerYawAngle(radians(yaw_deg), radians(yaw_accuracy_deg), gpsDataNew.time_ms, 2);
- }
- } else {
-
- gpsCheckStatus.bad_fix = true;
- hal.util->snprintf(prearm_fail_string, sizeof(prearm_fail_string), "Waiting for 3D fix");
- }
- }
- }
- bool NavEKF3_core::readDeltaAngle(uint8_t ins_index, Vector3f &dAng) {
- const AP_InertialSensor &ins = AP::ins();
- if (ins_index < ins.get_gyro_count()) {
- ins.get_delta_angle(ins_index,dAng);
- frontend->logging.log_imu = true;
- return true;
- }
- return false;
- }
- void NavEKF3_core::readBaroData()
- {
-
-
- const AP_Baro &baro = AP::baro();
- if (baro.get_last_update() - lastBaroReceived_ms > frontend->sensorIntervalMin_ms) {
- frontend->logging.log_baro = true;
- baroDataNew.hgt = baro.get_altitude();
-
-
- if (getTakeoffExpected()) {
- baroDataNew.hgt = MAX(baroDataNew.hgt, meaHgtAtTakeOff);
- }
-
- lastBaroReceived_ms = baro.get_last_update();
-
- baroDataNew.time_ms = lastBaroReceived_ms - frontend->_hgtDelay_ms;
-
- baroDataNew.time_ms -= localFilterTimeStep_ms/2;
-
- baroDataNew.time_ms = MAX(baroDataNew.time_ms,imuDataDelayed.time_ms);
-
- storedBaro.push(baroDataNew);
- }
- }
- void NavEKF3_core::calcFiltBaroOffset()
- {
-
- baroHgtOffset += 0.1f * constrain_float(baroDataDelayed.hgt + stateStruct.position.z - baroHgtOffset, -5.0f, 5.0f);
- }
- void NavEKF3_core::correctEkfOriginHeight()
- {
-
-
- float deltaTime = constrain_float(0.001f * (imuDataDelayed.time_ms - lastOriginHgtTime_ms), 0.0f, 1.0f);
- if (activeHgtSource == HGT_SOURCE_BARO) {
-
- const float baroDriftRate = 0.05f;
- ekfOriginHgtVar += sq(baroDriftRate * deltaTime);
- } else if (activeHgtSource == HGT_SOURCE_RNG) {
-
- const float maxTerrGrad = 0.25f;
- ekfOriginHgtVar += sq(maxTerrGrad * norm(stateStruct.velocity.x , stateStruct.velocity.y) * deltaTime);
- } else {
-
- return;
- }
- lastOriginHgtTime_ms = imuDataDelayed.time_ms;
-
-
- float originHgtObsVar = sq(gpsHgtAccuracy) + P[9][9];
-
- float gain = ekfOriginHgtVar / (ekfOriginHgtVar + originHgtObsVar);
-
- float innovation = - stateStruct.position.z - gpsDataDelayed.hgt;
-
- float ratio = sq(innovation) / (ekfOriginHgtVar + originHgtObsVar);
-
- if (ratio < 25.0f && gpsAccuracyGood) {
- ekfGpsRefHgt -= (double)(gain * innovation);
- ekfOriginHgtVar -= MAX(gain * ekfOriginHgtVar , 0.0f);
- }
- }
- void NavEKF3_core::readAirSpdData()
- {
-
-
-
- const AP_Airspeed *aspeed = _ahrs->get_airspeed();
- if (aspeed &&
- aspeed->use() &&
- (aspeed->last_update_ms() - timeTasReceived_ms) > frontend->sensorIntervalMin_ms) {
- tasDataNew.tas = aspeed->get_raw_airspeed() * AP::ahrs().get_EAS2TAS();
- timeTasReceived_ms = aspeed->last_update_ms();
- tasDataNew.time_ms = timeTasReceived_ms - frontend->tasDelay_ms;
-
- tasDataNew.time_ms -= localFilterTimeStep_ms/2;
-
- storedTAS.push(tasDataNew);
- }
-
- tasDataToFuse = storedTAS.recall(tasDataDelayed,imuDataDelayed.time_ms);
- }
- void NavEKF3_core::readRngBcnData()
- {
-
- const AP_Beacon *beacon = AP::beacon();
-
- if (beacon == nullptr) {
- return;
- }
-
- N_beacons = beacon->count();
-
- bool newDataToPush = false;
- uint8_t numRngBcnsChecked = 0;
-
- uint8_t index = lastRngBcnChecked;
- while (!newDataToPush && numRngBcnsChecked < N_beacons) {
-
- numRngBcnsChecked++;
-
- index++;
- if (index >= N_beacons) {
- index = 0;
- }
-
- if (beacon->beacon_healthy(index) &&
- beacon->beacon_last_update_ms(index) != lastTimeRngBcn_ms[index])
- {
-
- lastTimeRngBcn_ms[index] = beacon->beacon_last_update_ms(index);
- rngBcnDataNew.time_ms = lastTimeRngBcn_ms[index] - frontend->_rngBcnDelay_ms - localFilterTimeStep_ms/2;
-
-
- rngBcnDataNew.rngErr = frontend->_rngBcnNoise;
-
- rngBcnDataNew.rng = beacon->beacon_distance(index);
-
- rngBcnDataNew.beacon_posNED = beacon->beacon_position(index);
-
- rngBcnDataNew.beacon_ID = index;
-
- newDataToPush = true;
-
- lastRngBcnChecked = index;
- }
- }
-
- if (beacon->get_vehicle_position_ned(beaconVehiclePosNED, beaconVehiclePosErr)) {
- rngBcnLast3DmeasTime_ms = imuSampleTime_ms;
- }
-
- if (imuSampleTime_ms - rngBcnLast3DmeasTime_ms < 250 && beaconVehiclePosErr < 1.0f && rngBcnAlignmentCompleted) {
-
- const float posDiffSq = sq(receiverPos.x - beaconVehiclePosNED.x) + sq(receiverPos.y - beaconVehiclePosNED.y);
- const float posDiffVar = sq(beaconVehiclePosErr) + receiverPosCov[0][0] + receiverPosCov[1][1];
- if (posDiffSq < 9.0f * posDiffVar) {
- rngBcnGoodToAlign = true;
-
- if (!validOrigin && PV_AidingMode != AID_ABSOLUTE) {
-
- Location origin_loc;
- if (beacon->get_origin(origin_loc)) {
- setOriginLLH(origin_loc);
-
-
- alignMagStateDeclination();
-
- ekfOriginHgtVar = sq(beaconVehiclePosErr);
- }
- }
- } else {
- rngBcnGoodToAlign = false;
- }
- } else {
- rngBcnGoodToAlign = false;
- }
-
- if (newDataToPush) {
- storedRangeBeacon.push(rngBcnDataNew);
- }
-
- rngBcnDataToFuse = storedRangeBeacon.recall(rngBcnDataDelayed, imuDataDelayed.time_ms);
-
- if (rngBcnDataToFuse) {
- rngBcnDataDelayed.beacon_posNED.x += bcnPosOffsetNED.x;
- rngBcnDataDelayed.beacon_posNED.y += bcnPosOffsetNED.y;
- }
- }
- void NavEKF3_core::writeEulerYawAngle(float yawAngle, float yawAngleErr, uint32_t timeStamp_ms, uint8_t type)
- {
-
-
- if (((timeStamp_ms - yawMeasTime_ms) < frontend->sensorIntervalMin_ms) || !statesInitialised) {
- return;
- }
- yawAngDataNew.yawAng = yawAngle;
- yawAngDataNew.yawAngErr = yawAngleErr;
- yawAngDataNew.type = type;
- yawAngDataNew.time_ms = timeStamp_ms;
- storedYawAng.push(yawAngDataNew);
- yawMeasTime_ms = timeStamp_ms;
- }
- void NavEKF3_core::updateTimingStatistics(void)
- {
- if (timing.count == 0) {
- timing.dtIMUavg_max = dtIMUavg;
- timing.dtIMUavg_min = dtIMUavg;
- timing.dtEKFavg_max = dtEkfAvg;
- timing.dtEKFavg_min = dtEkfAvg;
- timing.delAngDT_max = imuDataDelayed.delAngDT;
- timing.delAngDT_min = imuDataDelayed.delAngDT;
- timing.delVelDT_max = imuDataDelayed.delVelDT;
- timing.delVelDT_min = imuDataDelayed.delVelDT;
- } else {
- timing.dtIMUavg_max = MAX(timing.dtIMUavg_max, dtIMUavg);
- timing.dtIMUavg_min = MIN(timing.dtIMUavg_min, dtIMUavg);
- timing.dtEKFavg_max = MAX(timing.dtEKFavg_max, dtEkfAvg);
- timing.dtEKFavg_min = MIN(timing.dtEKFavg_min, dtEkfAvg);
- timing.delAngDT_max = MAX(timing.delAngDT_max, imuDataDelayed.delAngDT);
- timing.delAngDT_min = MIN(timing.delAngDT_min, imuDataDelayed.delAngDT);
- timing.delVelDT_max = MAX(timing.delVelDT_max, imuDataDelayed.delVelDT);
- timing.delVelDT_min = MIN(timing.delVelDT_min, imuDataDelayed.delVelDT);
- }
- timing.count++;
- }
- void NavEKF3_core::getTimingStatistics(struct ekf_timing &_timing)
- {
- _timing = timing;
- memset(&timing, 0, sizeof(timing));
- }
- void NavEKF3_core::learnInactiveBiases(void)
- {
- const AP_InertialSensor &ins = AP::ins();
-
- for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
- if (!ins.use_gyro(i)) {
-
- continue;
- }
- if (gyro_index_active == i) {
-
- inactiveBias[i].gyro_bias = stateStruct.gyro_bias;
- } else {
-
-
-
- Vector3f filtered_gyro_active = ins.get_gyro(gyro_index_active) - (stateStruct.gyro_bias/dtEkfAvg);
- Vector3f filtered_gyro_inactive = ins.get_gyro(i) - (inactiveBias[i].gyro_bias/dtEkfAvg);
- Vector3f error = filtered_gyro_active - filtered_gyro_inactive;
-
- const float bias_limit = radians(5);
- error.x = constrain_float(error.x, -bias_limit, bias_limit);
- error.y = constrain_float(error.y, -bias_limit, bias_limit);
- error.z = constrain_float(error.z, -bias_limit, bias_limit);
-
-
- inactiveBias[i].gyro_bias -= error * (1.0e-4f * dtEkfAvg);
- }
- }
-
- for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
- if (!ins.use_accel(i)) {
-
- continue;
- }
- if (accel_index_active == i) {
-
- inactiveBias[i].accel_bias = stateStruct.accel_bias;
- } else {
-
-
-
- Vector3f filtered_accel_active = ins.get_accel(accel_index_active) - (stateStruct.accel_bias/dtEkfAvg);
- Vector3f filtered_accel_inactive = ins.get_accel(i) - (inactiveBias[i].accel_bias/dtEkfAvg);
- Vector3f error = filtered_accel_active - filtered_accel_inactive;
-
- const float bias_limit = 1.0;
- error.x = constrain_float(error.x, -bias_limit, bias_limit);
- error.y = constrain_float(error.y, -bias_limit, bias_limit);
- error.z = constrain_float(error.z, -bias_limit, bias_limit);
-
-
-
- inactiveBias[i].accel_bias -= error * (1.0e-4f * dtEkfAvg);
- }
- }
- }
|