mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_AHRS: Publish EKF ground speed limit
This commit is contained in:
parent
bc2255d6b1
commit
83775554ea
@ -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
|
||||
|
||||
|
@ -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…
Reference in New Issue
Block a user