mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_NavEKF3: add configuredToUseGPSForPosXY
This commit is contained in:
parent
4087d7b792
commit
adfc92523b
@ -1418,6 +1418,13 @@ bool NavEKF3::using_external_yaw(void) const
|
||||
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
|
||||
// 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.
|
||||
|
@ -387,7 +387,10 @@ public:
|
||||
|
||||
// are we using an external yaw source? This is needed by AHRS attitudes_consistent check
|
||||
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.
|
||||
void writeDefaultAirSpeed(float airspeed);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user