mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_NavEKF3: rename gpsVelInnovTime_ms to gpsRetrieveTime_ms
in preparation for using this for other things
This commit is contained in:
parent
2a6b45f4d9
commit
e8f361458e
@ -487,7 +487,7 @@ bool NavEKF3_core::getVelInnovationsAndVariancesForSource(AP_NavEKF_Source::Sour
|
||||
switch (source) {
|
||||
case AP_NavEKF_Source::SourceXY::GPS:
|
||||
// check for timeouts
|
||||
if (dal.millis() - gpsVelInnovTime_ms > 500) {
|
||||
if (dal.millis() - gpsRetrieveTime_ms > 500) {
|
||||
return false;
|
||||
}
|
||||
innovations = gpsVelInnov.tofloat();
|
||||
|
@ -500,8 +500,8 @@ void NavEKF3_core::SelectVelPosFusion()
|
||||
CorrectGPSForAntennaOffset(gpsDataDelayed);
|
||||
// calculate innovations and variances for reporting purposes only
|
||||
CalculateVelInnovationsAndVariances(gpsDataDelayed.vel, frontend->_gpsHorizVelNoise, frontend->gpsNEVelVarAccScale, gpsVelInnov, gpsVelVarInnov);
|
||||
// record time innovations were calculated (for timeout checks)
|
||||
gpsVelInnovTime_ms = dal.millis();
|
||||
// record time GPS data was retrieved from the buffer (for timeout checks)
|
||||
gpsRetrieveTime_ms = dal.millis();
|
||||
}
|
||||
|
||||
// detect position source changes. Trigger position reset if position source is valid
|
||||
|
@ -1259,7 +1259,7 @@ private:
|
||||
bool gpsAccuracyGoodForAltitude; // true when the GPS accuracy is considered to be good enough to use it as an altitude source.
|
||||
Vector3F gpsVelInnov; // gps velocity innovations
|
||||
Vector3F gpsVelVarInnov; // gps velocity innovation variances
|
||||
uint32_t gpsVelInnovTime_ms; // system time that gps velocity innovations were recorded (to detect timeouts)
|
||||
uint32_t gpsRetrieveTime_ms; // system time that GPS data was retrieved from the buffer (to detect timeouts)
|
||||
|
||||
// variables added for optical flow fusion
|
||||
EKF_obs_buffer_t<of_elements> storedOF; // OF data buffer
|
||||
|
Loading…
Reference in New Issue
Block a user