Browse Source

AP_AHRS: Publish EKF ground speed limit

master
priseborough 10 years ago committed by Andrew Tridgell
parent
commit
83775554ea
  1. 9
      libraries/AP_AHRS/AP_AHRS_NavEKF.cpp
  2. 3
      libraries/AP_AHRS/AP_AHRS_NavEKF.h

9
libraries/AP_AHRS/AP_AHRS_NavEKF.cpp

@ -324,7 +324,14 @@ void AP_AHRS_NavEKF::writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlo @@ -324,7 +324,14 @@ void AP_AHRS_NavEKF::writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlo
// inhibit GPS useage
uint8_t AP_AHRS_NavEKF::setInhibitGPS(void)
{
return EKF.setInhibitGPS();;
return EKF.setInhibitGPS();
}
// get speed limit
float AP_AHRS_NavEKF::getSpeedLimit(void)
{
return EKF.getSpeedLimit();
}
#endif // AP_AHRS_NAVEKF_AVAILABLE

3
libraries/AP_AHRS/AP_AHRS_NavEKF.h

@ -107,6 +107,9 @@ public: @@ -107,6 +107,9 @@ public:
// inibit GPS useage
uint8_t setInhibitGPS(void);
// get speed limit
float getSpeedLimit(void);
void set_ekf_use(bool setting) { _ekf_use.set(setting); }
// is the AHRS subsystem healthy?

Loading…
Cancel
Save