// 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(); rangeDataToFuse = storedRange.recall(rangeDataDelayed,imuDataDelayed.time_ms); // read baro height data from the sensor and check for new data in the buffer readBaroData(); baroDataToFuse = storedBaro.recall(baroDataDelayed, imuDataDelayed.time_ms); // select height source if (((frontend->_useRngSwHgt > 0) || (frontend->_altSource == 1)) && (imuSampleTime_ms - rngValidMeaTime_ms < 500)) { if (frontend->_altSource == 1) { // always use range finder activeHgtSource = HGT_SOURCE_RNG; } else { // determine if we are above or below the height switch region float rangeMaxUse = 1e-4f * (float)frontend->_rng.max_distance_cm() * (float)frontend->_useRngSwHgt; 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 float horizSpeed = norm(stateStruct.velocity.x, stateStruct.velocity.y); bool dontTrustTerrain = (horizSpeed > 2.0f) || !terrainHgtStable; bool trustTerrain = (horizSpeed < 1.0f) && 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; } } else if (belowLowerSwHgt && trustTerrain && (activeHgtSource != HGT_SOURCE_RNG)) { // reliable terrain and range finder so start using range finder height activeHgtSource = HGT_SOURCE_RNG; } } } else if ((frontend->_altSource == 2) && ((imuSampleTime_ms - lastTimeGpsReceived_ms) < 500) && validOrigin && gpsAccuracyGood) { activeHgtSource = HGT_SOURCE_GPS; } else { activeHgtSource = HGT_SOURCE_BARO; } // Use Baro alt as a fallback if we lose range finder or GPS bool lostRngHgt = ((activeHgtSource == HGT_SOURCE_RNG) && ((imuSampleTime_ms - rngValidMeaTime_ms) > 500)); bool lostGpsHgt = ((activeHgtSource == HGT_SOURCE_GPS) && ((imuSampleTime_ms - lastTimeGpsReceived_ms) > 2000)); if (lostRngHgt || lostGpsHgt) { activeHgtSource = HGT_SOURCE_BARO; } // if there is new baro data to fuse, calculate filtered baro data required by other processes if (baroDataToFuse) { // calculate offset to baro data that enables us to switch to Baro height use during operation if (activeHgtSource != HGT_SOURCE_BARO) { calcFiltBaroOffset(); } // filtered baro data used to provide a reference for takeoff // it is is reset to last height measurement on disarming in performArmingChecks() 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; } } // calculate offset to GPS height data that enables us to switch to GPS height during operation if (gpsDataToFuse && (activeHgtSource != HGT_SOURCE_GPS)) { calcFiltGpsHgtOffset(); } // Select the height measurement source if (rangeDataToFuse && (activeHgtSource == HGT_SOURCE_RNG)) { // using range finder data // correct for tilt using a flat earth model if (prevTnb.c.z >= 0.7) { // calculate height above ground hgtMea = MAX(rangeDataDelayed.rng * prevTnb.c.z, rngOnGnd); // correct for terrain position relative to datum hgtMea -= terrainState; // enable fusion fuseHgtData = true; // set the observation noise posDownObsNoise = sq(constrain_float(frontend->_rngNoise, 0.1f, 10.0f)); // add uncertainty created by terrain gradient and vehicle tilt posDownObsNoise += sq(rangeDataDelayed.rng * frontend->_terrGradMax) * MAX(0.0f , (1.0f - sq(prevTnb.c.z))); } else { // disable fusion if tilted too far fuseHgtData = false; } } else if (gpsDataToFuse && (activeHgtSource == HGT_SOURCE_GPS)) { // using GPS data hgtMea = gpsDataDelayed.hgt; // enable fusion fuseHgtData = true; // set the observation noise using receiver reported accuracy or the horizontal noise scaled for typical VDOP/HDOP ratio 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)) { // using Baro data hgtMea = baroDataDelayed.hgt - baroHgtOffset; // enable fusion fuseHgtData = true; // set the observation noise posDownObsNoise = sq(constrain_float(frontend->_baroAltNoise, 0.1f, 10.0f)); // reduce weighting (increase observation noise) on baro if we are likely to be in ground effect if (getTakeoffExpected() || getTouchdownExpected()) { posDownObsNoise *= frontend->gndEffectBaroScaler; } // 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 if (motorsArmed && getTakeoffExpected()) { hgtMea = MAX(hgtMea, meaHgtAtTakeOff); } } 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 hgtRetryTime_ms = (useGpsVertVel && !velTimeout) ? frontend->hgtRetryTimeMode0_ms : frontend->hgtRetryTimeMode12_ms; if (imuSampleTime_ms - lastHgtPassTime_ms > hgtRetryTime_ms) { hgtTimeout = true; } else { hgtTimeout = false; } }
// 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(); rangeDataToFuse = RecallRange(); // read baro height data from the sensor and check for new data in the buffer readBaroData(); baroDataToFuse = RecallBaro(); // determine if we should be using a height source other than baro bool usingRangeForHgt = (frontend->_altSource == 1 && imuSampleTime_ms - rngValidMeaTime_ms < 500 && frontend->_fusionModeGPS == 3); bool usingGpsForHgt = (frontend->_altSource == 2 && imuSampleTime_ms - lastTimeGpsReceived_ms < 500 && validOrigin); // if there is new baro data to fuse, calculate filterred baro data required by other processes if (baroDataToFuse) { // calculate offset to baro data that enables baro to be used as a backup if we are using other height sources if (usingRangeForHgt || usingGpsForHgt) { calcFiltBaroOffset(); } // filtered baro data used to provide a reference for takeoff // it is is reset to last height measurement on disarming in performArmingChecks() 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; } } // Select the height measurement source if (rangeDataToFuse && usingRangeForHgt) { // using range finder data // correct for tilt using a flat earth model if (prevTnb.c.z >= 0.7) { hgtMea = max(rangeDataDelayed.rng * prevTnb.c.z, rngOnGnd); // enable fusion fuseHgtData = true; // set the observation noise posDownObsNoise = sq(constrain_float(frontend->_rngNoise, 0.1f, 10.0f)); } else { // disable fusion if tilted too far fuseHgtData = false; } } else if (gpsDataToFuse && usingGpsForHgt) { // using GPS data hgtMea = gpsDataDelayed.hgt; // enable fusion fuseHgtData = true; // set the observation noise to the horizontal GPS noise plus a scaler becasue GPS vertical position is usually less accurate // TODO use VDOP/HDOP, reported accuracy or a separate parameter posDownObsNoise = sq(constrain_float(frontend->_gpsHorizPosNoise * 1.5f, 0.1f, 10.0f)); } else if (baroDataToFuse && !usingRangeForHgt && !usingGpsForHgt) { // using Baro data hgtMea = baroDataDelayed.hgt - baroHgtOffset; // enable fusion fuseHgtData = true; // set the observation noise posDownObsNoise = sq(constrain_float(frontend->_baroAltNoise, 0.1f, 10.0f)); // reduce weighting (increase observation noise) on baro if we are likely to be in ground effect if (getTakeoffExpected() || getTouchdownExpected()) { posDownObsNoise *= frontend->gndEffectBaroScaler; } } 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 hgtRetryTime_ms = (useGpsVertVel && !velTimeout) ? frontend->hgtRetryTimeMode0_ms : frontend->hgtRetryTimeMode12_ms; if (imuSampleTime_ms - lastHgtPassTime_ms > hgtRetryTime_ms) { hgtTimeout = true; } else { hgtTimeout = false; } }
// 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(); rangeDataToFuse = storedRange.recall(rangeDataDelayed,imuDataDelayed.time_ms); // 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 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; } } } // read baro height data from the sensor and check for new data in the buffer readBaroData(); baroDataToFuse = storedBaro.recall(baroDataDelayed, imuDataDelayed.time_ms); // select height source if (extNavUsedForPos) { // always use external vision as the hight source if using for position. activeHgtSource = HGT_SOURCE_EV; } else if (((frontend->_useRngSwHgt > 0) || (frontend->_altSource == 1)) && (imuSampleTime_ms - rngValidMeaTime_ms < 500)) { if (frontend->_altSource == 1) { // always use range finder activeHgtSource = HGT_SOURCE_RNG; } else { // determine if we are above or below the height switch region 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; // 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 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; /* * 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; } } else if (belowLowerSwHgt && trustTerrain && (activeHgtSource != HGT_SOURCE_RNG)) { // reliable terrain and range finder so start using range finder height 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; } // Use Baro alt as a fallback if we lose range finder, GPS or external nav 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 there is new baro data to fuse, calculate filtered baro data required by other processes if (baroDataToFuse) { // calculate offset to baro data that enables us to switch to Baro height use during operation if (activeHgtSource != HGT_SOURCE_BARO) { calcFiltBaroOffset(); } // filtered baro data used to provide a reference for takeoff // it is is reset to last height measurement on disarming in performArmingChecks() 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 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(); } // Select the height measurement source if (extNavDataToFuse && (activeHgtSource == HGT_SOURCE_EV)) { hgtMea = -extNavDataDelayed.pos.z; posDownObsNoise = sq(constrain_float(extNavDataDelayed.posErr, 0.1f, 10.0f)); } else if (rangeDataToFuse && (activeHgtSource == HGT_SOURCE_RNG)) { // using range finder data // correct for tilt using a flat earth model if (prevTnb.c.z >= 0.7) { // calculate height above ground hgtMea = MAX(rangeDataDelayed.rng * prevTnb.c.z, rngOnGnd); // correct for terrain position relative to datum hgtMea -= terrainState; // enable fusion fuseHgtData = true; velPosObs[5] = -hgtMea; // set the observation noise posDownObsNoise = sq(constrain_float(frontend->_rngNoise, 0.1f, 10.0f)); // add uncertainty created by terrain gradient and vehicle tilt posDownObsNoise += sq(rangeDataDelayed.rng * frontend->_terrGradMax) * MAX(0.0f , (1.0f - sq(prevTnb.c.z))); } else { // disable fusion if tilted too far fuseHgtData = false; } } else if (gpsDataToFuse && (activeHgtSource == HGT_SOURCE_GPS)) { // using GPS data hgtMea = gpsDataDelayed.hgt; // enable fusion velPosObs[5] = -hgtMea; fuseHgtData = true; // set the observation noise using receiver reported accuracy or the horizontal noise scaled for typical VDOP/HDOP ratio 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)) { // using Baro data hgtMea = baroDataDelayed.hgt - baroHgtOffset; // enable fusion velPosObs[5] = -hgtMea; fuseHgtData = true; // set the observation noise posDownObsNoise = sq(constrain_float(frontend->_baroAltNoise, 0.1f, 10.0f)); // reduce weighting (increase observation noise) on baro if we are likely to be in ground effect if (getTakeoffExpected() || getTouchdownExpected()) { posDownObsNoise *= frontend->gndEffectBaroScaler; } // 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 if (motorsArmed && getTakeoffExpected()) { hgtMea = MAX(hgtMea, meaHgtAtTakeOff); } } 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 hgtRetryTime_ms = (useGpsVertVel && !velTimeout) ? frontend->hgtRetryTimeMode0_ms : frontend->hgtRetryTimeMode12_ms; if (imuSampleTime_ms - lastHgtPassTime_ms > hgtRetryTime_ms) { hgtTimeout = true; } else { hgtTimeout = false; } }