mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF: fixed some matlab ! -> ~ typos
Pair-Programmed-With: Paul Riseborough <p_riseborough@live.com.au>
This commit is contained in:
parent
5a7afbf2cd
commit
68f1ae3036
|
@ -1580,7 +1580,7 @@ void NavEKF::FuseVelPosNED()
|
||||||
else gpsRetryTime = _gpsRetryTimeNoTAS;
|
else gpsRetryTime = _gpsRetryTimeNoTAS;
|
||||||
|
|
||||||
// form the observation vector and zero velocity and horizontal position observations if in static mode
|
// form the observation vector and zero velocity and horizontal position observations if in static mode
|
||||||
if (~staticMode) {
|
if (!staticMode) {
|
||||||
for (uint8_t i=0; i<=2; i++) observation[i] = velNED[i];
|
for (uint8_t i=0; i<=2; i++) observation[i] = velNED[i];
|
||||||
for (uint8_t i=3; i<=4; i++) observation[i] = posNE[i-3];
|
for (uint8_t i=3; i<=4; i++) observation[i] = posNE[i-3];
|
||||||
} else {
|
} else {
|
||||||
|
@ -1715,7 +1715,7 @@ void NavEKF::FuseVelPosNED()
|
||||||
velFailTime = hal.scheduler->millis();
|
velFailTime = hal.scheduler->millis();
|
||||||
}
|
}
|
||||||
// if data is not healthy and timed out and position is unhealthy we reset the velocity, but do not fuse data on this time step
|
// if data is not healthy and timed out and position is unhealthy we reset the velocity, but do not fuse data on this time step
|
||||||
else if (velTimeout && ~posHealth) {
|
else if (velTimeout && !posHealth) {
|
||||||
ResetVelocity();
|
ResetVelocity();
|
||||||
StoreStatesReset();
|
StoreStatesReset();
|
||||||
fuseVelData = false;
|
fuseVelData = false;
|
||||||
|
|
Loading…
Reference in New Issue