mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_AHRS: add and use pr/EK3_FEATURE_OPTFLOW_FUSION
This commit is contained in:
parent
04292a280c
commit
c5b9d1dcbb
@ -42,6 +42,7 @@
|
|||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
#include <SITL/SITL.h>
|
#include <SITL/SITL.h>
|
||||||
#endif
|
#endif
|
||||||
|
#include <AP_NavEKF3/AP_NavEKF3_feature.h>
|
||||||
|
|
||||||
#define ATTITUDE_CHECK_THRESH_ROLL_PITCH_RAD radians(10)
|
#define ATTITUDE_CHECK_THRESH_ROLL_PITCH_RAD radians(10)
|
||||||
#define ATTITUDE_CHECK_THRESH_YAW_RAD radians(20)
|
#define ATTITUDE_CHECK_THRESH_YAW_RAD radians(20)
|
||||||
@ -2338,7 +2339,7 @@ void AP_AHRS::writeOptFlowMeas(const uint8_t rawFlowQuality, const Vector2f &ra
|
|||||||
#if HAL_NAVEKF2_AVAILABLE
|
#if HAL_NAVEKF2_AVAILABLE
|
||||||
EKF2.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas, posOffset, heightOverride);
|
EKF2.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas, posOffset, heightOverride);
|
||||||
#endif
|
#endif
|
||||||
#if HAL_NAVEKF3_AVAILABLE
|
#if EK3_FEATURE_OPTFLOW_FUSION
|
||||||
EKF3.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas, posOffset, heightOverride);
|
EKF3.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas, posOffset, heightOverride);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
@ -2346,7 +2347,7 @@ void AP_AHRS::writeOptFlowMeas(const uint8_t rawFlowQuality, const Vector2f &ra
|
|||||||
// retrieve latest corrected optical flow samples (used for calibration)
|
// retrieve latest corrected optical flow samples (used for calibration)
|
||||||
bool AP_AHRS::getOptFlowSample(uint32_t& timeStamp_ms, Vector2f& flowRate, Vector2f& bodyRate, Vector2f& losPred) const
|
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);
|
return EKF3.getOptFlowSample(timeStamp_ms, flowRate, bodyRate, losPred);
|
||||||
#endif
|
#endif
|
||||||
return false;
|
return false;
|
||||||
|
Loading…
Reference in New Issue
Block a user