mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_NavEKF2: Remove unnecessary logic preventing constant position
This removes a legacy design concept that is no longer required in this filter implementation. Planes will not be armed without EKF aiding and the proposed copter throw mode also requires EKF aiding to be operating. The other problem with interrupting fusion during the launch is it doesn't reduce the corrections, it just delays them as wen the launch completes, the EKF inertial position estimate is still moving still moved and the corrections are therefore just delayed by the short launch interval. Thank you to OXINARF for picking up the inconsistency with the previous logic
This commit is contained in:
parent
7e05646316
commit
59bf29198d
@ -175,13 +175,7 @@ void NavEKF2_core::SelectVelPosFusion()
|
||||
gpsDataDelayed.vel.zero();
|
||||
gpsDataDelayed.pos.x = lastKnownPositionNE.x;
|
||||
gpsDataDelayed.pos.y = lastKnownPositionNE.y;
|
||||
// when in flight only fuse synthetic measurements when rate of change of velocity is less than 1.1g
|
||||
// to reduce attitude errors due to launch acceleration
|
||||
if (accNavMag < 1.1f * GRAVITY_MSS || motorsArmed) {
|
||||
fusePosData = true;
|
||||
} else {
|
||||
fusePosData = false;
|
||||
}
|
||||
fusePosData = true;
|
||||
fuseVelData = false;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user