mirror of https://github.com/ArduPilot/ardupilot
AP_AHRS : Add range finder health status to EKF optical flow data
This commit is contained in:
parent
27f9289391
commit
a4984a1e76
|
@ -318,9 +318,9 @@ bool AP_AHRS_NavEKF::initialised(void) const
|
||||||
};
|
};
|
||||||
|
|
||||||
// write optical flow data to EKF
|
// write optical flow data to EKF
|
||||||
void AP_AHRS_NavEKF::writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, float &rawSonarRange, uint32_t &msecFlowMeas)
|
void AP_AHRS_NavEKF::writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, uint8_t &rangeHealth, float &rawSonarRange)
|
||||||
{
|
{
|
||||||
EKF.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, rawSonarRange, msecFlowMeas);
|
EKF.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas, rangeHealth, rawSonarRange);
|
||||||
}
|
}
|
||||||
#endif // AP_AHRS_NAVEKF_AVAILABLE
|
#endif // AP_AHRS_NAVEKF_AVAILABLE
|
||||||
|
|
||||||
|
|
|
@ -102,7 +102,7 @@ public:
|
||||||
bool get_relative_position_NED(Vector3f &vec) const;
|
bool get_relative_position_NED(Vector3f &vec) const;
|
||||||
|
|
||||||
// write optical flow measurements to EKF
|
// write optical flow measurements to EKF
|
||||||
void writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, float &rawSonarRange, uint32_t &msecFlowMeas);
|
void writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, uint8_t &rangeHealth, float &rawSonarRange);
|
||||||
|
|
||||||
void set_ekf_use(bool setting) { _ekf_use.set(setting); }
|
void set_ekf_use(bool setting) { _ekf_use.set(setting); }
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue