AP_NavEKF3: add configuredToUseGPSForPosXY

This commit is contained in:
Randy Mackay 2020-11-24 14:54:20 +09:00 committed by Andrew Tridgell
parent 4087d7b792
commit adfc92523b
2 changed files with 11 additions and 1 deletions

View File

@ -1418,6 +1418,13 @@ bool NavEKF3::using_external_yaw(void) const
return core[primary].using_external_yaw(); return core[primary].using_external_yaw();
} }
// check if configured to use GPS for horizontal position estimation
bool NavEKF3::configuredToUseGPSForPosXY(void) const
{
// 0 = use 3D velocity, 1 = use 2D velocity, 2 = use no velocity, 3 = do not use GPS
return (sources.getPosXYSource() == AP_NavEKF_Source::SourceXY::GPS);
}
// write the raw optical flow measurements // write the raw optical flow measurements
// rawFlowQuality is a measured of quality between 0 and 255, with 255 being the best quality // rawFlowQuality is a measured of quality between 0 and 255, with 255 being the best quality
// rawFlowRates are the optical flow rates in rad/sec about the X and Y sensor axes. // rawFlowRates are the optical flow rates in rad/sec about the X and Y sensor axes.

View File

@ -388,6 +388,9 @@ public:
// are we using an external yaw source? This is needed by AHRS attitudes_consistent check // are we using an external yaw source? This is needed by AHRS attitudes_consistent check
bool using_external_yaw(void) const; bool using_external_yaw(void) const;
// check if configured to use GPS for horizontal position estimation
bool configuredToUseGPSForPosXY(void) const;
// Writes the default equivalent airspeed in m/s to be used in forward flight if a measured airspeed is required and not available. // Writes the default equivalent airspeed in m/s to be used in forward flight if a measured airspeed is required and not available.
void writeDefaultAirSpeed(float airspeed); void writeDefaultAirSpeed(float airspeed);