mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
AP_NavEKF3: rename using_external_yaw to using_noncompass_for_yaw
This commit is contained in:
parent
ce56bfe786
commit
0edfd2634f
@ -1466,13 +1466,13 @@ bool NavEKF3::use_compass(void) const
|
||||
return core[primary].use_compass();
|
||||
}
|
||||
|
||||
// are we using an external yaw source? Needed for ahrs attitudes_consistent
|
||||
bool NavEKF3::using_external_yaw(void) const
|
||||
// are we using (aka fusing) a non-compass yaw?
|
||||
bool NavEKF3::using_noncompass_for_yaw(void) const
|
||||
{
|
||||
if (!core) {
|
||||
return false;
|
||||
}
|
||||
return core[primary].using_external_yaw();
|
||||
return core[primary].using_noncompass_for_yaw();
|
||||
}
|
||||
|
||||
// check if configured to use GPS for horizontal position estimation
|
||||
|
@ -336,8 +336,8 @@ public:
|
||||
// write EKF information to on-board logs
|
||||
void Log_Write();
|
||||
|
||||
// are we using an external yaw source? This is needed by AHRS attitudes_consistent check
|
||||
bool using_external_yaw(void) const;
|
||||
// are we using (aka fusing) a non-compass yaw?
|
||||
bool using_noncompass_for_yaw() const;
|
||||
|
||||
// check if configured to use GPS for horizontal position estimation
|
||||
bool configuredToUseGPSForPosXY(void) const;
|
||||
|
@ -236,7 +236,7 @@ void NavEKF3_core::SelectBetaDragFusion()
|
||||
|
||||
// use of air data to constrain drift is necessary if we have limited sensor data or are doing inertial dead reckoning
|
||||
bool is_dead_reckoning = ((imuSampleTime_ms - lastPosPassTime_ms) > frontend->deadReckonDeclare_ms) && ((imuSampleTime_ms - lastVelPassTime_ms) > frontend->deadReckonDeclare_ms);
|
||||
const bool noYawSensor = !use_compass() && !using_external_yaw();
|
||||
const bool noYawSensor = !use_compass() && !using_noncompass_for_yaw();
|
||||
const bool f_required = (noYawSensor && (frontend->_betaMask & (1<<1))) || is_dead_reckoning;
|
||||
|
||||
// set true when sideslip fusion is feasible (requires zero sideslip assumption to be valid and use of wind states)
|
||||
|
@ -572,8 +572,8 @@ bool NavEKF3_core::use_compass(void) const
|
||||
!allMagSensorsFailed;
|
||||
}
|
||||
|
||||
// are we using a yaw source other than the magnetomer?
|
||||
bool NavEKF3_core::using_external_yaw(void) const
|
||||
// are we using (aka fusing) a non-compass yaw?
|
||||
bool NavEKF3_core::using_noncompass_for_yaw(void) const
|
||||
{
|
||||
const AP_NavEKF_Source::SourceYaw yaw_source = frontend->sources.getYawSource();
|
||||
#if EK3_FEATURE_EXTERNAL_NAV
|
||||
|
@ -394,8 +394,8 @@ public:
|
||||
// 6 was EXTERNAL_YAW_FALLBACK (do not use)
|
||||
};
|
||||
|
||||
// are we using an external yaw source? This is needed by AHRS attitudes_consistent check
|
||||
bool using_external_yaw(void) const;
|
||||
// are we using (aka fusing) a non-compass yaw?
|
||||
bool using_noncompass_for_yaw(void) 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);
|
||||
|
Loading…
Reference in New Issue
Block a user