Browse Source

AP_NavEKF2: support VISION_SPEED_ESTIMATE

c415-sdk
chobits 6 years ago committed by Randy Mackay
parent
commit
dee095b4a4
  1. 15
      libraries/AP_NavEKF2/AP_NavEKF2.cpp
  2. 10
      libraries/AP_NavEKF2/AP_NavEKF2.h
  3. 2
      libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp
  4. 19
      libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp
  5. 60
      libraries/AP_NavEKF2/AP_NavEKF2_PosVelFusion.cpp
  6. 10
      libraries/AP_NavEKF2/AP_NavEKF2_core.cpp
  7. 27
      libraries/AP_NavEKF2/AP_NavEKF2_core.h

15
libraries/AP_NavEKF2/AP_NavEKF2.cpp

@ -1706,3 +1706,18 @@ void NavEKF2::writeDefaultAirSpeed(float airspeed)
} }
} }
} }
/* Write velocity data from an external navigation system
* vel : velocity in NED (m)
* err : velocity error (m/s)
* timeStamp_ms : system time the measurement was taken, not the time it was received (mSec)
* delay_ms : average delay of external nav system measurements relative to inertial measurements
*/
void NavEKF2::writeExtNavVelData(const Vector3f &vel, float err, uint32_t timeStamp_ms, uint16_t delay_ms)
{
if (core) {
for (uint8_t i=0; i<num_cores; i++) {
core[i].writeExtNavVelData(vel, err, timeStamp_ms, delay_ms);
}
}
}

10
libraries/AP_NavEKF2/AP_NavEKF2.h

