mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_Motors: add get for throttle comp
This commit is contained in:
parent
791fbcf9b3
commit
88be3d67e7
@ -158,6 +158,9 @@ public:
|
|||||||
// has no effect when throttle is above hover throttle
|
// has no effect when throttle is above hover throttle
|
||||||
void set_throttle_low_comp(float throttle_low_comp) { _throttle_low_comp_desired = throttle_low_comp; }
|
void set_throttle_low_comp(float throttle_low_comp) { _throttle_low_comp_desired = throttle_low_comp; }
|
||||||
|
|
||||||
|
// get_throttle_low_comp - get low throttle compensation value
|
||||||
|
float get_throttle_low_comp() { return _throttle_low_comp; }
|
||||||
|
|
||||||
// get_lift_max - get maximum lift ratio
|
// get_lift_max - get maximum lift ratio
|
||||||
float get_lift_max() { return _lift_max; }
|
float get_lift_max() { return _lift_max; }
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user