Copter: throttle deadzone parameter

Allows increasing or decreasing the deadband size in AltHold, Loiter,
PosHold flight modes
This commit is contained in:
Randy Mackay 2013-10-27 22:13:42 +09:00
parent ff94120fbd
commit 68df421484
4 changed files with 18 additions and 7 deletions

View File

@ -151,8 +151,8 @@ static int16_t get_pilot_desired_throttle(int16_t throttle_control)
// get_pilot_desired_climb_rate - transform pilot's throttle input to
// climb rate in cm/s. we use radio_in instead of control_in to get the full range
// without any deadzone at the bottom
#define THROTTLE_IN_DEADBAND_TOP (THROTTLE_IN_MIDDLE+THROTTLE_IN_DEADBAND) // top of the deadband
#define THROTTLE_IN_DEADBAND_BOTTOM (THROTTLE_IN_MIDDLE-THROTTLE_IN_DEADBAND) // bottom of the deadband
#define THROTTLE_IN_DEADBAND_TOP (THROTTLE_IN_MIDDLE+g.throttle_deadzone) // top of the deadband
#define THROTTLE_IN_DEADBAND_BOTTOM (THROTTLE_IN_MIDDLE-g.throttle_deadzone) // bottom of the deadband
static int16_t get_pilot_desired_climb_rate(int16_t throttle_control)
{
int16_t desired_rate = 0;
@ -168,10 +168,10 @@ static int16_t get_pilot_desired_climb_rate(int16_t throttle_control)
// check throttle is above, below or in the deadband
if (throttle_control < THROTTLE_IN_DEADBAND_BOTTOM) {
// below the deadband
desired_rate = (int32_t)g.pilot_velocity_z_max * (throttle_control-THROTTLE_IN_DEADBAND_BOTTOM) / (THROTTLE_IN_MIDDLE - THROTTLE_IN_DEADBAND);
desired_rate = (int32_t)g.pilot_velocity_z_max * (throttle_control-THROTTLE_IN_DEADBAND_BOTTOM) / (THROTTLE_IN_MIDDLE - g.throttle_deadzone);
}else if (throttle_control > THROTTLE_IN_DEADBAND_TOP) {
// above the deadband
desired_rate = (int32_t)g.pilot_velocity_z_max * (throttle_control-THROTTLE_IN_DEADBAND_TOP) / (THROTTLE_IN_MIDDLE - THROTTLE_IN_DEADBAND);
desired_rate = (int32_t)g.pilot_velocity_z_max * (throttle_control-THROTTLE_IN_DEADBAND_TOP) / (THROTTLE_IN_MIDDLE - g.throttle_deadzone);
}else{
// must be in the deadband
desired_rate = 0;

View File

@ -119,7 +119,8 @@ public:
k_param_sonar, // sonar object
k_param_ekfcheck_thresh,
k_param_terrain,
k_param_acro_expo, // 56
k_param_acro_expo,
k_param_throttle_deadzone, // 57
// 65: AP_Limits Library
k_param_limits = 65, // deprecated - remove
@ -365,6 +366,7 @@ public:
AP_Int16 failsafe_throttle_value;
AP_Int16 throttle_cruise;
AP_Int16 throttle_mid;
AP_Int16 throttle_deadzone;
// Flight modes
//

View File

@ -295,6 +295,15 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Increment: 1
GSCALAR(throttle_mid, "THR_MID", THR_MID_DEFAULT),
// @Param: THR_DZ
// @DisplayName: Throttle deadzone
// @Description: The deadzone above and below mid throttle. Used in AltHold, Loiter, PosHold flight modes
// @User: Standard
// @Range: 0 300
// @Units: pwm
// @Increment: 1
GSCALAR(throttle_deadzone, "THR_DZ", THR_DZ_DEFAULT),
// @Param: FLTMODE1
// @DisplayName: Flight Mode 1
// @Description: Flight mode when Channel 5 pwm is <= 1230

View File

@ -659,8 +659,8 @@
# define THR_MAX_DEFAULT 1000 // maximum throttle sent to the motors
#endif
#ifndef THROTTLE_IN_DEADBAND
# define THROTTLE_IN_DEADBAND 100 // the throttle input channel's deadband in PWM
#ifndef THR_DZ_DEFAULT
# define THR_DZ_DEFAULT 100 // the deadzone above and below mid throttle while in althold or loiter
#endif
#ifndef ALT_HOLD_P