mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 17:48:35 -04:00
AP_NavEKF3: added optflow support for AP_DAL
This commit is contained in:
parent
224792b8b8
commit
7bbbbd314c
@ -172,6 +172,8 @@ void NavEKF3_core::writeWheelOdom(float delAng, float delTime, uint32_t timeStam
|
|||||||
// this needs to be called externally.
|
// this needs to be called externally.
|
||||||
void NavEKF3_core::writeOptFlowMeas(const uint8_t rawFlowQuality, const Vector2f &rawFlowRates, const Vector2f &rawGyroRates, const uint32_t msecFlowMeas, const Vector3f &posOffset)
|
void NavEKF3_core::writeOptFlowMeas(const uint8_t rawFlowQuality, const Vector2f &rawFlowRates, const Vector2f &rawGyroRates, const uint32_t msecFlowMeas, const Vector3f &posOffset)
|
||||||
{
|
{
|
||||||
|
AP::dal().writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas, posOffset);
|
||||||
|
|
||||||
// limit update rate to maximum allowed by sensor buffers
|
// limit update rate to maximum allowed by sensor buffers
|
||||||
if ((imuSampleTime_ms - flowMeaTime_ms) < frontend->sensorIntervalMin_ms) {
|
if ((imuSampleTime_ms - flowMeaTime_ms) < frontend->sensorIntervalMin_ms) {
|
||||||
return;
|
return;
|
||||||
|
Loading…
Reference in New Issue
Block a user