mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
AP_NavEKF3: use err info from ext nav interface
This commit is contained in:
parent
5e5a0d2111
commit
9b448b83c0
@ -963,11 +963,7 @@ void NavEKF3_core::writeExtNavData(const Vector3f &pos, const Quaternion &quat,
|
||||
}
|
||||
|
||||
extNavDataNew.pos = pos;
|
||||
if (posErr > 0) {
|
||||
extNavDataNew.posErr = posErr;
|
||||
} else {
|
||||
extNavDataNew.posErr = frontend->_gpsHorizPosNoise;
|
||||
}
|
||||
extNavDataNew.posErr = posErr;
|
||||
|
||||
// calculate timestamp
|
||||
timeStamp_ms = timeStamp_ms - delay_ms;
|
||||
|
Loading…
Reference in New Issue
Block a user