AP_NavEKF3: add using_extnav_for_yaw

This commit is contained in:
Randy Mackay 2021-08-18 16:44:33 +09:00 committed by Andrew Tridgell
parent b984f1370c
commit 63e579d738
4 changed files with 26 additions and 0 deletions

View File

@ -1475,6 +1475,15 @@ bool NavEKF3::using_noncompass_for_yaw(void) const
return core[primary].using_noncompass_for_yaw();
}
// are we using (aka fusing) external nav for yaw?
bool NavEKF3::using_extnav_for_yaw() const
{
if (!core) {
return false;
}
return core[primary].using_extnav_for_yaw();
}
// check if configured to use GPS for horizontal position estimation
bool NavEKF3::configuredToUseGPSForPosXY(void) const
{

View File

@ -339,6 +339,9 @@ public:
// are we using (aka fusing) a non-compass yaw?
bool using_noncompass_for_yaw() const;
// are we using (aka fusing) external nav for yaw?
bool using_extnav_for_yaw() const;
// check if configured to use GPS for horizontal position estimation
bool configuredToUseGPSForPosXY(void) const;

View File

@ -588,6 +588,17 @@ bool NavEKF3_core::using_noncompass_for_yaw(void) const
return false;
}
// are we using (aka fusing) external nav for yaw?
bool NavEKF3_core::using_extnav_for_yaw() const
{
#if EK3_FEATURE_EXTERNAL_NAV
if (frontend->sources.getYawSource() == AP_NavEKF_Source::SourceYaw::EXTNAV) {
return ((imuSampleTime_ms - last_extnav_yaw_fusion_ms < 5000) || (imuSampleTime_ms - lastSynthYawTime_ms < 5000));
}
#endif
return false;
}
/*
should we assume zero sideslip?
*/

View File

@ -397,6 +397,9 @@ public:
// are we using (aka fusing) a non-compass yaw?
bool using_noncompass_for_yaw(void) const;
// are we using (aka fusing) external nav for yaw?
bool using_extnav_for_yaw() const;
// Writes the default equivalent airspeed and 1-sigma uncertainty in m/s to be used in forward flight if a measured airspeed is required and not available.
void writeDefaultAirSpeed(float airspeed, float uncertainty);