AP_TECS: added get_max_climbrate()

This commit is contained in:
Andrew Tridgell 2014-08-07 09:29:31 +10:00
parent b89988b2df
commit c990714377
1 changed files with 3 additions and 0 deletions

View File

@ -69,6 +69,9 @@ public:
// return current target airspeed
float get_target_airspeed(void) const { return _TAS_dem / _ahrs.get_EAS2TAS(); }
// return maximum climb rate
float get_max_climbrate(void) const { return _maxClimbRate; }
// this supports the TECS_* user settable parameters
static const struct AP_Param::GroupInfo var_info[];