AP_Motors: Constrain get_throttle_hover value with allowed range

This commit is contained in:
Sergey Bokhantsev 2021-03-31 22:31:28 +03:00 committed by Randy Mackay
parent f988064e48
commit ef95bf088c
2 changed files with 2 additions and 2 deletions

View File

@ -125,7 +125,7 @@ public:
// update estimated throttle required to hover
void update_throttle_hover(float dt);
float get_throttle_hover() const override { return _collective_hover; }
float get_throttle_hover() const override { return constrain_float(_collective_hover, AP_MOTORS_HELI_COLLECTIVE_HOVER_MIN, AP_MOTORS_HELI_COLLECTIVE_HOVER_MAX); }
// accessor to get the takeoff collective flag signifying that current collective is greater than collective required to indicate takeoff
bool get_takeoff_collective() const { return _heliflags.takeoff_collective; }

View File

@ -50,7 +50,7 @@ public:
// update estimated throttle required to hover
void update_throttle_hover(float dt);
virtual float get_throttle_hover() const override { return _throttle_hover; }
virtual float get_throttle_hover() const override { return constrain_float(_throttle_hover, AP_MOTORS_THST_HOVER_MIN, AP_MOTORS_THST_HOVER_MAX); }
// passes throttle directly to all motors for ESC calibration.
// throttle_input is in the range of 0 ~ 1 where 0 will send get_pwm_output_min() and 1 will send get_pwm_output_max()