Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_NavEKF3: ignore VelZ of body odometry if SRCn_VELZ is set to None #28548

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 4 additions & 1 deletion libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2031,7 +2031,10 @@ void NavEKF3_core::SelectBodyOdomFusion()
// Check for body odometry data (aka visual position delta) at the fusion time horizon
const bool bodyOdomDataToFuse = storedBodyOdm.recall(bodyOdmDataDelayed, imuDataDelayed.time_ms);
if (bodyOdomDataToFuse && frontend->sources.useVelXYSource(AP_NavEKF_Source::SourceXY::EXTNAV)) {

// If VelZ source is set to none, don't use the odometry data for Z velocity
if (!frontend->sources.haveVelZSource()) {
bodyOdmDataDelayed.vel.z = stateStruct.velocity.z;
}
// Fuse data into the main filter
FuseBodyVel();
}
Expand Down
Loading