mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 08:53:56 -04:00
AP_NavEKF2: Ensure that GPS origin is set before using data for height
This commit is contained in:
parent
b8427e5d95
commit
97799ef0b3
@ -545,7 +545,7 @@ void NavEKF2_core::selectHeightForFusion()
|
|||||||
|
|
||||||
// determine if we should be using a height source other than baro
|
// determine if we should be using a height source other than baro
|
||||||
bool usingRangeForHgt = (frontend->_altSource == 1 && imuSampleTime_ms - rngValidMeaTime_ms < 500 && frontend->_fusionModeGPS == 3);
|
bool usingRangeForHgt = (frontend->_altSource == 1 && imuSampleTime_ms - rngValidMeaTime_ms < 500 && frontend->_fusionModeGPS == 3);
|
||||||
bool usingGpsForHgt = (frontend->_altSource == 2 && imuSampleTime_ms - lastTimeGpsReceived_ms < 500);
|
bool usingGpsForHgt = (frontend->_altSource == 2 && imuSampleTime_ms - lastTimeGpsReceived_ms < 500 && validOrigin);
|
||||||
|
|
||||||
// if there is new baro data to fuse, calculate filterred baro data required by other processes
|
// if there is new baro data to fuse, calculate filterred baro data required by other processes
|
||||||
if (baroDataToFuse) {
|
if (baroDataToFuse) {
|
||||||
|
Loading…
Reference in New Issue
Block a user