mirror of https://github.com/ArduPilot/ardupilot
AP_TECS: added get_max_climbrate()
This commit is contained in:
parent
b89988b2df
commit
c990714377
|
@ -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[];
|
||||
|
||||
|
|
Loading…
Reference in New Issue