AC_PosControl: add get_alt_error method

This commit is contained in:
Randy Mackay 2014-01-06 12:30:51 +09:00 committed by Andrew Tridgell
parent abb42bcb41
commit 3ce1c0a9d5
2 changed files with 14 additions and 4 deletions

View File

@ -61,6 +61,12 @@ AC_PosControl::AC_PosControl(const AP_AHRS& ahrs, const AP_InertialNav& inav,
/// z-axis position controller
///
// get_alt_error - returns altitude error in cm
float AC_PosControl::get_alt_error() const
{
return (_pos_target.z - _inav.get_position().z);
}
/// set_target_to_stopping_point_z - returns reasonable stopping altitude in cm above home
void AC_PosControl::set_target_to_stopping_point_z()
{

View File

@ -67,9 +67,13 @@ public:
///
void set_alt_target(float alt_cm) { _pos_target.z = alt_cm; }
/// get_alt_target, get_desired_alt - get desired altitude (in cm above home) from loiter or wp controller which should be fed into throttle controller
/// To-Do: remove one of the two functions below
float get_alt_target() const { return _pos_target.z; }
/// get_desired_alt - get desired altitude (in cm above home) from loiter or wp controller which should be fed into throttle controller
float get_desired_alt() const { return _pos_target.z; }
// get_alt_error - returns altitude error in cm
float get_alt_error() const;
/// set_target_to_stopping_point_z - sets altitude target to reasonable stopping altitude in cm above home
void set_target_to_stopping_point_z();