Skip to content

Commit

Permalink
ezLanding
Browse files Browse the repository at this point in the history
  • Loading branch information
ctzsnooze authored and tbolin committed Dec 23, 2022
1 parent 0a46ef3 commit 2ca8460
Show file tree
Hide file tree
Showing 10 changed files with 42 additions and 3 deletions.
2 changes: 2 additions & 0 deletions src/main/blackbox/blackbox.c
Expand Up @@ -1330,6 +1330,8 @@ static bool blackboxWriteSysinfo(void)
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_TPA_MODE, "%d", currentPidProfile->tpa_mode);
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_TPA_RATE, "%d", currentPidProfile->tpa_rate);
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_TPA_BREAKPOINT, "%d", currentPidProfile->tpa_breakpoint);
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_EZ_LANDING_THRESHOLD, "%d", currentPidProfile->ez_landing_threshold);
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_EZ_LANDING_LIMIT, "%d", currentPidProfile->ez_landing_limit);
BLACKBOX_PRINT_HEADER_LINE("rc_rates", "%d,%d,%d", currentControlRateProfile->rcRates[ROLL],
currentControlRateProfile->rcRates[PITCH],
currentControlRateProfile->rcRates[YAW]);
Expand Down
8 changes: 5 additions & 3 deletions src/main/cli/settings.c
Expand Up @@ -1213,10 +1213,12 @@ const clivalue_t valueTable[] = {
{ PARAM_NAME_SIMPLIFIED_GYRO_FILTER_MULTIPLIER, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { SIMPLIFIED_TUNING_FILTERS_MIN, SIMPLIFIED_TUNING_MAX }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, simplified_gyro_filter_multiplier) },
#endif
#ifdef USE_TPA_MODE
{ PARAM_NAME_TPA_MODE, VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_TPA_MODE }, PG_PID_PROFILE, offsetof(pidProfile_t, tpa_mode) },
{ PARAM_NAME_TPA_MODE, VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_TPA_MODE }, PG_PID_PROFILE, offsetof(pidProfile_t, tpa_mode) },
#endif
{ PARAM_NAME_TPA_RATE, VAR_UINT8 | PROFILE_VALUE, .config.minmaxUnsigned = { 0, TPA_MAX}, PG_PID_PROFILE, offsetof(pidProfile_t, tpa_rate) },
{ PARAM_NAME_TPA_BREAKPOINT, VAR_UINT16 | PROFILE_VALUE, .config.minmaxUnsigned = { PWM_PULSE_MIN, PWM_PULSE_MAX }, PG_PID_PROFILE, offsetof(pidProfile_t, tpa_breakpoint) },
{ PARAM_NAME_TPA_RATE, VAR_UINT8 | PROFILE_VALUE, .config.minmaxUnsigned = { 0, TPA_MAX}, PG_PID_PROFILE, offsetof(pidProfile_t, tpa_rate) },
{ PARAM_NAME_TPA_BREAKPOINT, VAR_UINT16 | PROFILE_VALUE, .config.minmaxUnsigned = { PWM_PULSE_MIN, PWM_PULSE_MAX }, PG_PID_PROFILE, offsetof(pidProfile_t, tpa_breakpoint) },
{ PARAM_NAME_EZ_LANDING_THRESHOLD, VAR_UINT8 | PROFILE_VALUE, .config.minmaxUnsigned = { 0, 50 }, PG_PID_PROFILE, offsetof(pidProfile_t, ez_landing_threshold) },
{ PARAM_NAME_EZ_LANDING_LIMIT, VAR_UINT8 | PROFILE_VALUE, .config.minmaxUnsigned = { 5, 50 }, PG_PID_PROFILE, offsetof(pidProfile_t, ez_landing_limit) },

// PG_TELEMETRY_CONFIG
#ifdef USE_TELEMETRY
Expand Down
2 changes: 2 additions & 0 deletions src/main/fc/parameter_names.h
Expand Up @@ -55,6 +55,8 @@
#define PARAM_NAME_TPA_RATE "tpa_rate"
#define PARAM_NAME_TPA_BREAKPOINT "tpa_breakpoint"
#define PARAM_NAME_TPA_MODE "tpa_mode"
#define PARAM_NAME_EZ_LANDING_THRESHOLD "ez_landing_threshold"
#define PARAM_NAME_EZ_LANDING_LIMIT "ez_landing_limit"
#define PARAM_NAME_THROTTLE_LIMIT_TYPE "throttle_limit_type"
#define PARAM_NAME_THROTTLE_LIMIT_PERCENT "throttle_limit_percent"
#define PARAM_NAME_GYRO_CAL_ON_FIRST_ARM "gyro_cal_on_first_arm"
Expand Down
8 changes: 8 additions & 0 deletions src/main/fc/rc.c
Expand Up @@ -65,6 +65,7 @@ float rcCommandDelta[XYZ_AXIS_COUNT];
#endif
static float rawSetpoint[XYZ_AXIS_COUNT];
static float setpointRate[3], rcDeflection[3], rcDeflectionAbs[3];
static float maxRcDeflectionAbs;
static bool reverseMotors = false;
static applyRatesFn *applyRates;
static uint16_t currentRxRefreshRate;
Expand Down Expand Up @@ -132,6 +133,11 @@ float getRcDeflectionAbs(int axis)
return rcDeflectionAbs[axis];
}

