mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
AP_Motors: prevent negative thrust
this prevents a sqrt of a negative number
This commit is contained in:
parent
9f33ece3ef
commit
a2ed8fb313
@ -328,6 +328,7 @@ float AP_MotorsMulticopter::get_compensation_gain() const
|
|||||||
|
|
||||||
int16_t AP_MotorsMulticopter::calc_thrust_to_pwm(float thrust_in) const
|
int16_t AP_MotorsMulticopter::calc_thrust_to_pwm(float thrust_in) const
|
||||||
{
|
{
|
||||||
|
thrust_in = constrain_float(thrust_in, 0, 1);
|
||||||
return constrain_int16((get_pwm_output_min() + _min_throttle + apply_thrust_curve_and_volt_scaling(thrust_in) *
|
return constrain_int16((get_pwm_output_min() + _min_throttle + apply_thrust_curve_and_volt_scaling(thrust_in) *
|
||||||
(get_pwm_output_max() - (get_pwm_output_min() + _min_throttle))), get_pwm_output_min() + _min_throttle, get_pwm_output_max());
|
(get_pwm_output_max() - (get_pwm_output_min() + _min_throttle))), get_pwm_output_min() + _min_throttle, get_pwm_output_max());
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user