mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_AHRS: Add support for fixed height optical flow
This commit is contained in:
parent
6490436aca
commit
5d3e636d71
@ -2193,13 +2193,13 @@ bool AP_AHRS::get_filter_status(nav_filter_status &status) const
|
|||||||
}
|
}
|
||||||
|
|
||||||
// write optical flow data to EKF
|
// write optical flow data to EKF
|
||||||
void AP_AHRS::writeOptFlowMeas(const uint8_t rawFlowQuality, const Vector2f &rawFlowRates, const Vector2f &rawGyroRates, const uint32_t msecFlowMeas, const Vector3f &posOffset)
|
void AP_AHRS::writeOptFlowMeas(const uint8_t rawFlowQuality, const Vector2f &rawFlowRates, const Vector2f &rawGyroRates, const uint32_t msecFlowMeas, const Vector3f &posOffset, float heightOverride)
|
||||||
{
|
{
|
||||||
#if HAL_NAVEKF2_AVAILABLE
|
#if HAL_NAVEKF2_AVAILABLE
|
||||||
EKF2.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas, posOffset);
|
EKF2.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas, posOffset, heightOverride);
|
||||||
#endif
|
#endif
|
||||||
#if HAL_NAVEKF3_AVAILABLE
|
#if HAL_NAVEKF3_AVAILABLE
|
||||||
EKF3.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas, posOffset);
|
EKF3.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas, posOffset, heightOverride);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -236,7 +236,7 @@ public:
|
|||||||
bool get_vert_pos_rate(float &velocity) const;
|
bool get_vert_pos_rate(float &velocity) const;
|
||||||
|
|
||||||
// write optical flow measurements to EKF
|
// write optical flow measurements to EKF
|
||||||
void writeOptFlowMeas(const uint8_t rawFlowQuality, const Vector2f &rawFlowRates, const Vector2f &rawGyroRates, const uint32_t msecFlowMeas, const Vector3f &posOffset);
|
void writeOptFlowMeas(const uint8_t rawFlowQuality, const Vector2f &rawFlowRates, const Vector2f &rawGyroRates, const uint32_t msecFlowMeas, const Vector3f &posOffset, const float heightOverride);
|
||||||
|
|
||||||
// retrieve latest corrected optical flow samples (used for calibration)
|
// retrieve latest corrected optical flow samples (used for calibration)
|
||||||
bool getOptFlowSample(uint32_t& timeStamp_ms, Vector2f& flowRate, Vector2f& bodyRate, Vector2f& losPred) const;
|
bool getOptFlowSample(uint32_t& timeStamp_ms, Vector2f& flowRate, Vector2f& bodyRate, Vector2f& losPred) const;
|
||||||
|
Loading…
Reference in New Issue
Block a user