float getMaxRcDeflectionAbs(void)
{
return maxRcDeflectionAbs;
}

#ifdef USE_FEEDFORWARD
float getRawSetpoint(int axis)
{
Expand Down Expand Up @@ -543,6 +549,7 @@ FAST_CODE void processRcCommand(void)
{
if (isRxDataNew) {
newRxDataForFF = true;
maxRcDeflectionAbs = 0.0f;
for (int axis = FD_ROLL; axis <= FD_YAW; axis++) {

#ifdef USE_FEEDFORWARD
Expand Down Expand Up @@ -575,6 +582,7 @@ FAST_CODE void processRcCommand(void)
rcDeflection[axis] = rcCommandf;
const float rcCommandfAbs = fabsf(rcCommandf);
rcDeflectionAbs[axis] = rcCommandfAbs;
maxRcDeflectionAbs = fmaxf(maxRcDeflectionAbs, rcCommandfAbs);

angleRate = applyRates(axis, rcCommandf, rcCommandfAbs);

Expand Down
1 change: 1 addition & 0 deletions src/main/fc/rc.h
Expand Up @@ -33,6 +33,7 @@ void processRcCommand(void);
float getSetpointRate(int axis);
float getRcDeflection(int axis);
float getRcDeflectionAbs(int axis);
float getMaxRcDeflectionAbs(void);
void updateRcCommands(void);
void resetYawAxis(void);
void initRcProcessing(void);
Expand Down
15 changes: 15 additions & 0 deletions src/main/flight/mixer.c
Expand Up @@ -262,6 +262,21 @@ static void calculateThrottleAndCurrentMotorEndpoints(timeUs_t currentTimeUs)
motorOutputMin = motorRangeMin;
motorOutputRange = motorRangeMax - motorRangeMin;
motorOutputMixSign = 1;

// easy landing code, limits motor output when sticks and throttle are below threshold
const float throttlePercent = throttle / 1000.0f;
if (mixerRuntime.ezLandingThreshold && throttlePercent < mixerRuntime.ezLandingThreshold) { // throttle low
float ezLandAttenuator = 0.0f;
float maxDeflection = getMaxRcDeflectionAbs();
if (maxDeflection < mixerRuntime.ezLandingThreshold) { // all sticks, including throttle, under threshold
ezLandAttenuator = fmaxf(maxDeflection, throttlePercent); // value range 0 -> threshold
ezLandAttenuator /= mixerRuntime.ezLandingThreshold; // normalised 0 - 1
ezLandAttenuator = 1.0f - ezLandAttenuator; // 1 -> 0
ezLandAttenuator *= mixerRuntime.ezLandingLimit; // eg 0.9 -> 0.0 if limit is 10
}
const float motorRange = motorRangeMax - mixerRuntime.motorOutputLow;
motorRangeMax -= ezLandAttenuator * motorRange; // available motor range limited to 15% if threshold is 15
}
}

throttle = constrainf(throttle / currentThrottleInputRange, 0.0f, 1.0f);
Expand Down
3 changes: 3 additions & 0 deletions src/main/flight/mixer_init.c
Expand Up @@ -322,6 +322,9 @@ void mixerInitProfile(void)
}
}
#endif

mixerRuntime.ezLandingThreshold = currentPidProfile->ez_landing_threshold / 100.0f;
mixerRuntime.ezLandingLimit = 1.0f - currentPidProfile->ez_landing_limit / 100.0f;
}

#ifdef USE_LAUNCH_CONTROL
Expand Down
2 changes: 2 additions & 0 deletions src/main/flight/mixer_init.h
Expand Up @@ -53,6 +53,8 @@ typedef struct mixerRuntime_s {
float vbatFull;
float vbatRangeToCompensate;
#endif
float ezLandingThreshold;
float ezLandingLimit;
} mixerRuntime_t;

extern mixerRuntime_t mixerRuntime;
2 changes: 2 additions & 0 deletions src/main/flight/pid.c
Expand Up @@ -223,6 +223,8 @@ void resetPidProfile(pidProfile_t *pidProfile)
.tpa_mode = TPA_MODE_D,
.tpa_rate = 65,
.tpa_breakpoint = 1350,
.ez_landing_threshold = 25,
.ez_landing_limit = 10,
);

#ifndef USE_D_MIN
Expand Down
2 changes: 2 additions & 0 deletions src/main/flight/pid.h
Expand Up @@ -233,6 +233,8 @@ typedef struct pidProfile_s {
uint8_t tpa_mode; // Controls which PID terms TPA effects
uint8_t tpa_rate; // Percent reduction in P or D at full throttle
uint16_t tpa_breakpoint; // Breakpoint where TPA is activated
uint8_t ez_landing_threshold; // Threshold stick position below which motor output is limited
uint8_t ez_landing_limit; // Maximum motor output when all sticks centred and throttle zero
} pidProfile_t;

PG_DECLARE_ARRAY(pidProfile_t, PID_PROFILE_COUNT, pidProfiles);
Expand Down

0 comments on commit 2ca8460

Please sign in to comment.