mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
AP_TECS: added get_land_sinkrate()
This commit is contained in:
parent
8c1cab84c7
commit
70f5ec60e8
@ -73,6 +73,9 @@ public:
|
|||||||
// return maximum climb rate
|
// return maximum climb rate
|
||||||
float get_max_climbrate(void) const { return _maxClimbRate; }
|
float get_max_climbrate(void) const { return _maxClimbRate; }
|
||||||
|
|
||||||
|
// return landing sink rate
|
||||||
|
float get_land_sinkrate(void) const { return _land_sink; }
|
||||||
|
|
||||||
// this supports the TECS_* user settable parameters
|
// this supports the TECS_* user settable parameters
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user