1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-19 14:25:20 +03:00

AIR MODE Optimalisations // Disable retarded arm

enable level modes
This commit is contained in:
borisbstyle 2015-12-06 23:22:54 +01:00
parent fe5ec022de
commit 400fe14e30
6 changed files with 14 additions and 15 deletions

View file

@ -445,7 +445,7 @@ static void resetConf(void)
masterConfig.inputFilteringMode = INPUT_FILTERING_DISABLED; masterConfig.inputFilteringMode = INPUT_FILTERING_DISABLED;
masterConfig.retarded_arm = 0; masterConfig.retarded_arm = 0; // TODO - Cleanup retarded arm support
masterConfig.disarm_kill_switch = 1; masterConfig.disarm_kill_switch = 1;
masterConfig.auto_disarm_delay = 5; masterConfig.auto_disarm_delay = 5;
masterConfig.small_angle = 25; masterConfig.small_angle = 25;

View file

@ -801,7 +801,7 @@ void mixTable(void)
} }
// adjust feedback to scale PID error inputs to our limitations. // adjust feedback to scale PID error inputs to our limitations.
rpy_limiting = constrainf(((rpy_limiting * th_range) / rpy_range), 0.1f, 1.0f); rpy_limiting = constrainf(((rpy_limiting * th_range) / rpy_range), 0.2f, 1.0f);
} }
if (ARMING_FLAG(ARMED)) { if (ARMING_FLAG(ARMED)) {
@ -857,8 +857,6 @@ void mixTable(void)
if (((rcData[THROTTLE]) < rxConfig->mincheck) && !(IS_RC_MODE_ACTIVE(BOXAIRMODE))) { if (((rcData[THROTTLE]) < rxConfig->mincheck) && !(IS_RC_MODE_ACTIVE(BOXAIRMODE))) {
if (feature(FEATURE_MOTOR_STOP)) { if (feature(FEATURE_MOTOR_STOP)) {
motor[i] = escAndServoConfig->mincommand; motor[i] = escAndServoConfig->mincommand;
} else {
motor[i] = escAndServoConfig->minthrottle;
} }
} }
} }

View file

@ -161,6 +161,10 @@ static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
} }
} }
if (IS_RC_MODE_ACTIVE(BOXAIRMODE)) {
AngleRate = AngleRate * rpy_limiting;
}
gyroRate = gyroADC[axis] * gyro.scale; // gyro output scaled to dps gyroRate = gyroADC[axis] * gyro.scale; // gyro output scaled to dps
// --------low-level gyro-based PID. ---------- // --------low-level gyro-based PID. ----------
@ -169,10 +173,6 @@ static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
// multiplication of rcCommand corresponds to changing the sticks scaling here // multiplication of rcCommand corresponds to changing the sticks scaling here
RateError = AngleRate - gyroRate; RateError = AngleRate - gyroRate;
if (IS_RC_MODE_ACTIVE(BOXAIRMODE)) {
RateError = RateError * rpy_limiting;
}
// -----calculate P component // -----calculate P component
PTerm = RateError * pidProfile->P_f[axis] * PIDweight[axis] / 100; PTerm = RateError * pidProfile->P_f[axis] * PIDweight[axis] / 100;
@ -283,16 +283,16 @@ static void pidRewrite(pidProfile_t *pidProfile, controlRateConfig_t *controlRat
} }
} }
if (IS_RC_MODE_ACTIVE(BOXAIRMODE)) {
AngleRateTmp = AngleRateTmp * rpy_limiting;
}
// --------low-level gyro-based PID. ---------- // --------low-level gyro-based PID. ----------
// Used in stand-alone mode for ACRO, controlled by higher level regulators in other modes // Used in stand-alone mode for ACRO, controlled by higher level regulators in other modes
// -----calculate scaled error.AngleRates // -----calculate scaled error.AngleRates
// multiplication of rcCommand corresponds to changing the sticks scaling here // multiplication of rcCommand corresponds to changing the sticks scaling here
RateError = AngleRateTmp - (gyroADC[axis] / 4); RateError = AngleRateTmp - (gyroADC[axis] / 4);
if (IS_RC_MODE_ACTIVE(BOXAIRMODE)) {
RateError = RateError * rpy_limiting;
}
// -----calculate P component // -----calculate P component
PTerm = (RateError * pidProfile->P8[axis] * PIDweight[axis] / 100) >> 7; PTerm = (RateError * pidProfile->P8[axis] * PIDweight[axis] / 100) >> 7;

View file

@ -48,7 +48,7 @@ typedef enum {
BOXSERVO3, BOXSERVO3,
BOXBLACKBOX, BOXBLACKBOX,
BOXFAILSAFE, BOXFAILSAFE,
BOXAIRMODE, BOXAIRMODE,
CHECKBOX_ITEM_COUNT CHECKBOX_ITEM_COUNT
} boxId_e; } boxId_e;
@ -126,6 +126,8 @@ typedef struct modeActivationCondition_s {
#define IS_RANGE_USABLE(range) ((range)->startStep < (range)->endStep) #define IS_RANGE_USABLE(range) ((range)->startStep < (range)->endStep)
#define SHOULD_RESET_ERRORS ((throttleStatus == THROTTLE_LOW && !(IS_RC_MODE_ACTIVE(BOXAIRMODE))) || !(ARMING_FLAG(ARMED)) || failsafeIsActive())
typedef struct controlRateConfig_s { typedef struct controlRateConfig_s {
uint8_t rcRate8; uint8_t rcRate8;
uint8_t rcExpo8; uint8_t rcExpo8;

View file

@ -472,7 +472,6 @@ const clivalue_t valueTable[] = {
{ "motor_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.motor_pwm_rate, .config.minmax = { 50, 32000 } }, { "motor_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.motor_pwm_rate, .config.minmax = { 50, 32000 } },
{ "servo_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.servo_pwm_rate, .config.minmax = { 50, 498 } }, { "servo_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.servo_pwm_rate, .config.minmax = { 50, 498 } },
{ "retarded_arm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.retarded_arm, .config.lookup = { TABLE_OFF_ON } },
{ "disarm_kill_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.disarm_kill_switch, .config.lookup = { TABLE_OFF_ON } }, { "disarm_kill_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.disarm_kill_switch, .config.lookup = { TABLE_OFF_ON } },
{ "auto_disarm_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.auto_disarm_delay, .config.minmax = { 0, 60 } }, { "auto_disarm_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.auto_disarm_delay, .config.minmax = { 0, 60 } },
{ "small_angle", VAR_UINT8 | MASTER_VALUE, &masterConfig.small_angle, .config.minmax = { 0, 180 } }, { "small_angle", VAR_UINT8 | MASTER_VALUE, &masterConfig.small_angle, .config.minmax = { 0, 180 } },

View file

@ -565,7 +565,7 @@ void processRx(void)
throttleStatus_e throttleStatus = calculateThrottleStatus(&masterConfig.rxConfig, masterConfig.flight3DConfig.deadband3d_throttle); throttleStatus_e throttleStatus = calculateThrottleStatus(&masterConfig.rxConfig, masterConfig.flight3DConfig.deadband3d_throttle);
if ((throttleStatus == THROTTLE_LOW && !(IS_RC_MODE_ACTIVE(BOXAIRMODE))) || !(ARMING_FLAG(ARMED))) { if (SHOULD_RESET_ERRORS) {
pidResetErrorAngle(); pidResetErrorAngle();
pidResetErrorGyro(); pidResetErrorGyro();
} }