AP_MotorsMulticopter: rename _thrust_curve_min to spin_min

This commit is contained in:
Leonard Hall 2016-05-22 18:32:19 +09:30 committed by Randy Mackay
parent 142a67bb6d
commit 0ee7b00b0b
2 changed files with 13 additions and 13 deletions

View File

@ -53,7 +53,7 @@ const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = {
// @Description: Point at which the thrust saturates expressed as a number from 0 to 1 in the entire output range
// @Values: 0.9:Low, 0.95:Default, 1.0:High
// @User: Advanced
AP_GROUPINFO("SPIN_MAX", 9, AP_MotorsMulticopter, _thrust_curve_max, AP_MOTORS_SPIN_MAX_DEFAULT),
AP_GROUPINFO("SPIN_MAX", 9, AP_MotorsMulticopter, _spin_max, AP_MOTORS_SPIN_MAX_DEFAULT),
// @Param: BAT_VOLT_MAX
// @DisplayName: Battery voltage compensation maximum voltage
@ -107,14 +107,14 @@ const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = {
// @Description: Point at which the thrust starts expressed as a number from 0 to 1 in the entire output range
// @Values: 0.0:Low, 0.15:Default, 0.3:High
// @User: Advanced
AP_GROUPINFO("SPIN_MIN", 18, AP_MotorsMulticopter, _thrust_curve_min, AP_MOTORS_SPIN_MIN_DEFAULT),
AP_GROUPINFO("SPIN_MIN", 18, AP_MotorsMulticopter, _spin_min, AP_MOTORS_SPIN_MIN_DEFAULT),
// @Param: SPIN_ARM
// @DisplayName: Motor Spin armed
// @Description: Point at which the motors start to spin expressed as a number from 0 to 1 in the entire output range
// @Values: 0.0:Low, 0.1:Default, 0.2:High
// @User: Advanced
AP_GROUPINFO("SPIN_ARM", 19, AP_MotorsMulticopter, _thrust_curve_arm, AP_MOTORS_SPIN_ARM_DEFAULT),
AP_GROUPINFO("SPIN_ARM", 19, AP_MotorsMulticopter, _spin_arm, AP_MOTORS_SPIN_ARM_DEFAULT),
// @Param: THST_HOVER
// @DisplayName: Thrust Hover Value
@ -243,9 +243,9 @@ float AP_MotorsMulticopter::apply_thrust_curve_and_volt_scaling(float thrust) co
}
// scale to maximum thrust point
throttle_ratio *= _thrust_curve_max;
throttle_ratio *= _spin_max;
return constrain_float(throttle_ratio, 0.0f, _thrust_curve_max);
return constrain_float(throttle_ratio, 0.0f, _spin_max);
}
// update_lift_max from battery voltage - used for voltage compensation
@ -316,13 +316,13 @@ float AP_MotorsMulticopter::get_compensation_gain() const
int16_t AP_MotorsMulticopter::calc_thrust_to_pwm(float thrust_in) const
{
thrust_in = constrain_float(thrust_in, 0, 1);
return get_pwm_output_min() + (get_pwm_output_max()-get_pwm_output_min()) * (_thrust_curve_min + (_thrust_curve_max-_thrust_curve_min)*apply_thrust_curve_and_volt_scaling(thrust_in));
return get_pwm_output_min() + (get_pwm_output_max()-get_pwm_output_min()) * (_spin_min + (_spin_max-_spin_min)*apply_thrust_curve_and_volt_scaling(thrust_in));
}
int16_t AP_MotorsMulticopter::calc_spin_up_to_pwm() const
{
return get_pwm_output_min() + constrain_float(_spin_up_ratio, 0.0f, 1.0f) * _spin_min * (get_pwm_output_max()-get_pwm_output_min());}
return get_pwm_output_min() + constrain_float(_spin_up_ratio, 0.0f, 1.0f) * _spin_min * (get_pwm_output_max()-get_pwm_output_min());
}
// get minimum or maximum pwm value that can be output to motors
int16_t AP_MotorsMulticopter::get_pwm_output_min() const
{
@ -420,8 +420,8 @@ void AP_MotorsMulticopter::output_logic()
}
} else { // _spool_desired == SPIN_WHEN_ARMED
float spin_up_armed_ratio = 0.0f;
if (_thrust_curve_min > 0.0f) {
spin_up_armed_ratio = _thrust_curve_arm / _thrust_curve_min;
if (_spin_min > 0.0f) {
spin_up_armed_ratio = _spin_arm / _spin_min;
}
_spin_up_ratio += constrain_float(spin_up_armed_ratio-_spin_up_ratio, -spool_step, spool_step);
}

View File

@ -147,9 +147,9 @@ protected:
// parameters
AP_Int16 _yaw_headroom; // yaw control is given at least this pwm range
AP_Float _thrust_curve_expo; // curve used to linearize pwm to thrust conversion. set to 0 for linear and 1 for second order approximation
AP_Float _thrust_curve_min; // throttle out ratio which produces the minimum thrust. (i.e. 0 ~ 1 ) of the full throttle range
AP_Float _thrust_curve_max; // throttle out ratio which produces the maximum thrust. (i.e. 0 ~ 1 ) of the full throttle range
AP_Float _thrust_curve_arm; // throttle out ratio which produces the armed spin rate. (i.e. 0 ~ 1 ) of the full throttle range
AP_Float _spin_min; // throttle out ratio which produces the minimum thrust. (i.e. 0 ~ 1 ) of the full throttle range
AP_Float _spin_max; // throttle out ratio which produces the maximum thrust. (i.e. 0 ~ 1 ) of the full throttle range
AP_Float _spin_arm; // throttle out ratio which produces the armed spin rate. (i.e. 0 ~ 1 ) of the full throttle range
AP_Float _batt_voltage_max; // maximum voltage used to scale lift
AP_Float _batt_voltage_min; // minimum voltage used to scale lift
AP_Float _batt_current_max; // current over which maximum throttle is limited