mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-20 23:05:19 +03:00
Remove old mixer // Separate Acro Plus from Airmode // Fix MOTOLAB merge issues
This commit is contained in:
parent
61186c0227
commit
a1ebe6fd4f
8 changed files with 143 additions and 247 deletions
|
@ -103,11 +103,6 @@ enum {
|
|||
|
||||
#define GYRO_WATCHDOG_DELAY 100 // Watchdog delay for gyro sync
|
||||
|
||||
// AIR MODE Reset timers
|
||||
#define ERROR_RESET_DEACTIVATE_DELAY (1 * 1000) // 1 sec delay to disable AIR MODE Iterm resetting
|
||||
bool preventItermWindup = false;
|
||||
static bool ResetErrorActivated = true;
|
||||
|
||||
uint16_t cycleTime = 0; // this is the number in micro second to achieve a full loop, it can differ a little and is taken into account in the PID loop
|
||||
|
||||
float dT;
|
||||
|
@ -482,40 +477,8 @@ void processRx(void)
|
|||
|
||||
throttleStatus_e throttleStatus = calculateThrottleStatus(&masterConfig.rxConfig, masterConfig.flight3DConfig.deadband3d_throttle);
|
||||
|
||||
static bool airModeErrorResetIsEnabled = true; // Should always initialize with reset enabled
|
||||
static uint32_t airModeErrorResetTimeout = 0; // Timeout for both activate and deactivate mode
|
||||
|
||||
if (throttleStatus == THROTTLE_LOW) {
|
||||
// When in AIR Mode LOW Throttle and reset was already disabled we will only prevent further growing
|
||||
if ((IS_RC_MODE_ACTIVE(BOXAIRMODE)) && !airModeErrorResetIsEnabled) {
|
||||
if (calculateRollPitchCenterStatus(&masterConfig.rxConfig) == CENTERED) {
|
||||
preventItermWindup = true; // Iterm is now limited to the last value
|
||||
} else {
|
||||
preventItermWindup = false; // Iterm should considered safe to increase
|
||||
}
|
||||
}
|
||||
|
||||
// Conditions to reset Error
|
||||
if (!ARMING_FLAG(ARMED) || feature(FEATURE_MOTOR_STOP) || ((IS_RC_MODE_ACTIVE(BOXAIRMODE)) && airModeErrorResetIsEnabled) || !IS_RC_MODE_ACTIVE(BOXAIRMODE)) {
|
||||
ResetErrorActivated = true; // As RX code is not executed each loop a flag has to be set for fast looptimes
|
||||
airModeErrorResetTimeout = millis() + ERROR_RESET_DEACTIVATE_DELAY; // Reset de-activate timer
|
||||
airModeErrorResetIsEnabled = true; // Enable Reset again especially after Disarm
|
||||
preventItermWindup = false; // Reset limiting
|
||||
}
|
||||
} else {
|
||||
if (!(feature(FEATURE_MOTOR_STOP)) && ARMING_FLAG(ARMED) && IS_RC_MODE_ACTIVE(BOXAIRMODE)) {
|
||||
if (airModeErrorResetIsEnabled) {
|
||||
if (millis() > airModeErrorResetTimeout && calculateRollPitchCenterStatus(&masterConfig.rxConfig) == NOT_CENTERED) { // Only disable error reset when roll and pitch not centered
|
||||
airModeErrorResetIsEnabled = false;
|
||||
preventItermWindup = false; // Reset limiting for Iterm
|
||||
}
|
||||
} else {
|
||||
preventItermWindup = false; // Reset limiting for Iterm
|
||||
}
|
||||
} else {
|
||||
preventItermWindup = false; // Reset limiting. Usefull when flipping between normal and AIR mode
|
||||
}
|
||||
ResetErrorActivated = false; // Disable resetting of error
|
||||
if (throttleStatus == THROTTLE_LOW) {
|
||||
pidResetErrorGyro();
|
||||
}
|
||||
|
||||
// When armed and motors aren't spinning, do beeps and then disarm
|
||||
|
@ -723,10 +686,6 @@ void taskMainPidLoop(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
if (ResetErrorActivated) {
|
||||
pidResetErrorGyro();
|
||||
}
|
||||
|
||||
// PID - note this is function pointer set by setPIDController()
|
||||
pid_controller(
|
||||
¤tProfile->pidProfile,
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue