mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
AP_NavEKF3: Add accessor function for airspeed health monitoring
This commit is contained in:
parent
991959ddf7
commit
037cf9d2e9
@ -1211,6 +1211,15 @@ bool NavEKF3::getAirSpdVec(Vector3f &vel) const
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// return the innovation in m/s, innovation variance in (m/s)^2 and age in msec of the last TAS measurement processed
|
||||||
|
bool NavEKF3::getAirSpdHealthData(float &innovation, float &innovationVariance, uint32_t &age_ms) const
|
||||||
|
{
|
||||||
|
if (core) {
|
||||||
|
return core[primary].getAirSpdHealthData(innovation, innovationVariance, age_ms);
|
||||||
|
}
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
// Return the rate of change of vertical position in the down direction (dPosD/dt) in m/s
|
// Return the rate of change of vertical position in the down direction (dPosD/dt) in m/s
|
||||||
float NavEKF3::getPosDownDerivative() const
|
float NavEKF3::getPosDownDerivative() const
|
||||||
{
|
{
|
||||||
|
@ -84,6 +84,10 @@ public:
|
|||||||
// returns false if estimate is unavailable
|
// returns false if estimate is unavailable
|
||||||
bool getAirSpdVec(Vector3f &vel) const;
|
bool getAirSpdVec(Vector3f &vel) const;
|
||||||
|
|
||||||
|
// return the innovation in m/s, innovation variance in (m/s)^2 and age in msec of the last TAS measurement processed
|
||||||
|
// returns false if the data is unavilable
|
||||||
|
bool getAirSpdHealthData(float &innovation, float &innovationVariance, uint32_t &age_ms) const;
|
||||||
|
|
||||||
// Return the rate of change of vertical position in the down direction (dPosD/dt) in m/s
|
// Return the rate of change of vertical position in the down direction (dPosD/dt) in m/s
|
||||||
// This can be different to the z component of the EKF velocity state because it will fluctuate with height errors and corrections in the EKF
|
// This can be different to the z component of the EKF velocity state because it will fluctuate with height errors and corrections in the EKF
|
||||||
// but will always be kinematically consistent with the z component of the EKF position state
|
// but will always be kinematically consistent with the z component of the EKF position state
|
||||||
|
@ -191,6 +191,19 @@ bool NavEKF3_core::getAirSpdVec(Vector3f &vel) const
|
|||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// return the innovation in m/s, innovation variance in (m/s)^2 and age in msec of the last TAS measurement processed
|
||||||
|
// returns false if the data is unavailable
|
||||||
|
bool NavEKF3_core::getAirSpdHealthData(float &innovation, float &innovationVariance, uint32_t &age_ms) const
|
||||||
|
{
|
||||||
|
if (tasDataDelayed.time_ms == 0) {
|
||||||
|
// no data has been processed since startup
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
innovation = (float)innovVtas;
|
||||||
|
innovationVariance = (float)varInnovVtas;
|
||||||
|
age_ms = imuSampleTime_ms - tasDataDelayed.time_ms;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
// Return the rate of change of vertical position in the down direction (dPosD/dt) of the body frame origin in m/s
|
// Return the rate of change of vertical position in the down direction (dPosD/dt) of the body frame origin in m/s
|
||||||
float NavEKF3_core::getPosDownDerivative(void) const
|
float NavEKF3_core::getPosDownDerivative(void) const
|
||||||
|
@ -150,6 +150,10 @@ public:
|
|||||||
// returns false if estimate is unavailable
|
// returns false if estimate is unavailable
|
||||||
bool getAirSpdVec(Vector3f &vel) const;
|
bool getAirSpdVec(Vector3f &vel) const;
|
||||||
|
|
||||||
|
// return the innovation in m/s, innovation variance in (m/s)^2 and age in msec of the last TAS measurement processed
|
||||||
|
// returns false if the data is unavailable
|
||||||
|
bool getAirSpdHealthData(float &innovation, float &innovationVariance, uint32_t &age_ms) const;
|
||||||
|
|
||||||
// Return the rate of change of vertical position in the down direction (dPosD/dt) in m/s
|
// Return the rate of change of vertical position in the down direction (dPosD/dt) in m/s
|
||||||
// This can be different to the z component of the EKF velocity state because it will fluctuate with height errors and corrections in the EKF
|
// This can be different to the z component of the EKF velocity state because it will fluctuate with height errors and corrections in the EKF
|
||||||
// but will always be kinematically consistent with the z component of the EKF position state
|
// but will always be kinematically consistent with the z component of the EKF position state
|
||||||
|
Loading…
Reference in New Issue
Block a user