AP_AHRS: implement get_hgt_ctrl_limit on base class

If no limits are required false can be returned, so an trivial
implementation is possible
This commit is contained in:
Peter Barker 2017-12-07 15:51:28 +11:00 committed by Randy Mackay
parent 89e12163cd
commit 8a4ab685c7
2 changed files with 6 additions and 1 deletions

View File

@ -563,6 +563,11 @@ public:
virtual void update_AOA_SSA(void);
// get_hgt_ctrl_limit - get maximum height to be observed by the
// control loops in meters and a validity flag. It will return
// false when no limiting is required
virtual bool get_hgt_ctrl_limit(float &limit) const { return false; };
protected:
AHRS_VehicleClass _vehicle_class;

View File

@ -223,7 +223,7 @@ public:
// get_hgt_ctrl_limit - get maximum height to be observed by the control loops in meters and a validity flag
// this is used to limit height during optical flow navigation
// it will return invalid when no limiting is required
bool get_hgt_ctrl_limit(float &limit) const;
bool get_hgt_ctrl_limit(float &limit) const override;
// get_llh - updates the provided location with the latest calculated location including absolute altitude
// returns true on success (i.e. the EKF knows it's latest position), false on failure