AP_AHRS: Add public method to inhibit GPS useage when using EKF

This provides the calling vehicle software the abiity to request the EKF to not use GPS.
An integer is returned that indicates the type of operation available:
0 = request rejected (request will only be accepted if the EKF is in static mode, eg pre-armed)
1 = request accepted, attitude, vertical velocity and position estimates available
2 = request accepted, attitude, height rate, height, horizontal velocity and relative position estimates available
This commit is contained in:
priseborough 2014-11-13 05:49:15 +11:00 committed by Andrew Tridgell
parent e53d28854e
commit 5532750a99
2 changed files with 9 additions and 0 deletions

View File

@ -320,5 +320,11 @@ void AP_AHRS_NavEKF::writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlo
{
EKF.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas, rangeHealth, rawSonarRange);
}
// inhibit GPS useage
uint8_t AP_AHRS_NavEKF::setInhibitGPS(void)
{
return EKF.setInhibitGPS();;
}
#endif // AP_AHRS_NAVEKF_AVAILABLE

View File

@ -104,6 +104,9 @@ public:
// write optical flow measurements to EKF
void writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, uint8_t &rangeHealth, float &rawSonarRange);
// inibit GPS useage
uint8_t setInhibitGPS(void);
void set_ekf_use(bool setting) { _ekf_use.set(setting); }
// is the AHRS subsystem healthy?