mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AP_Motors: expose throttle min and max
This commit is contained in:
parent
89b7e6b1c8
commit
a0298aee29
@ -104,6 +104,9 @@ public:
|
||||
// this is used to limit the amount that the stability patch will increase the throttle to give more room for roll, pitch and yaw control
|
||||
void set_mid_throttle(uint16_t mid_throttle);
|
||||
|
||||
int16_t throttle_min() const { return _min_throttle;}
|
||||
int16_t throttle_max() const { return _max_throttle;}
|
||||
|
||||
// output - sends commands to the motors
|
||||
void output();
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user