mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_AHRS: Expand EKF speed limit public method to handle control limits
This commit is contained in:
parent
d994da0886
commit
5b8265ad6f
@ -328,9 +328,9 @@ uint8_t AP_AHRS_NavEKF::setInhibitGPS(void)
|
||||
}
|
||||
|
||||
// get speed limit
|
||||
float AP_AHRS_NavEKF::getSpeedLimit(void)
|
||||
void AP_AHRS_NavEKF::getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler)
|
||||
{
|
||||
return EKF.getSpeedLimit();
|
||||
EKF.getEkfControlLimits(ekfGndSpdLimit,ekfNavVelGainScaler);
|
||||
}
|
||||
|
||||
#endif // AP_AHRS_NAVEKF_AVAILABLE
|
||||
|
@ -108,7 +108,7 @@ public:
|
||||
uint8_t setInhibitGPS(void);
|
||||
|
||||
// get speed limit
|
||||
float getSpeedLimit(void);
|
||||
void getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler);
|
||||
|
||||
void set_ekf_use(bool setting) { _ekf_use.set(setting); }
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user