Skip to content

Commit

Permalink
AP_AHRS: add and use pr/EK3_FEATURE_OPTFLOW_FUSION
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker committed May 9, 2023
1 parent 28598e8 commit 77cad5c
Showing 1 changed file with 3 additions and 2 deletions.
5 changes: 3 additions & 2 deletions libraries/AP_AHRS/AP_AHRS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@
#include <GCS_MAVLink/GCS.h>
#include <AP_InertialSensor/AP_InertialSensor.h>
#include <AP_CustomRotations/AP_CustomRotations.h>
#include <AP_NavEKF3/AP_NavEKF3_feature.h>

#define ATTITUDE_CHECK_THRESH_ROLL_PITCH_RAD radians(10)
#define ATTITUDE_CHECK_THRESH_YAW_RAD radians(20)
Expand Down Expand Up @@ -2105,15 +2106,15 @@ void AP_AHRS::writeOptFlowMeas(const uint8_t rawFlowQuality, const Vector2f &ra
#if HAL_NAVEKF2_AVAILABLE
EKF2.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas, posOffset, heightOverride);
#endif
#if HAL_NAVEKF3_AVAILABLE
#if EK3_FEATURE_OPTFLOW_FUSION
EKF3.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas, posOffset, heightOverride);
#endif
}

// retrieve latest corrected optical flow samples (used for calibration)
bool AP_AHRS::getOptFlowSample(uint32_t& timeStamp_ms, Vector2f& flowRate, Vector2f& bodyRate, Vector2f& losPred) const
{
#if HAL_NAVEKF3_AVAILABLE
#if EK3_FEATURE_OPTFLOW_FUSION
return EKF3.getOptFlowSample(timeStamp_ms, flowRate, bodyRate, losPred);
#endif
return false;
Expand Down

0 comments on commit 77cad5c

Please sign in to comment.