AP_Motors: make THR_LOW_COMP a variable instead of param

This commit is contained in:
Randy Mackay 2015-03-09 22:23:16 +09:00
parent c537c38646
commit 5e26450a6f
2 changed files with 4 additions and 7 deletions

View File

@ -53,12 +53,7 @@ const AP_Param::GroupInfo AP_Motors::var_info[] PROGMEM = {
// @User: Advanced
AP_GROUPINFO("YAW_HEADROOM", 6, AP_Motors, _yaw_headroom, AP_MOTORS_YAW_HEADROOM_DEFAULT),
// @Param: THR_LOW_CMP
// @DisplayName: Motor low throttle compensation
// @Description: Ratio controlling the max throttle output during competing requests of low throttle from the pilot (or autopilot) and higher throttle for attitude control
// @Values: 0.2:Favour Throttle Control, 0.5:Equal Weighting, 1:Favour Attitude Control
// @User: Advanced
AP_GROUPINFO("THR_LOW_CMP", 7, AP_Motors, _throttle_low_comp, AP_MOTORS_THR_LOW_CMP_DEFAULT),
// 7 was THR_LOW_CMP
// @Param: THST_EXPO
// @DisplayName: Thrust Curve Expo
@ -113,6 +108,8 @@ AP_Motors::AP_Motors(RC_Channel& rc_roll, RC_Channel& rc_pitch, RC_Channel& rc_t
_max_throttle(AP_MOTORS_DEFAULT_MAX_THROTTLE),
_hover_out(AP_MOTORS_DEFAULT_MID_THROTTLE),
_spin_when_armed_ramped(0),
_throttle_low_comp(AP_MOTORS_THR_LOW_CMP_DEFAULT),
_throttle_low_comp_desired(AP_MOTORS_THR_LOW_CMP_DEFAULT),
_batt_voltage(0.0f),
_batt_voltage_resting(0.0f),
_batt_current(0.0f),

View File

@ -237,7 +237,6 @@ protected:
AP_Int16 _spin_when_armed; // used to control whether the motors always spin when armed. pwm value above radio_min
AP_Int16 _yaw_headroom; // yaw control is given at least this pwm range
AP_Float _throttle_low_comp; // mix between throttle and hover throttle for 0 to 1 and ratio above hover throttle for >1
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_max; // throttle which produces the maximum thrust. (i.e. 0 ~ 1 ) of the full throttle range
AP_Float _batt_voltage_max; // maximum voltage used to scale lift
@ -255,6 +254,7 @@ protected:
int16_t _max_throttle; // the maximum throttle to be sent to the motors (sometimes limited by slow start)
int16_t _hover_out; // the estimated hover throttle as pct * 10 (i.e. 0 ~ 1000)
int16_t _spin_when_armed_ramped;// equal to _spin_when_armed parameter but slowly ramped up from zero
float _throttle_low_comp; // mix between throttle and hover throttle for 0 to 1 and ratio above hover throttle for >1
float _throttle_low_comp_desired; // desired throttle_low_comp value, actual throttle_low_comp is slewed towards this value over 1~2 seconds
// battery voltage compensation variables