AP_Motors: remove use of external PWM min and max

This commit is contained in:
Iampete1 2021-09-04 18:11:49 +01:00 committed by Randy Mackay
parent a69f40b7fb
commit 14dfac42e7
4 changed files with 15 additions and 58 deletions

View File

@ -232,7 +232,7 @@ void AP_Motors6DOF::output_min()
int16_t AP_Motors6DOF::calc_thrust_to_pwm(float thrust_in) const int16_t AP_Motors6DOF::calc_thrust_to_pwm(float thrust_in) const
{ {
return constrain_int16(1500 + thrust_in * 400, _throttle_radio_min, _throttle_radio_max); return constrain_int16(1500 + thrust_in * 400, get_pwm_output_min(), get_pwm_output_max());
} }
void AP_Motors6DOF::output_to_motors() void AP_Motors6DOF::output_to_motors()

View File

@ -85,19 +85,19 @@ const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = {
// @Param: PWM_MIN // @Param: PWM_MIN
// @DisplayName: PWM output minimum // @DisplayName: PWM output minimum
// @Description: This sets the min PWM output value in microseconds that will ever be output to the motors, 0 = use input RC3_MIN // @Description: This sets the min PWM output value in microseconds that will ever be output to the motors
// @Units: PWM // @Units: PWM
// @Range: 0 2000 // @Range: 0 2000
// @User: Advanced // @User: Advanced
AP_GROUPINFO("PWM_MIN", 16, AP_MotorsMulticopter, _pwm_min, 0), AP_GROUPINFO("PWM_MIN", 16, AP_MotorsMulticopter, _pwm_min, 1000),
// @Param: PWM_MAX // @Param: PWM_MAX
// @DisplayName: PWM output maximum // @DisplayName: PWM output maximum
// @Description: This sets the max PWM value in microseconds that will ever be output to the motors, 0 = use input RC3_MAX // @Description: This sets the max PWM value in microseconds that will ever be output to the motors
// @Units: PWM // @Units: PWM
// @Range: 0 2000 // @Range: 0 2000
// @User: Advanced // @User: Advanced
AP_GROUPINFO("PWM_MAX", 17, AP_MotorsMulticopter, _pwm_max, 0), AP_GROUPINFO("PWM_MAX", 17, AP_MotorsMulticopter, _pwm_max, 2000),
// @Param: SPIN_MIN // @Param: SPIN_MIN
// @DisplayName: Motor Spin minimum // @DisplayName: Motor Spin minimum
@ -221,9 +221,6 @@ AP_MotorsMulticopter::AP_MotorsMulticopter(uint16_t loop_rate, uint16_t speed_hz
_batt_voltage_filt.set_cutoff_frequency(AP_MOTORS_BATT_VOLT_FILT_HZ); _batt_voltage_filt.set_cutoff_frequency(AP_MOTORS_BATT_VOLT_FILT_HZ);
_batt_voltage_filt.reset(1.0f); _batt_voltage_filt.reset(1.0f);
// default throttle range
_throttle_radio_min = 1100;
_throttle_radio_max = 1900;
}; };
// output - sends commands to the motors // output - sends commands to the motors
@ -485,59 +482,23 @@ float AP_MotorsMulticopter::actuator_spin_up_to_ground_idle() const
return constrain_float(_spin_up_ratio, 0.0f, 1.0f) * _spin_min; return constrain_float(_spin_up_ratio, 0.0f, 1.0f) * _spin_min;
} }
// get minimum pwm value that can be output to motors
int16_t AP_MotorsMulticopter::get_pwm_output_min() const
{
// return _pwm_min if both PWM_MIN and PWM_MAX parameters are defined and valid
if ((_pwm_min > 0) && (_pwm_max > 0) && (_pwm_max > _pwm_min)) {
return _pwm_min;
}
return _throttle_radio_min;
}
// get maximum pwm value that can be output to motors
int16_t AP_MotorsMulticopter::get_pwm_output_max() const
{
// return _pwm_max if both PWM_MIN and PWM_MAX parameters are defined and valid
if ((_pwm_min > 0) && (_pwm_max > 0) && (_pwm_max > _pwm_min)) {
return _pwm_max;
}
return _throttle_radio_max;
}
// parameter checks for MOT_PWM_MIN/MAX, returns true if parameters are valid // parameter checks for MOT_PWM_MIN/MAX, returns true if parameters are valid
bool AP_MotorsMulticopter::check_mot_pwm_params() const bool AP_MotorsMulticopter::check_mot_pwm_params() const
{ {
// both must be zero or both non-zero:
if (_pwm_min == 0 && _pwm_max != 0) {
return false;
}
if (_pwm_min != 0 && _pwm_max == 0) {
return false;
}
// sanity says that minimum should be less than maximum: // sanity says that minimum should be less than maximum:
if (_pwm_min != 0 && _pwm_min >= _pwm_max) { if (_pwm_min >= _pwm_max) {
return false; return false;
} }
// negative values are out-of-range: // negative values are out-of-range:
if (_pwm_min < 0 || _pwm_max < 0) { if (_pwm_max <= 0) {
return false; return false;
} }
return true; return true;
} }
// 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) // update_throttle_range - update throttle endpoints
// also sets throttle channel minimum and maximum pwm void AP_MotorsMulticopter::update_throttle_range()
void AP_MotorsMulticopter::set_throttle_range(int16_t radio_min, int16_t radio_max)
{ {
// sanity check
if (radio_max <= radio_min) {
return;
}
_throttle_radio_min = radio_min;
_throttle_radio_max = radio_max;
// if all outputs are digital adjust the range. We also do this for type PWM_RANGE, as those use the // if all outputs are digital adjust the range. We also do this for type PWM_RANGE, as those use the
// scaled output, which is then mapped to PWM via the SRV_Channel library // scaled output, which is then mapped to PWM via the SRV_Channel library
if (SRV_Channels::have_digital_outputs(get_motor_mask()) || (_pwm_type == PWM_TYPE_PWM_RANGE)) { if (SRV_Channels::have_digital_outputs(get_motor_mask()) || (_pwm_type == PWM_TYPE_PWM_RANGE)) {

View File

@ -44,9 +44,8 @@ public:
// set_yaw_headroom - set yaw headroom (yaw is given at least this amount of pwm) // set_yaw_headroom - set yaw headroom (yaw is given at least this amount of pwm)
void set_yaw_headroom(int16_t pwm) { _yaw_headroom = pwm; } void set_yaw_headroom(int16_t pwm) { _yaw_headroom = pwm; }
// 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) // update_throttle_range - update throttle endpoints
// also sets minimum and maximum pwm values that will be sent to the motors void update_throttle_range();
void set_throttle_range(int16_t radio_min, int16_t radio_max);
// update estimated throttle required to hover // update estimated throttle required to hover
void update_throttle_hover(float dt); void update_throttle_hover(float dt);
@ -81,9 +80,9 @@ public:
virtual uint16_t get_motor_mask() override; virtual uint16_t get_motor_mask() override;
// get minimum or maximum pwm value that can be output to motors // get minimum or maximum pwm value that can be output to motors
int16_t get_pwm_output_min() const; int16_t get_pwm_output_min() const { return _pwm_min; }
int16_t get_pwm_output_max() const; int16_t get_pwm_output_max() const { return _pwm_max; }
// parameter check for MOT_PWM_MIN/MAX, returns true if parameters are valid // parameter check for MOT_PWM_MIN/MAX, returns true if parameters are valid
bool check_mot_pwm_params() const; bool check_mot_pwm_params() const;
@ -193,9 +192,6 @@ protected:
// motor output variables // motor output variables
bool motor_enabled[AP_MOTORS_MAX_NUM_MOTORS]; // true if motor is enabled bool motor_enabled[AP_MOTORS_MAX_NUM_MOTORS]; // true if motor is enabled
int16_t _throttle_radio_min; // minimum PWM from RC input's throttle channel (i.e. minimum PWM input from receiver, RC3_MIN)
int16_t _throttle_radio_max; // maximum PWM from RC input's throttle channel (i.e. maximum PWM input from receiver, RC3_MAX)
// spool variables
// spool variables // spool variables
float _spin_up_ratio; // throttle percentage (0 ~ 1) between zero and throttle_min float _spin_up_ratio; // throttle percentage (0 ~ 1) between zero and throttle_min

View File

@ -44,7 +44,7 @@ void setup()
motors.set_update_rate(490); motors.set_update_rate(490);
motors.init(AP_Motors::MOTOR_FRAME_QUAD, AP_Motors::MOTOR_FRAME_TYPE_X); motors.init(AP_Motors::MOTOR_FRAME_QUAD, AP_Motors::MOTOR_FRAME_TYPE_X);
#if HELI_TEST == 0 #if HELI_TEST == 0
motors.set_throttle_range(1000,2000); motors.update_throttle_range();
motors.set_throttle_avg_max(0.5f); motors.set_throttle_avg_max(0.5f);
#endif #endif
motors.output_min(); motors.output_min();