mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
AP_NavEKF3: optical flow fusion checks source
This commit is contained in:
parent
4cadaa5194
commit
8a56ce49be
@ -52,7 +52,7 @@ void NavEKF3_core::SelectFlowFusion()
|
|||||||
|
|
||||||
// Fuse optical flow data into the main filter
|
// Fuse optical flow data into the main filter
|
||||||
if (flowDataToFuse && tiltOK) {
|
if (flowDataToFuse && tiltOK) {
|
||||||
if (frontend->_flowUse == FLOW_USE_NAV) {
|
if ((frontend->_flowUse == FLOW_USE_NAV) && (frontend->_sources.getVelXYSource() == AP_NavEKF_Source::SourceXY::OPTFLOW)) {
|
||||||
// Set the flow noise used by the fusion processes
|
// Set the flow noise used by the fusion processes
|
||||||
R_LOS = sq(MAX(frontend->_flowNoise, 0.05f));
|
R_LOS = sq(MAX(frontend->_flowNoise, 0.05f));
|
||||||
// Fuse the optical flow X and Y axis data into the main filter sequentially
|
// Fuse the optical flow X and Y axis data into the main filter sequentially
|
||||||
|
Loading…
Reference in New Issue
Block a user