mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
AP_NavEKF3: Don't block no compass planes from running GPS alignment checks
This commit is contained in:
parent
6baeb1cd9d
commit
eb2ff2192d
@ -12,7 +12,7 @@
|
|||||||
*/
|
*/
|
||||||
void NavEKF3_core::calcGpsGoodToAlign(void)
|
void NavEKF3_core::calcGpsGoodToAlign(void)
|
||||||
{
|
{
|
||||||
if (inFlight && assume_zero_sideslip() && !use_compass()) {
|
if (inFlight && !finalInflightYawInit && assume_zero_sideslip() && !use_compass()) {
|
||||||
// this is a special case where a plane has launched without magnetometer
|
// this is a special case where a plane has launched without magnetometer
|
||||||
// is now in the air and needs to align yaw to the GPS and start navigating as soon as possible
|
// is now in the air and needs to align yaw to the GPS and start navigating as soon as possible
|
||||||
gpsGoodToAlign = true;
|
gpsGoodToAlign = true;
|
||||||
|
Loading…
Reference in New Issue
Block a user