mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_NavEKF3: Don't allow mag to interfere with use of external yaw sensor
This commit is contained in:
parent
b56914b879
commit
122f214416
@ -450,7 +450,7 @@ bool NavEKF3_core::readyToUseRangeBeacon(void) const
|
||||
// return true if we should use the compass
|
||||
bool NavEKF3_core::use_compass(void) const
|
||||
{
|
||||
return _ahrs->get_compass() && _ahrs->get_compass()->use_for_yaw(magSelectIndex) && !allMagSensorsFailed;
|
||||
return (frontend->_magCal != 5) && _ahrs->get_compass() && _ahrs->get_compass()->use_for_yaw(magSelectIndex) && !allMagSensorsFailed;
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -261,7 +261,7 @@ void NavEKF3_core::SelectMagFusion()
|
||||
magFusePerformed = false;
|
||||
|
||||
// Handle case where we are using an external yaw sensor instead of a magnetomer
|
||||
if ((frontend->_magCal == 5) && !use_compass()) {
|
||||
if ((frontend->_magCal == 5)) {
|
||||
if (storedYawAng.recall(yawAngDataDelayed,imuDataDelayed.time_ms)) {
|
||||
if (tiltAlignComplete && !yawAlignComplete) {
|
||||
alignYawAngle();
|
||||
|
Loading…
Reference in New Issue
Block a user