Browse Source

AP_NavEKF2: add configuredToUseGPSForPosXY

zr-v5.1
Randy Mackay 4 years ago committed by Andrew Tridgell
parent
commit
4087d7b792
  1. 7
      libraries/AP_NavEKF2/AP_NavEKF2.cpp
  2. 3
      libraries/AP_NavEKF2/AP_NavEKF2.h

7
libraries/AP_NavEKF2/AP_NavEKF2.cpp

@ -1694,6 +1694,13 @@ bool NavEKF2::isExtNavUsedForYaw() const
return false; return false;
} }
// check if configured to use GPS for horizontal position estimation
bool NavEKF2::configuredToUseGPSForPosXY(void) const
{
// 0 = use 3D velocity, 1 = use 2D velocity, 2 = use no velocity, 3 = do not use GPS
return (_fusionModeGPS.get() != 3);
}
void NavEKF2::requestYawReset(void) void NavEKF2::requestYawReset(void)
{ {
AP::dal().log_event2(AP_DAL::Event::requestYawReset); AP::dal().log_event2(AP_DAL::Event::requestYawReset);

3
libraries/AP_NavEKF2/AP_NavEKF2.h

@ -362,6 +362,9 @@ public:
// check if external navigation is being used for yaw observation // check if external navigation is being used for yaw observation
bool isExtNavUsedForYaw(void) const; bool isExtNavUsedForYaw(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);

Loading…
Cancel
Save