mirror of https://github.com/ArduPilot/ardupilot
AP_TECS: created accessor for TECS_LAND_ARSPD param
This commit is contained in:
parent
0af322e90d
commit
525c7b24e3
|
@ -68,8 +68,11 @@ public:
|
|||
// return maximum climb rate
|
||||
virtual float get_max_climbrate(void) const = 0;
|
||||
|
||||
// return landing sink rate
|
||||
virtual float get_land_sinkrate(void) const = 0;
|
||||
// return landing sink rate
|
||||
virtual float get_land_sinkrate(void) const = 0;
|
||||
|
||||
// return landing airspeed
|
||||
virtual float get_land_airspeed(void) const = 0;
|
||||
|
||||
// set path_proportion accessor
|
||||
virtual void set_path_proportion(float path_proportion) = 0;
|
||||
|
|
|
@ -87,6 +87,11 @@ public:
|
|||
return _land_sink;
|
||||
}
|
||||
|
||||
// return landing airspeed
|
||||
float get_land_airspeed(void) const {
|
||||
return _landAirspeed;
|
||||
}
|
||||
|
||||
// return height rate demand, in m/s
|
||||
float get_height_rate_demand(void) const {
|
||||
return _hgt_rate_dem;
|
||||
|
|
Loading…
Reference in New Issue