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:
parent
89e12163cd
commit
8a4ab685c7
@ -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;
|
||||
|
||||
|
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user