mirror of https://github.com/ArduPilot/ardupilot
AP_InertialNav: Add function to return EKF height control limit
This commit is contained in:
parent
cf04600710
commit
51624149e1
|
@ -134,6 +134,21 @@ bool AP_InertialNav_NavEKF::get_hagl(float height) const
|
||||||
return valid;
|
return valid;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* 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
|
||||||
|
*/
|
||||||
|
bool AP_InertialNav_NavEKF::get_hgt_ctrl_limit(float limit) const
|
||||||
|
{
|
||||||
|
// true when estimate is valid
|
||||||
|
bool valid = _ahrs_ekf.get_NavEKF().getHeightControlLimit(limit);
|
||||||
|
// convert height from m to cm
|
||||||
|
limit *= 100.0f;
|
||||||
|
return valid;
|
||||||
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* get_velocity_z - returns the current climbrate.
|
* get_velocity_z - returns the current climbrate.
|
||||||
*
|
*
|
||||||
|
|
|
@ -94,6 +94,14 @@ public:
|
||||||
*/
|
*/
|
||||||
bool get_hagl(float hagl) const;
|
bool get_hagl(float hagl) const;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* 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
|
||||||
|
*/
|
||||||
|
bool get_hgt_ctrl_limit(float limit) const;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* get_velocity_z - returns the current climbrate.
|
* get_velocity_z - returns the current climbrate.
|
||||||
*
|
*
|
||||||
|
|
Loading…
Reference in New Issue