mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 23:43:58 -04:00
AP_MotorsMuticopter: calc_thrust_to_pwm converts thrust in 0 to 1 range to pwm
pwm output is always between throttle min and throttle max
This commit is contained in:
parent
80ddce103f
commit
cb39f8aab7
@ -352,6 +352,12 @@ float AP_MotorsMulticopter::thr_range_to_rel_pwm(float thr) const
|
|||||||
return _throttle_pwm_scalar*thr;
|
return _throttle_pwm_scalar*thr;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
int16_t AP_MotorsMulticopter::calc_thrust_to_pwm(float thrust_in) const
|
||||||
|
{
|
||||||
|
return constrain_int16((_throttle_radio_min + _min_throttle + apply_thrust_curve_and_volt_scaling(thrust_in) *
|
||||||
|
( _throttle_radio_max - (_throttle_radio_min + _min_throttle))), _throttle_radio_min + _min_throttle, _throttle_radio_max);
|
||||||
|
}
|
||||||
|
|
||||||
// set_throttle_range - sets the minimum throttle that will be sent to the engines when they're not off (i.e. to prevents issues with some motors spinning and some not at very low throttle)
|
// set_throttle_range - sets the minimum throttle that will be sent to the engines when they're not off (i.e. to prevents issues with some motors spinning and some not at very low throttle)
|
||||||
// also sets throttle channel minimum and maximum pwm
|
// also sets throttle channel minimum and maximum pwm
|
||||||
void AP_MotorsMulticopter::set_throttle_range(uint16_t min_throttle, int16_t radio_min, int16_t radio_max)
|
void AP_MotorsMulticopter::set_throttle_range(uint16_t min_throttle, int16_t radio_min, int16_t radio_max)
|
||||||
|
@ -139,6 +139,9 @@ protected:
|
|||||||
float calc_yaw_pwm() { return (_yaw_control_input * _rpy_pwm_scalar); }
|
float calc_yaw_pwm() { return (_yaw_control_input * _rpy_pwm_scalar); }
|
||||||
int16_t calc_throttle_radio_output() { return (_throttle_control_input * _throttle_pwm_scalar) + _throttle_radio_min;}
|
int16_t calc_throttle_radio_output() { return (_throttle_control_input * _throttle_pwm_scalar) + _throttle_radio_min;}
|
||||||
|
|
||||||
|
// convert thrust (0~1) range back to pwm range
|
||||||
|
int16_t calc_thrust_to_pwm(float thrust_in) const;
|
||||||
|
|
||||||
// flag bitmask
|
// flag bitmask
|
||||||
struct {
|
struct {
|
||||||
uint8_t slow_start : 1; // 1 if slow start is active
|
uint8_t slow_start : 1; // 1 if slow start is active
|
||||||
|
Loading…
Reference in New Issue
Block a user