@ -343,6 +343,15 @@ public:
*/ */
void writeExtNavData(const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint16_t delay_ms, uint32_t resetTime_ms); void writeExtNavData(const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint16_t delay_ms, uint32_t resetTime_ms);
/*
* Write velocity data from an external navigation system
* vel : velocity in NED (m)
* err : velocity error (m/s)
* timeStamp_ms : system time the measurement was taken, not the time it was received (mSec)
* delay_ms : average delay of external nav system measurements relative to inertial measurements
*/
void writeExtNavVelData(const Vector3f &vel, float err, uint32_t timeStamp_ms, uint16_t delay_ms);
/* /*
check if switching lanes will reduce the normalised check if switching lanes will reduce the normalised
innovations. This is called when the vehicle code is about to innovations. This is called when the vehicle code is about to
@ -445,6 +454,7 @@ private:
// Tuning parameters // Tuning parameters
const float gpsNEVelVarAccScale = 0.05f; // Scale factor applied to NE velocity measurement variance due to manoeuvre acceleration const float gpsNEVelVarAccScale = 0.05f; // Scale factor applied to NE velocity measurement variance due to manoeuvre acceleration
const float gpsDVelVarAccScale = 0.07f; // Scale factor applied to vertical velocity measurement variance due to manoeuvre acceleration const float gpsDVelVarAccScale = 0.07f; // Scale factor applied to vertical velocity measurement variance due to manoeuvre acceleration
const float extNavVelVarAccScale = 0.05f; // Scale factor applied to ext nav velocity measurement variance due to manoeuvre acceleration
const float gpsPosVarAccScale = 0.05f; // Scale factor applied to horizontal position measurement variance due to manoeuvre acceleration const float gpsPosVarAccScale = 0.05f; // Scale factor applied to horizontal position measurement variance due to manoeuvre acceleration
const uint8_t magDelay_ms = 60; // Magnetometer measurement delay (msec) const uint8_t magDelay_ms = 60; // Magnetometer measurement delay (msec)
const uint8_t tasDelay_ms = 240; // Airspeed measurement delay (msec) const uint8_t tasDelay_ms = 240; // Airspeed measurement delay (msec)

2
libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp

@ -513,7 +513,7 @@ void NavEKF2_core::updateFilterStatus(void)
bool doingFlowNav = (PV_AidingMode == AID_RELATIVE) && flowDataValid; bool doingFlowNav = (PV_AidingMode == AID_RELATIVE) && flowDataValid;
bool doingWindRelNav = !tasTimeout && assume_zero_sideslip(); bool doingWindRelNav = !tasTimeout && assume_zero_sideslip();
bool doingNormalGpsNav = !posTimeout && (PV_AidingMode == AID_ABSOLUTE); bool doingNormalGpsNav = !posTimeout && (PV_AidingMode == AID_ABSOLUTE);
bool someVertRefData = (!velTimeout && useGpsVertVel) || !hgtTimeout; bool someVertRefData = (!velTimeout && (useGpsVertVel || useExtNavVel)) || !hgtTimeout;
bool someHorizRefData = !(velTimeout && posTimeout && tasTimeout) || doingFlowNav; bool someHorizRefData = !(velTimeout && posTimeout && tasTimeout) || doingFlowNav;
bool optFlowNavPossible = flowDataValid && delAngBiasLearned; bool optFlowNavPossible = flowDataValid && delAngBiasLearned;
bool gpsNavPossible = !gpsNotAvailable && gpsGoodToAlign && delAngBiasLearned; bool gpsNavPossible = !gpsNotAvailable && gpsGoodToAlign && delAngBiasLearned;

19
libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp

@ -1015,3 +1015,22 @@ void NavEKF2_core::writeDefaultAirSpeed(float airspeed)
{ {
defaultAirSpeed = airspeed; defaultAirSpeed = airspeed;
} }
void NavEKF2_core::writeExtNavVelData(const Vector3f &vel, float err, uint32_t timeStamp_ms, uint16_t delay_ms)
{
if ((timeStamp_ms - extNavVelMeasTime_ms) < 70) {
return;
}
extNavVelMeasTime_ms = timeStamp_ms;
useExtNavVel = true;
extNavVelNew.vel = vel;
extNavVelNew.err = err;
timeStamp_ms = timeStamp_ms - delay_ms;
// Correct for the average intersampling delay due to the filter updaterate
timeStamp_ms -= localFilterTimeStep_ms/2;
// Prevent time delay exceeding age of oldest IMU data in the buffer
timeStamp_ms = MAX(timeStamp_ms,imuDataDelayed.time_ms);
extNavVelNew.time_ms = timeStamp_ms;
storedExtNavVel.push(extNavVelNew);
}

60
libraries/AP_NavEKF2/AP_NavEKF2_PosVelFusion.cpp

@ -46,6 +46,12 @@ void NavEKF2_core::ResetVelocity(void)
// clear the timeout flags and counters // clear the timeout flags and counters
velTimeout = false; velTimeout = false;
lastVelPassTime_ms = imuSampleTime_ms; lastVelPassTime_ms = imuSampleTime_ms;
} 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);
velTimeout = false;
lastVelPassTime_ms = imuSampleTime_ms;
} else { } else {
stateStruct.velocity.x = 0.0f; stateStruct.velocity.x = 0.0f;
stateStruct.velocity.y = 0.0f; stateStruct.velocity.y = 0.0f;
@ -222,6 +228,8 @@ void NavEKF2_core::ResetHeight(void)
// Check that GPS vertical velocity data is available and can be used // Check that GPS vertical velocity data is available and can be used
if (inFlight && !gpsNotAvailable && frontend->_fusionModeGPS == 0 && !frontend->inhibitGpsVertVelUse) { if (inFlight && !gpsNotAvailable && frontend->_fusionModeGPS == 0 && !frontend->inhibitGpsVertVelUse) {
stateStruct.velocity.z = gpsDataNew.vel.z; stateStruct.velocity.z = gpsDataNew.vel.z;
} else if (inFlight && useExtNavVel) {
stateStruct.velocity.z = extNavVelNew.vel.z;
} else if (onGround) { } else if (onGround) {
stateStruct.velocity.z = 0.0f; stateStruct.velocity.z = 0.0f;
} }
@ -237,8 +245,11 @@ void NavEKF2_core::ResetHeight(void)
zeroCols(P,5,5); zeroCols(P,5,5);
// set the variances to the measurement variance // set the variances to the measurement variance
P[5][5] = sq(frontend->_gpsVertVelNoise); if (useExtNavVel) {
P[5][5] = sq(extNavVelNew.err);
} else {
P[5][5] = sq(frontend->_gpsVertVelNoise);
}
} }
// reset the stateStruct's D position // reset the stateStruct's D position
@ -354,6 +365,24 @@ void NavEKF2_core::CorrectExtNavForSensorOffset(Vector3f &ext_position) const
#endif #endif
} }
// correct external navigation earth-frame velocity using sensor body-frame offset
void NavEKF2_core::CorrectExtNavVelForSensorOffset(Vector3f &ext_velocity) const
{
#if HAL_VISUALODOM_ENABLED
AP_VisualOdom *visual_odom = AP::visualodom();
if (visual_odom == nullptr) {
return;
}
const Vector3f &posOffsetBody = visual_odom->get_pos_offset() - accelPosOffset;
if (posOffsetBody.is_zero()) {
return;
}
// TODO use a filtered angular rate with a group delay that matches the sensor delay
const Vector3f angRate = imuDataDelayed.delAng * (1.0f/imuDataDelayed.delAngDT);
ext_velocity += get_vel_correction_for_sensor_offset(posOffsetBody, prevTnb, angRate);
#endif
}
/******************************************************** /********************************************************
* FUSE MEASURED_DATA * * FUSE MEASURED_DATA *
********************************************************/ ********************************************************/
@ -372,6 +401,10 @@ void NavEKF2_core::SelectVelPosFusion()
// Check for data at the fusion time horizon // Check for data at the fusion time horizon
extNavDataToFuse = storedExtNav.recall(extNavDataDelayed, imuDataDelayed.time_ms); extNavDataToFuse = storedExtNav.recall(extNavDataDelayed, imuDataDelayed.time_ms);
extNavVelToFuse = storedExtNavVel.recall(extNavVelDelayed, imuDataDelayed.time_ms);
if (extNavVelToFuse) {
CorrectExtNavVelForSensorOffset(extNavVelDelayed.vel);
}
// read GPS data from the sensor and check for new data in the buffer // read GPS data from the sensor and check for new data in the buffer
readGpsData(); readGpsData();
@ -436,6 +469,13 @@ void NavEKF2_core::SelectVelPosFusion()
fusePosData = false; fusePosData = false;
} }
if (extNavVelToFuse && (frontend->_fusionModeGPS == 3)) {
fuseVelData = true;
velPosObs[0] = extNavVelDelayed.vel.x;
velPosObs[1] = extNavVelDelayed.vel.y;
velPosObs[2] = extNavVelDelayed.vel.z;
}
// we have GPS data to fuse and a request to align the yaw using the GPS course // we have GPS data to fuse and a request to align the yaw using the GPS course
if (gpsYawResetRequest) { if (gpsYawResetRequest) {
realignYawGPS(); realignYawGPS();
@ -582,6 +622,8 @@ void NavEKF2_core::FuseVelPosNED()
// use GPS receivers reported speed accuracy if available and floor at value set by GPS velocity noise parameter // use GPS receivers reported speed accuracy if available and floor at value set by GPS velocity noise parameter
R_OBS[0] = sq(constrain_float(gpsSpdAccuracy, frontend->_gpsHorizVelNoise, 50.0f)); R_OBS[0] = sq(constrain_float(gpsSpdAccuracy, frontend->_gpsHorizVelNoise, 50.0f));
R_OBS[2] = sq(constrain_float(gpsSpdAccuracy, frontend->_gpsVertVelNoise, 50.0f)); R_OBS[2] = sq(constrain_float(gpsSpdAccuracy, frontend->_gpsVertVelNoise, 50.0f));
} else if (extNavVelToFuse) {
R_OBS[2] = R_OBS[0] = sq(constrain_float(extNavVelDelayed.err, 0.05f, 5.0f));
} else { } else {
// calculate additional error in GPS velocity caused by manoeuvring // calculate additional error in GPS velocity caused by manoeuvring
R_OBS[0] = sq(constrain_float(frontend->_gpsHorizVelNoise, 0.05f, 5.0f)) + sq(frontend->gpsNEVelVarAccScale * accNavMag); R_OBS[0] = sq(constrain_float(frontend->_gpsHorizVelNoise, 0.05f, 5.0f)) + sq(frontend->gpsNEVelVarAccScale * accNavMag);
@ -600,7 +642,13 @@ void NavEKF2_core::FuseVelPosNED()
// For data integrity checks we use the same measurement variances as used to calculate the Kalman gains for all measurements except GPS horizontal velocity // For data integrity checks we use the same measurement variances as used to calculate the Kalman gains for all measurements except GPS horizontal velocity
// 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 // 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
// plus a margin for manoeuvres. It is better to reject GPS horizontal velocity errors early // plus a margin for manoeuvres. It is better to reject GPS horizontal velocity errors early
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); float obs_data_chk;
if (extNavVelToFuse) {
obs_data_chk = sq(constrain_float(extNavVelDelayed.err, 0.05f, 5.0f)) + sq(frontend->extNavVelVarAccScale * accNavMag);
} else {
obs_data_chk = sq(constrain_float(frontend->_gpsHorizVelNoise, 0.05f, 5.0f)) + sq(frontend->gpsNEVelVarAccScale * accNavMag);
}
R_OBS_DATA_CHECKS[0] = R_OBS_DATA_CHECKS[1] = R_OBS_DATA_CHECKS[2] = obs_data_chk;
} }
R_OBS[5] = posDownObsNoise; R_OBS[5] = posDownObsNoise;
for (uint8_t i=3; i<=5; i++) R_OBS_DATA_CHECKS[i] = R_OBS[i]; for (uint8_t i=3; i<=5; i++) R_OBS_DATA_CHECKS[i] = R_OBS[i];
@ -667,7 +715,7 @@ void NavEKF2_core::FuseVelPosNED()
// test velocity measurements // test velocity measurements
uint8_t imax = 2; uint8_t imax = 2;
// Don't fuse vertical velocity observations if inhibited by the user or if we are using synthetic data // Don't fuse vertical velocity observations if inhibited by the user or if we are using synthetic data
if (frontend->_fusionModeGPS > 0 || PV_AidingMode != AID_ABSOLUTE || frontend->inhibitGpsVertVelUse) { if (!useExtNavVel && (frontend->_fusionModeGPS > 0 || PV_AidingMode != AID_ABSOLUTE || frontend->inhibitGpsVertVelUse)) {
imax = 1; imax = 1;
} }
float innovVelSumSq = 0; // sum of squares of velocity innovations float innovVelSumSq = 0; // sum of squares of velocity innovations
@ -751,7 +799,7 @@ void NavEKF2_core::FuseVelPosNED()
if (fuseVelData && velHealth) { if (fuseVelData && velHealth) {
fuseData[0] = true; fuseData[0] = true;
fuseData[1] = true; fuseData[1] = true;
if (useGpsVertVel) { if (useGpsVertVel || useExtNavVel) {
fuseData[2] = true; fuseData[2] = true;
} }
tiltErrVec.zero(); tiltErrVec.zero();
@ -1077,7 +1125,7 @@ void NavEKF2_core::selectHeightForFusion()
// If we haven't fused height data for a while, then declare the height data as being timed out // 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 // 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; hgtRetryTime_ms = ((useGpsVertVel || useExtNavVel) && !velTimeout) ? frontend->hgtRetryTimeMode0_ms : frontend->hgtRetryTimeMode12_ms;
if (imuSampleTime_ms - lastHgtPassTime_ms > hgtRetryTime_ms) { if (imuSampleTime_ms - lastHgtPassTime_ms > hgtRetryTime_ms) {
hgtTimeout = true; hgtTimeout = true;
} else { } else {

10
libraries/AP_NavEKF2/AP_NavEKF2_core.cpp

@ -110,6 +110,9 @@ bool NavEKF2_core::setup_core(uint8_t _imu_index, uint8_t _core_index)
if(!storedOutput.init(imu_buffer_length)) { if(!storedOutput.init(imu_buffer_length)) {
return false; return false;
} }
if(!storedExtNavVel.init(OBS_BUFFER_LENGTH)) {
return false;
}
if ((yawEstimator == nullptr) && (frontend->_gsfRunMask & (1U<<core_index))) { if ((yawEstimator == nullptr) && (frontend->_gsfRunMask & (1U<<core_index))) {
// check if there is enough memory to create the EKF-GSF object // check if there is enough memory to create the EKF-GSF object
@ -337,6 +340,12 @@ void NavEKF2_core::InitialiseVariables()
extNavUsedForPos = false; extNavUsedForPos = false;
extNavYawResetRequest = false; extNavYawResetRequest = false;
memset(&extNavVelNew, 0, sizeof(extNavVelNew));
memset(&extNavVelDelayed, 0, sizeof(extNavVelDelayed));
extNavVelToFuse = false;
extNavVelMeasTime_ms = 0;
useExtNavVel = false;
// zero data buffers // zero data buffers
storedIMU.reset(); storedIMU.reset();
storedGPS.reset(); storedGPS.reset();
@ -346,6 +355,7 @@ void NavEKF2_core::InitialiseVariables()
storedOutput.reset(); storedOutput.reset();
storedRangeBeacon.reset(); storedRangeBeacon.reset();
storedExtNav.reset(); storedExtNav.reset();
storedExtNavVel.reset();
// now init mag variables // now init mag variables
yawAlignComplete = false; yawAlignComplete = false;

27
libraries/AP_NavEKF2/AP_NavEKF2_core.h

@ -334,6 +334,15 @@ public:
*/ */
void writeExtNavData(const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint16_t delay_ms, uint32_t resetTime_ms); void writeExtNavData(const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint16_t delay_ms, uint32_t resetTime_ms);
/*
* Write velocity data from an external navigation system
* vel : velocity in NED (m)
* err : velocity error (m/s)
* timeStamp_ms : system time the measurement was taken, not the time it was received (mSec)
* delay_ms : average delay of external nav system measurements relative to inertial measurements
*/
void writeExtNavVelData(const Vector3f &vel, float err, uint32_t timeStamp_ms, uint16_t delay_ms);
// return true when external nav data is also being used as a yaw observation // return true when external nav data is also being used as a yaw observation
bool isExtNavUsedForYaw(void); bool isExtNavUsedForYaw(void);
@ -506,6 +515,12 @@ private:
float accel_zbias; float accel_zbias;
} inactiveBias[INS_MAX_INSTANCES]; } inactiveBias[INS_MAX_INSTANCES];
struct ext_nav_vel_elements {
Vector3f vel; // velocity in NED (m)
float err; // velocity measurement error (m/s)
uint32_t time_ms; // measurement timestamp (msec)
};
// update the navigation filter status // update the navigation filter status
void updateFilterStatus(void); void updateFilterStatus(void);
@ -805,7 +820,10 @@ private:
// correct external navigation earth-frame position using sensor body-frame offset // correct external navigation earth-frame position using sensor body-frame offset
void CorrectExtNavForSensorOffset(Vector3f &ext_position) const; void CorrectExtNavForSensorOffset(Vector3f &ext_position) const;
// correct external navigation earth-frame velocity using sensor body-frame offset
void CorrectExtNavVelForSensorOffset(Vector3f &ext_velocity) const;
// Runs the IMU prediction step for an independent GSF yaw estimator algorithm // Runs the IMU prediction step for an independent GSF yaw estimator algorithm
// that uses IMU, GPS horizontal velocity and optionally true airspeed data. // that uses IMU, GPS horizontal velocity and optionally true airspeed data.
void runYawEstimatorPrediction(void); void runYawEstimatorPrediction(void);
@ -1172,6 +1190,13 @@ private:
bool extNavUsedForPos; // true when the external nav data is being used as a position reference. bool extNavUsedForPos; // true when the external nav data is being used as a position reference.
bool extNavYawResetRequest; // true when a reset of vehicle yaw using the external nav data is requested bool extNavYawResetRequest; // true when a reset of vehicle yaw using the external nav data is requested
obs_ring_buffer_t<ext_nav_vel_elements> storedExtNavVel; // external navigation velocity data buffer
ext_nav_vel_elements extNavVelNew; // external navigation velocity data at the current time horizon
ext_nav_vel_elements extNavVelDelayed; // external navigation velocity data at the fusion time horizon
uint32_t extNavVelMeasTime_ms; // time external navigation velocity measurements were accepted for input to the data buffer (msec)
bool extNavVelToFuse; // true when there is new external navigation velocity to fuse
bool useExtNavVel; // true external navigation velocity should be used
// flags indicating severe numerical errors in innovation variance calculation for different fusion operations // flags indicating severe numerical errors in innovation variance calculation for different fusion operations
struct { struct {
bool bad_xmag:1; bool bad_xmag:1;

Loading…
Cancel
Save