mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-20 06:45:16 +03:00
Less Anti Winduo in Air mode
This commit is contained in:
parent
9b3a2f3f76
commit
9859bbfcae
5 changed files with 10 additions and 8 deletions
|
@ -75,14 +75,17 @@ typedef void (*pidControllerFuncPtr)(pidProfile_t *pidProfile, controlRateConfig
|
||||||
|
|
||||||
pidControllerFuncPtr pid_controller = pidRewrite; // which pid controller are we using, defaultMultiWii
|
pidControllerFuncPtr pid_controller = pidRewrite; // which pid controller are we using, defaultMultiWii
|
||||||
|
|
||||||
void pidResetErrorGyro(void)
|
void pidResetErrorGyro(rxConfig_t *rxConfig)
|
||||||
{
|
{
|
||||||
int axis;
|
int axis;
|
||||||
|
|
||||||
for (axis = 0; axis < 3; axis++) {
|
for (axis = 0; axis < 3; axis++) {
|
||||||
if (IS_RC_MODE_ACTIVE(BOXAIRMODE)) {
|
if (IS_RC_MODE_ACTIVE(BOXAIRMODE)) {
|
||||||
PREVENT_WINDUP(errorGyroI[axis], previousErrorGyroI[axis]);
|
int rollPitchStatus = calculateRollPitchCenterStatus(rxConfig);
|
||||||
PREVENT_WINDUP(errorGyroIf[axis], previousErrorGyroIf[axis]);
|
if (rollPitchStatus == CENTERED) {
|
||||||
|
PREVENT_WINDUP(errorGyroI[axis], previousErrorGyroI[axis]);
|
||||||
|
PREVENT_WINDUP(errorGyroIf[axis], previousErrorGyroIf[axis]);
|
||||||
|
}
|
||||||
} else {
|
} else {
|
||||||
errorGyroI[axis] = 0;
|
errorGyroI[axis] = 0;
|
||||||
errorGyroIf[axis] = 0.0f;
|
errorGyroIf[axis] = 0.0f;
|
||||||
|
|
|
@ -14,6 +14,7 @@
|
||||||
* You should have received a copy of the GNU General Public License
|
* You should have received a copy of the GNU General Public License
|
||||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
#include "rx/rx.h"
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
@ -81,5 +82,5 @@ extern int16_t axisPID[XYZ_AXIS_COUNT];
|
||||||
extern int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3];
|
extern int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3];
|
||||||
|
|
||||||
void pidSetController(pidControllerType_e type);
|
void pidSetController(pidControllerType_e type);
|
||||||
void pidResetErrorGyro(void);
|
void pidResetErrorGyro(rxConfig_t *rxConfig);
|
||||||
|
|
||||||
|
|
|
@ -120,7 +120,6 @@ throttleStatus_e calculateThrottleStatus(rxConfig_t *rxConfig, uint16_t deadband
|
||||||
return THROTTLE_HIGH;
|
return THROTTLE_HIGH;
|
||||||
}
|
}
|
||||||
|
|
||||||
/* TODO - Cleanup
|
|
||||||
rollPitchStatus_e calculateRollPitchCenterStatus(rxConfig_t *rxConfig)
|
rollPitchStatus_e calculateRollPitchCenterStatus(rxConfig_t *rxConfig)
|
||||||
{
|
{
|
||||||
if (((rcData[PITCH] < (rxConfig->midrc + AIRMODEDEADBAND)) && (rcData[PITCH] > (rxConfig->midrc -AIRMODEDEADBAND)))
|
if (((rcData[PITCH] < (rxConfig->midrc + AIRMODEDEADBAND)) && (rcData[PITCH] > (rxConfig->midrc -AIRMODEDEADBAND)))
|
||||||
|
@ -129,7 +128,6 @@ rollPitchStatus_e calculateRollPitchCenterStatus(rxConfig_t *rxConfig)
|
||||||
|
|
||||||
return NOT_CENTERED;
|
return NOT_CENTERED;
|
||||||
}
|
}
|
||||||
*/
|
|
||||||
|
|
||||||
void processRcStickPositions(rxConfig_t *rxConfig, throttleStatus_e throttleStatus, bool retarded_arm, bool disarm_kill_switch)
|
void processRcStickPositions(rxConfig_t *rxConfig, throttleStatus_e throttleStatus, bool retarded_arm, bool disarm_kill_switch)
|
||||||
{
|
{
|
||||||
|
|
|
@ -78,7 +78,7 @@ typedef enum {
|
||||||
THROTTLE_HIGH
|
THROTTLE_HIGH
|
||||||
} throttleStatus_e;
|
} throttleStatus_e;
|
||||||
|
|
||||||
#define AIRMODEDEADBAND 10
|
#define AIRMODEDEADBAND 12
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
NOT_CENTERED = 0,
|
NOT_CENTERED = 0,
|
||||||
|
|
|
@ -478,7 +478,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) {
|
if (throttleStatus == THROTTLE_LOW) {
|
||||||
pidResetErrorGyro();
|
pidResetErrorGyro(&masterConfig.rxConfig);
|
||||||
}
|
}
|
||||||
|
|
||||||
// When armed and motors aren't spinning, do beeps and then disarm
|
// When armed and motors aren't spinning, do beeps and then disarm
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue