mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
AP_NavEKF: Do not perform start-up yaw alignment if no compass
Yaw cannot be aligned until in-flight when there is sufficient GPS velocity.
This commit is contained in:
parent
d2694fe5dc
commit
08de4e6d95
@ -172,7 +172,7 @@ void NavEKF2_core::checkAttitudeAlignmentStatus()
|
||||
}
|
||||
|
||||
// Once tilt has converged, align yaw using magnetic field measurements
|
||||
if (tiltAlignComplete && !yawAlignComplete) {
|
||||
if (tiltAlignComplete && !yawAlignComplete && use_compass()) {
|
||||
Vector3f eulerAngles;
|
||||
stateStruct.quat.to_euler(eulerAngles.x, eulerAngles.y, eulerAngles.z);
|
||||
stateStruct.quat = calcQuatAndFieldStates(eulerAngles.x, eulerAngles.y);
|
||||
|
Loading…
Reference in New Issue
Block a user