mirror of https://github.com/ArduPilot/ardupilot
AP_InertialNav: expose get_hgt_ctrl_limit to parent class
This commit is contained in:
parent
d2431dafd0
commit
e7ba2420c1
|
@ -104,6 +104,14 @@ public:
|
|||
*/
|
||||
virtual float get_altitude() const = 0;
|
||||
|
||||
/**
|
||||
* get_hgt_ctrl_limit - get maximum height to be observed by the control loops in cm and a validity flag
|
||||
* this is used to limit height during optical flow navigation
|
||||
* it will return invalid when no limiting is required
|
||||
* @return
|
||||
*/
|
||||
virtual bool get_hgt_ctrl_limit(float& limit) const = 0;
|
||||
|
||||
/**
|
||||
* get_velocity_z - returns the current climbrate.
|
||||
*
|
||||
|
|
Loading…
Reference in New Issue