Copter: remove THR_MAX parameter

This commit is contained in:
Randy Mackay 2015-03-16 13:35:57 +09:00
parent 9a3f48cc1f
commit b10730f35c
5 changed files with 6 additions and 18 deletions

View File

@ -246,7 +246,7 @@ public:
k_param_rc_10, k_param_rc_10,
k_param_rc_11, k_param_rc_11,
k_param_throttle_min, k_param_throttle_min,
k_param_throttle_max, k_param_throttle_max, // remove
k_param_failsafe_throttle, k_param_failsafe_throttle,
k_param_throttle_fs_action, // remove k_param_throttle_fs_action, // remove
k_param_failsafe_throttle_value, k_param_failsafe_throttle_value,
@ -367,7 +367,6 @@ public:
// Throttle // Throttle
// //
AP_Int16 throttle_min; AP_Int16 throttle_min;
AP_Int16 throttle_max;
AP_Int8 failsafe_throttle; AP_Int8 failsafe_throttle;
AP_Int16 failsafe_throttle_value; AP_Int16 failsafe_throttle_value;
AP_Int16 throttle_mid; AP_Int16 throttle_mid;

View File

@ -219,15 +219,6 @@ const AP_Param::Info var_info[] PROGMEM = {
// @User: Standard // @User: Standard
GSCALAR(throttle_min, "THR_MIN", THR_MIN_DEFAULT), GSCALAR(throttle_min, "THR_MIN", THR_MIN_DEFAULT),
// @Param: THR_MAX
// @DisplayName: Throttle Maximum
// @Description: The maximum throttle that will be sent to the motors. This should normally be left as 1000.
// @Units: Percent*10
// @Range: 800 1000
// @Increment: 1
// @User: Advanced
GSCALAR(throttle_max, "THR_MAX", THR_MAX_DEFAULT),
// @Param: FS_THR_ENABLE // @Param: FS_THR_ENABLE
// @DisplayName: Throttle Failsafe Enable // @DisplayName: Throttle Failsafe Enable
// @Description: The throttle failsafe allows you to configure a software failsafe activated by a setting on the throttle input channel // @Description: The throttle failsafe allows you to configure a software failsafe activated by a setting on the throttle input channel

View File

@ -626,9 +626,7 @@
#ifndef THR_MIN_DEFAULT #ifndef THR_MIN_DEFAULT
# define THR_MIN_DEFAULT 130 // minimum throttle sent to the motors when armed and pilot throttle above zero # define THR_MIN_DEFAULT 130 // minimum throttle sent to the motors when armed and pilot throttle above zero
#endif #endif
#ifndef THR_MAX_DEFAULT #define THR_MAX 1000 // maximum throttle input and output sent to the motors
# define THR_MAX_DEFAULT 1000 // maximum throttle sent to the motors
#endif
#ifndef THR_DZ_DEFAULT #ifndef THR_DZ_DEFAULT
# define THR_DZ_DEFAULT 100 // the deadzone above and below mid throttle while in althold or loiter # define THR_DZ_DEFAULT 100 // the deadzone above and below mid throttle while in althold or loiter

View File

@ -107,7 +107,7 @@ int16_t get_throttle_assist(float velz, int16_t pilot_throttle_scaled)
// Only active when pilot's throttle is between 213 ~ 787 // Only active when pilot's throttle is between 213 ~ 787
// Assistance is strongest when throttle is at mid, drops linearly to no assistance at 213 and 787 // Assistance is strongest when throttle is at mid, drops linearly to no assistance at 213 and 787
float thr_assist = 0.0f; float thr_assist = 0.0f;
if (pilot_throttle_scaled > g.throttle_min && pilot_throttle_scaled < g.throttle_max && if (pilot_throttle_scaled > g.throttle_min && pilot_throttle_scaled < THR_MAX &&
pilot_throttle_scaled > DRIFT_THR_MIN && pilot_throttle_scaled < DRIFT_THR_MAX) { pilot_throttle_scaled > DRIFT_THR_MIN && pilot_throttle_scaled < DRIFT_THR_MAX) {
// calculate throttle assist gain // calculate throttle assist gain
thr_assist = 1.2 - ((float)abs(pilot_throttle_scaled - 500) / 240.0f); thr_assist = 1.2 - ((float)abs(pilot_throttle_scaled - 500) / 240.0f);
@ -117,7 +117,7 @@ int16_t get_throttle_assist(float velz, int16_t pilot_throttle_scaled)
thr_assist = constrain_float(thr_assist, -DRIFT_THR_ASSIST_MAX, DRIFT_THR_ASSIST_MAX); thr_assist = constrain_float(thr_assist, -DRIFT_THR_ASSIST_MAX, DRIFT_THR_ASSIST_MAX);
// ensure throttle assist never pushes throttle below throttle_min or above throttle_max // ensure throttle assist never pushes throttle below throttle_min or above throttle_max
thr_assist = constrain_float(thr_assist, g.throttle_min - pilot_throttle_scaled, g.throttle_max - pilot_throttle_scaled); thr_assist = constrain_float(thr_assist, g.throttle_min - pilot_throttle_scaled, THR_MAX - pilot_throttle_scaled);
} }
return pilot_throttle_scaled + thr_assist; return pilot_throttle_scaled + thr_assist;

View File

@ -23,7 +23,7 @@ static void init_rc_in()
// set rc channel ranges // set rc channel ranges
g.rc_1.set_angle(ROLL_PITCH_INPUT_MAX); g.rc_1.set_angle(ROLL_PITCH_INPUT_MAX);
g.rc_2.set_angle(ROLL_PITCH_INPUT_MAX); g.rc_2.set_angle(ROLL_PITCH_INPUT_MAX);
g.rc_3.set_range(g.throttle_min, g.throttle_max); g.rc_3.set_range(g.throttle_min, THR_MAX);
g.rc_4.set_angle(4500); g.rc_4.set_angle(4500);
g.rc_1.set_type(RC_CHANNEL_TYPE_ANGLE_RAW); g.rc_1.set_type(RC_CHANNEL_TYPE_ANGLE_RAW);
@ -185,4 +185,4 @@ static void set_throttle_zero_flag(int16_t throttle_control)
} else if (tnow_ms - last_nonzero_throttle_ms > THROTTLE_ZERO_DEBOUNCE_TIME_MS) { } else if (tnow_ms - last_nonzero_throttle_ms > THROTTLE_ZERO_DEBOUNCE_TIME_MS) {
ap.throttle_zero = true; ap.throttle_zero = true;
} }
} }