Merge remote-tracking branch 'borisbstyle/betaflight' into blackbox-enhancements
This commit is contained in:
commit
2731e9e046
2
Makefile
2
Makefile
|
@ -599,9 +599,11 @@ COLIBRI_RACE_SRC = \
|
|||
drivers/bus_bst_stm32f30x.c \
|
||||
drivers/accgyro_mpu.c \
|
||||
drivers/accgyro_mpu6500.c \
|
||||
drivers/accgyro_spi_mpu6000.c \
|
||||
drivers/accgyro_spi_mpu6500.c \
|
||||
drivers/accgyro_mpu6500.c \
|
||||
drivers/barometer_ms5611.c \
|
||||
drivers/compass_ak8963.c \
|
||||
drivers/compass_ak8975.c \
|
||||
drivers/compass_hmc5883l.c \
|
||||
drivers/display_ug2864hsweg01.c \
|
||||
|
|
|
@ -144,6 +144,11 @@ char *itoa(int i, char *a, int base)
|
|||
|
||||
#endif
|
||||
|
||||
/* Note: the floatString must be at least 13 bytes long to cover all cases.
|
||||
* This includes up to 10 digits (32 bit ints can hold numbers up to 10
|
||||
* digits long) + the decimal point + negative sign or space + null
|
||||
* terminator.
|
||||
*/
|
||||
char *ftoa(float x, char *floatString)
|
||||
{
|
||||
int32_t value;
|
||||
|
|
|
@ -21,7 +21,17 @@ void li2a(long num, char *bf);
|
|||
void ui2a(unsigned int num, unsigned int base, int uc, char *bf);
|
||||
void i2a(int num, char *bf);
|
||||
char a2i(char ch, const char **src, int base, int *nump);
|
||||
|
||||
/* Simple conversion of a float to a string. Will display completely
|
||||
* inaccurate results for floats larger than about 2.15E6 (2^31 / 1000)
|
||||
* (same thing for negative values < -2.15E6).
|
||||
* Will always display 3 decimals, so anything smaller than 1E-3 will
|
||||
* not be displayed.
|
||||
* The floatString will be filled in with the result and will be
|
||||
* returned. It must be at least 13 bytes in length to cover all cases!
|
||||
*/
|
||||
char *ftoa(float x, char *floatString);
|
||||
|
||||
float fastA2F(const char *p);
|
||||
|
||||
#ifndef HAVE_ITOA_FUNCTION
|
||||
|
|
|
@ -134,7 +134,7 @@ static uint32_t activeFeaturesLatch = 0;
|
|||
static uint8_t currentControlRateProfileIndex = 0;
|
||||
controlRateConfig_t *currentControlRateProfile;
|
||||
|
||||
static const uint8_t EEPROM_CONF_VERSION = 131;
|
||||
static const uint8_t EEPROM_CONF_VERSION = 132;
|
||||
|
||||
static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims)
|
||||
{
|
||||
|
@ -178,7 +178,8 @@ static void resetPidProfile(pidProfile_t *pidProfile)
|
|||
|
||||
pidProfile->yaw_p_limit = YAW_P_LIMIT_MAX;
|
||||
pidProfile->yaw_lpf_hz = 70.0f;
|
||||
pidProfile->dterm_average_count = 4;
|
||||
pidProfile->dterm_average_count = 0;
|
||||
pidProfile->dynamic_dterm_threshold = 20;
|
||||
pidProfile->rollPitchItermResetRate = 200;
|
||||
pidProfile->yawItermResetRate = 50;
|
||||
pidProfile->dterm_lpf_hz = 70.0f; // filtering ON by default
|
||||
|
|
|
@ -132,6 +132,8 @@ void mpu6000SpiGyroInit(uint8_t lpf)
|
|||
mpu6000WriteRegister(MPU6000_CONFIG, lpf);
|
||||
delayMicroseconds(1);
|
||||
|
||||
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_18MHZ_CLOCK_DIVIDER); // 18 MHz SPI clock
|
||||
|
||||
int16_t data[3];
|
||||
mpuGyroRead(data);
|
||||
|
||||
|
|
|
@ -59,7 +59,7 @@ int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3];
|
|||
#endif
|
||||
|
||||
// PIDweight is a scale factor for PIDs which is derived from the throttle and TPA setting, and 100 = 100% scale means no PID reduction
|
||||
uint8_t dynP8[3], dynI8[3], dynD8[3], PIDweight[3];
|
||||
uint8_t PIDweight[3];
|
||||
|
||||
static int32_t errorGyroI[3], errorGyroILimit[3];
|
||||
static float errorGyroIf[3], errorGyroIfLimit[3];
|
||||
|
@ -133,6 +133,7 @@ static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
|
|||
static float lastErrorForDelta[3];
|
||||
static float deltaState[3][DELTA_MAX_SAMPLES];
|
||||
float delta;
|
||||
float dynamicDTermGain;
|
||||
int axis;
|
||||
float horizonLevelStrength = 1;
|
||||
|
||||
|
@ -141,7 +142,7 @@ static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
|
|||
// Scaling factors for Pids to match rewrite and use same defaults
|
||||
static const float luxPTermScale = 1.0f / 128;
|
||||
static const float luxITermScale = 1000000.0f / 0x1000000;
|
||||
static const float luxDTermScale = (0.000001f * (float)0xFFFF) / 256;
|
||||
static const float luxDTermScale = (0.000001f * (float)0xFFFF) / 508;
|
||||
|
||||
if (FLIGHT_MODE(HORIZON_MODE)) {
|
||||
// Figure out the raw stick positions
|
||||
|
@ -245,13 +246,21 @@ static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
|
|||
// would be scaled by different dt each time. Division by dT fixes that.
|
||||
delta *= (1.0f / getdT());
|
||||
|
||||
// Several different Dterm filtering methods to prevent noise. All of them can be combined
|
||||
|
||||
// Filter delta
|
||||
if (pidProfile->dterm_lpf_hz) delta = filterApplyPt1(delta, &deltaFilterState[axis], pidProfile->dterm_lpf_hz, getdT());
|
||||
|
||||
// Apply moving average
|
||||
if (pidProfile->dterm_average_count) delta = filterApplyAveragef(delta, pidProfile->dterm_average_count, deltaState[axis]);
|
||||
if (pidProfile->dterm_average_count) delta = filterApplyAveragef(delta, pidProfile->dterm_average_count, deltaState[axis]) * 2;
|
||||
|
||||
DTerm = constrainf(luxDTermScale * delta * (float)pidProfile->D8[axis] * tpaFactor, -300.0f, 300.0f);
|
||||
|
||||
// Dynamic D Implementation
|
||||
if (pidProfile->dynamic_dterm_threshold) {
|
||||
dynamicDTermGain = constrainf(ABS(DTerm) / pidProfile->dynamic_dterm_threshold, 0.0f, 1.0f);
|
||||
DTerm *= dynamicDTermGain;
|
||||
}
|
||||
}
|
||||
|
||||
// -----calculate total PID output
|
||||
|
@ -273,145 +282,6 @@ static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
|
|||
}
|
||||
}
|
||||
|
||||
static void pidMultiWii23(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig, uint16_t max_angle_inclination,
|
||||
rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig)
|
||||
{
|
||||
UNUSED(rxConfig);
|
||||
|
||||
int axis, prop = 0;
|
||||
int32_t rc, error, errorAngle, delta, gyroError;
|
||||
int32_t PTerm, ITerm, PTermACC, ITermACC, DTerm;
|
||||
static int16_t lastErrorForDelta[2];
|
||||
static int32_t deltaState[3][DELTA_MAX_SAMPLES];
|
||||
|
||||
if (FLIGHT_MODE(HORIZON_MODE)) {
|
||||
prop = MIN(MAX(ABS(rcCommand[PITCH]), ABS(rcCommand[ROLL])), 512);
|
||||
}
|
||||
|
||||
// PITCH & ROLL
|
||||
for (axis = 0; axis < 2; axis++) {
|
||||
|
||||
rc = rcCommand[axis] << 1;
|
||||
|
||||
gyroError = gyroADC[axis] / 4;
|
||||
|
||||
error = rc - gyroError;
|
||||
errorGyroI[axis] = constrain(errorGyroI[axis] + ((error * (uint16_t)targetPidLooptime) >> 11) , -16000, +16000); // WindUp 16 bits is ok here
|
||||
|
||||
if (ABS(gyroADC[axis]) > (640 * 4)) {
|
||||
errorGyroI[axis] = 0;
|
||||
}
|
||||
|
||||
// Anti windup protection
|
||||
if (antiWindupProtection || motorLimitReached) {
|
||||
errorGyroI[axis] = constrain(errorGyroI[axis], -errorGyroILimit[axis], errorGyroILimit[axis]);
|
||||
} else {
|
||||
errorGyroILimit[axis] = ABS(errorGyroI[axis]);
|
||||
}
|
||||
|
||||
ITerm = (errorGyroI[axis] >> 7) * pidProfile->I8[axis] >> 6; // 16 bits is ok here 16000/125 = 128 ; 128*250 = 32000
|
||||
|
||||
PTerm = (int32_t)rc * pidProfile->P8[axis] >> 6;
|
||||
|
||||
if (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) { // axis relying on ACC
|
||||
// 50 degrees max inclination
|
||||
#ifdef GPS
|
||||
errorAngle = constrain(2 * rcCommand[axis] + GPS_angle[axis], -((int) max_angle_inclination),
|
||||
+max_angle_inclination) - attitude.raw[axis] + angleTrim->raw[axis];
|
||||
#else
|
||||
errorAngle = constrain(2 * rcCommand[axis], -((int) max_angle_inclination),
|
||||
+max_angle_inclination) - attitude.raw[axis] + angleTrim->raw[axis];
|
||||
#endif
|
||||
|
||||
errorAngleI[axis] = constrain(errorAngleI[axis] + errorAngle, -10000, +10000); // WindUp //16 bits is ok here
|
||||
|
||||
PTermACC = ((int32_t)errorAngle * pidProfile->P8[PIDLEVEL]) >> 7; // 32 bits is needed for calculation: errorAngle*P8 could exceed 32768 16 bits is ok for result
|
||||
|
||||
int16_t limit = pidProfile->D8[PIDLEVEL] * 5;
|
||||
PTermACC = constrain(PTermACC, -limit, +limit);
|
||||
|
||||
ITermACC = ((int32_t)errorAngleI[axis] * pidProfile->I8[PIDLEVEL]) >> 12; // 32 bits is needed for calculation:10000*I8 could exceed 32768 16 bits is ok for result
|
||||
|
||||
ITerm = ITermACC + ((ITerm - ITermACC) * prop >> 9);
|
||||
PTerm = PTermACC + ((PTerm - PTermACC) * prop >> 9);
|
||||
}
|
||||
|
||||
PTerm -= ((int32_t)gyroError * dynP8[axis]) >> 6; // 32 bits is needed for calculation
|
||||
|
||||
//-----calculate D-term based on the configured approach (delta from measurement or deltafromError)
|
||||
if (pidProfile->deltaMethod == DELTA_FROM_ERROR) {
|
||||
delta = error - lastErrorForDelta[axis];
|
||||
lastErrorForDelta[axis] = error;
|
||||
} else { /* Delta from measurement */
|
||||
delta = -(gyroError - lastErrorForDelta[axis]);
|
||||
lastErrorForDelta[axis] = gyroError;
|
||||
}
|
||||
|
||||
// Scale delta to looptime
|
||||
delta = (delta * ((uint16_t) 0xFFFF)) / ((uint16_t)targetPidLooptime << 5);
|
||||
|
||||
// Filer delta
|
||||
if (pidProfile->dterm_lpf_hz) delta = filterApplyPt1((float)delta, &deltaFilterState[axis], pidProfile->dterm_lpf_hz, getdT());
|
||||
|
||||
// Apply moving average and multiply to get original scaling
|
||||
if (pidProfile->dterm_average_count) delta = filterApplyAverage(delta, pidProfile->dterm_average_count, deltaState[axis]) * 2;
|
||||
|
||||
DTerm = (delta * dynD8[axis]) >> 5; // 32 bits is needed for calculation
|
||||
|
||||
axisPID[axis] = PTerm + ITerm + DTerm;
|
||||
|
||||
if (lowThrottlePidReduction) axisPID[axis] /= 3;
|
||||
|
||||
#ifdef GTUNE
|
||||
if (FLIGHT_MODE(GTUNE_MODE) && ARMING_FLAG(ARMED)) {
|
||||
calculate_Gtune(axis);
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef BLACKBOX
|
||||
axisPID_P[axis] = PTerm;
|
||||
axisPID_I[axis] = ITerm;
|
||||
axisPID_D[axis] = DTerm;
|
||||
#endif
|
||||
}
|
||||
|
||||
//YAW
|
||||
rc = (int32_t)rcCommand[FD_YAW] * (2 * controlRateConfig->rates[FD_YAW] + 30) >> 5;
|
||||
#ifdef ALIENWII32
|
||||
error = rc - gyroADC[FD_YAW];
|
||||
#else
|
||||
error = rc - (gyroADC[FD_YAW] / 4);
|
||||
#endif
|
||||
errorGyroI[FD_YAW] += (int32_t)error * pidProfile->I8[FD_YAW];
|
||||
errorGyroI[FD_YAW] = constrain(errorGyroI[FD_YAW], 2 - ((int32_t)1 << 28), -2 + ((int32_t)1 << 28));
|
||||
if (ABS(rc) > 50) errorGyroI[FD_YAW] = 0;
|
||||
|
||||
PTerm = (int32_t)error * pidProfile->P8[FD_YAW] >> 6; // TODO: Bitwise shift on a signed integer is not recommended
|
||||
|
||||
// Constrain YAW by yaw_p_limit value if not servo driven in that case servolimits apply
|
||||
if(motorCount >= 4 && pidProfile->yaw_p_limit < YAW_P_LIMIT_MAX) {
|
||||
PTerm = constrain(PTerm, -pidProfile->yaw_p_limit, pidProfile->yaw_p_limit);
|
||||
}
|
||||
|
||||
ITerm = constrain((int16_t)(errorGyroI[FD_YAW] >> 13), -GYRO_I_MAX, +GYRO_I_MAX);
|
||||
|
||||
axisPID[FD_YAW] = PTerm + ITerm;
|
||||
|
||||
if (pidProfile->yaw_lpf_hz) axisPID[FD_YAW] = filterApplyPt1(axisPID[FD_YAW], &yawFilterState, pidProfile->yaw_lpf_hz, getdT());
|
||||
|
||||
#ifdef GTUNE
|
||||
if (FLIGHT_MODE(GTUNE_MODE) && ARMING_FLAG(ARMED)) {
|
||||
calculate_Gtune(FD_YAW);
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef BLACKBOX
|
||||
axisPID_P[FD_YAW] = PTerm;
|
||||
axisPID_I[FD_YAW] = ITerm;
|
||||
axisPID_D[FD_YAW] = 0;
|
||||
#endif
|
||||
}
|
||||
|
||||
static void pidMultiWiiRewrite(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig, uint16_t max_angle_inclination,
|
||||
rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig)
|
||||
{
|
||||
|
@ -422,6 +292,7 @@ static void pidMultiWiiRewrite(pidProfile_t *pidProfile, controlRateConfig_t *co
|
|||
static int32_t lastErrorForDelta[3] = { 0, 0, 0 };
|
||||
static int32_t deltaState[3][DELTA_MAX_SAMPLES];
|
||||
int32_t AngleRateTmp, RateError, gyroRate;
|
||||
int32_t dynamicDTermGain;
|
||||
|
||||
int8_t horizonLevelStrength = 100;
|
||||
|
||||
|
@ -528,15 +399,23 @@ static void pidMultiWiiRewrite(pidProfile_t *pidProfile, controlRateConfig_t *co
|
|||
|
||||
// Correct difference by cycle time. Cycle time is jittery (can be different 2 times), so calculated difference
|
||||
// would be scaled by different dt each time. Division by dT fixes that.
|
||||
delta = (delta * ((uint16_t) 0xFFFF / ((uint16_t)targetPidLooptime >> 4))) >> 6;
|
||||
delta = (delta * ((uint16_t) 0xFFFF / ((uint16_t)targetPidLooptime >> 4))) >> 5;
|
||||
|
||||
// Several different Dterm filtering methods to prevent noise. All of them can be combined
|
||||
|
||||
// Filter delta
|
||||
if (pidProfile->dterm_lpf_hz) delta = filterApplyPt1((float)delta, &deltaFilterState[axis], pidProfile->dterm_lpf_hz, getdT());
|
||||
|
||||
// Apply moving average
|
||||
if (pidProfile->dterm_average_count) delta = filterApplyAverage(delta, pidProfile->dterm_average_count, deltaState[axis]) * 2;
|
||||
if (pidProfile->dterm_average_count) delta = filterApplyAverage(delta, pidProfile->dterm_average_count, deltaState[axis]);
|
||||
|
||||
DTerm = (delta * pidProfile->D8[axis] * PIDweight[axis] / 100) >> 8;
|
||||
|
||||
// Dynamic D Implementation
|
||||
if (pidProfile->dynamic_dterm_threshold) {
|
||||
dynamicDTermGain = constrain((ABS(DTerm) << 7) / pidProfile->dynamic_dterm_threshold, 0, 1 << 7);
|
||||
DTerm = (DTerm * dynamicDTermGain) >> 7;
|
||||
}
|
||||
}
|
||||
|
||||
// -----calculate total PID output
|
||||
|
@ -567,9 +446,6 @@ void pidSetController(pidControllerType_e type)
|
|||
break;
|
||||
case PID_CONTROLLER_LUX_FLOAT:
|
||||
pid_controller = pidLuxFloat;
|
||||
break;
|
||||
case PID_CONTROLLER_MW23:
|
||||
pid_controller = pidMultiWii23;
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -37,8 +37,7 @@ typedef enum {
|
|||
} pidIndex_e;
|
||||
|
||||
typedef enum {
|
||||
PID_CONTROLLER_MW23,
|
||||
PID_CONTROLLER_MWREWRITE,
|
||||
PID_CONTROLLER_MWREWRITE = 1,
|
||||
PID_CONTROLLER_LUX_FLOAT,
|
||||
PID_COUNT
|
||||
} pidControllerType_e;
|
||||
|
@ -72,6 +71,7 @@ typedef struct pidProfile_s {
|
|||
uint8_t deltaMethod; // Alternative delta Calculation
|
||||
uint16_t yaw_p_limit;
|
||||
uint8_t dterm_average_count; // Configurable delta count for dterm
|
||||
uint8_t dynamic_dterm_threshold;
|
||||
|
||||
#ifdef GTUNE
|
||||
uint8_t gtune_lolimP[3]; // [0..200] Lower limit of P during G tune
|
||||
|
|
|
@ -245,6 +245,19 @@ const ledConfig_t defaultLedStripConfig[] = {
|
|||
{ CALCULATE_LED_XY( 1, 1), 3, LED_FUNCTION_THRUST_RING},
|
||||
{ CALCULATE_LED_XY( 1, 1), 3, LED_FUNCTION_THRUST_RING},
|
||||
};
|
||||
#elif defined(USE_COLIBTI_RACE_LED_DEFAULT_CONFIG)
|
||||
const ledConfig_t defaultLedStripConfig[] = {
|
||||
{ CALCULATE_LED_XY( 0, 0), 6, LED_DIRECTION_WEST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
|
||||
{ CALCULATE_LED_XY( 0, 1), 6, LED_DIRECTION_WEST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
|
||||
{ CALCULATE_LED_XY( 0, 8), 6, LED_DIRECTION_WEST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
|
||||
{ CALCULATE_LED_XY( 7, 15), 6, LED_FUNCTION_COLOR },
|
||||
{ CALCULATE_LED_XY( 8, 15), 6, LED_FUNCTION_COLOR },
|
||||
{ CALCULATE_LED_XY( 7, 14), 6, LED_FUNCTION_COLOR },
|
||||
{ CALCULATE_LED_XY( 8, 14), 6, LED_FUNCTION_COLOR },
|
||||
{ CALCULATE_LED_XY( 15, 8), 6, LED_DIRECTION_EAST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
|
||||
{ CALCULATE_LED_XY( 15, 1), 6, LED_DIRECTION_EAST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
|
||||
{ CALCULATE_LED_XY( 15, 0), 6, LED_DIRECTION_EAST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
|
||||
};
|
||||
#else
|
||||
const ledConfig_t defaultLedStripConfig[] = {
|
||||
{ CALCULATE_LED_XY(15, 15), 0, LED_DIRECTION_SOUTH | LED_DIRECTION_EAST | LED_FUNCTION_INDICATOR | LED_FUNCTION_ARM_STATE },
|
||||
|
|
|
@ -371,7 +371,7 @@ static const char * const lookupTableBlackboxDevice[] = {
|
|||
|
||||
|
||||
static const char * const lookupTablePidController[] = {
|
||||
"MW23", "MWREWRITE", "LUX"
|
||||
"UNUSED", "MWREWRITE", "LUX"
|
||||
};
|
||||
|
||||
static const char * const lookupTableSerialRX[] = {
|
||||
|
@ -722,6 +722,7 @@ const clivalue_t valueTable[] = {
|
|||
{ "pid_delta_method", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.deltaMethod, .config.lookup = { TABLE_DELTA_METHOD } },
|
||||
{ "dterm_lowpass_hz", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dterm_lpf_hz, .config.minmax = {0, 500 } },
|
||||
{ "dterm_average_count", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dterm_average_count, .config.minmax = {0, 12 } },
|
||||
{ "dynamic_dterm_threshold", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dynamic_dterm_threshold, .config.minmax = {0, 100 } },
|
||||
{ "iterm_reset_degrees", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.rollPitchItermResetRate, .config.minmax = {50, 1000 } },
|
||||
{ "yaw_iterm_reset_degrees", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yawItermResetRate, .config.minmax = {25, 1000 } },
|
||||
{ "yaw_lowpass_hz", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yaw_lpf_hz, .config.minmax = {0, 500 } },
|
||||
|
@ -2446,7 +2447,7 @@ static void cliWrite(uint8_t ch)
|
|||
static void cliPrintVar(const clivalue_t *var, uint32_t full)
|
||||
{
|
||||
int32_t value = 0;
|
||||
char buf[8];
|
||||
char buf[13];
|
||||
|
||||
void *ptr = var->ptr;
|
||||
if ((var->type & VALUE_SECTION_MASK) == PROFILE_VALUE) {
|
||||
|
|
|
@ -1309,7 +1309,7 @@ static bool processInCommand(void)
|
|||
break;
|
||||
case MSP_SET_PID_CONTROLLER:
|
||||
oldPid = currentProfile->pidProfile.pidController;
|
||||
currentProfile->pidProfile.pidController = read8();
|
||||
currentProfile->pidProfile.pidController = constrain(read8(), 1, 2);
|
||||
pidSetController(currentProfile->pidProfile.pidController);
|
||||
if (oldPid != currentProfile->pidProfile.pidController) setGyroSamplingSpeed(0); // recalculate looptimes for new PID
|
||||
break;
|
||||
|
|
|
@ -223,16 +223,16 @@ void scaleRcCommandToFpvCamAngle(void) {
|
|||
void annexCode(void)
|
||||
{
|
||||
int32_t tmp, tmp2;
|
||||
int32_t axis, prop1 = 0, prop2;
|
||||
int32_t axis, prop;
|
||||
|
||||
// PITCH & ROLL only dynamic PID adjustment, depending on throttle value
|
||||
if (rcData[THROTTLE] < currentControlRateProfile->tpa_breakpoint) {
|
||||
prop2 = 100;
|
||||
prop = 100;
|
||||
} else {
|
||||
if (rcData[THROTTLE] < 2000) {
|
||||
prop2 = 100 - (uint16_t)currentControlRateProfile->dynThrPID * (rcData[THROTTLE] - currentControlRateProfile->tpa_breakpoint) / (2000 - currentControlRateProfile->tpa_breakpoint);
|
||||
prop = 100 - (uint16_t)currentControlRateProfile->dynThrPID * (rcData[THROTTLE] - currentControlRateProfile->tpa_breakpoint) / (2000 - currentControlRateProfile->tpa_breakpoint);
|
||||
} else {
|
||||
prop2 = 100 - currentControlRateProfile->dynThrPID;
|
||||
prop = 100 - currentControlRateProfile->dynThrPID;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -249,8 +249,6 @@ void annexCode(void)
|
|||
|
||||
tmp2 = tmp / 100;
|
||||
rcCommand[axis] = lookupPitchRollRC[tmp2] + (tmp - tmp2 * 100) * (lookupPitchRollRC[tmp2 + 1] - lookupPitchRollRC[tmp2]) / 100;
|
||||
prop1 = 100 - (uint16_t)currentControlRateProfile->rates[axis] * tmp / 500;
|
||||
prop1 = (uint16_t)prop1 * prop2 / 100;
|
||||
} else if (axis == YAW) {
|
||||
if (masterConfig.rcControlsConfig.yaw_deadband) {
|
||||
if (tmp > masterConfig.rcControlsConfig.yaw_deadband) {
|
||||
|
@ -261,19 +259,14 @@ void annexCode(void)
|
|||
}
|
||||
tmp2 = tmp / 100;
|
||||
rcCommand[axis] = (lookupYawRC[tmp2] + (tmp - tmp2 * 100) * (lookupYawRC[tmp2 + 1] - lookupYawRC[tmp2]) / 100) * -masterConfig.yaw_control_direction;
|
||||
prop1 = 100 - (uint16_t)currentControlRateProfile->rates[axis] * ABS(tmp) / 500;
|
||||
}
|
||||
// FIXME axis indexes into pids. use something like lookupPidIndex(rc_alias_e alias) to reduce coupling.
|
||||
dynP8[axis] = (uint16_t)currentProfile->pidProfile.P8[axis] * prop1 / 100;
|
||||
dynI8[axis] = (uint16_t)currentProfile->pidProfile.I8[axis] * prop1 / 100;
|
||||
dynD8[axis] = (uint16_t)currentProfile->pidProfile.D8[axis] * prop1 / 100;
|
||||
|
||||
// non coupled PID reduction scaler used in PID controller 1 and PID controller 2. YAW TPA disabled. 100 means 100% of the pids
|
||||
if (axis == YAW) {
|
||||
PIDweight[axis] = 100;
|
||||
}
|
||||
else {
|
||||
PIDweight[axis] = prop2;
|
||||
PIDweight[axis] = prop;
|
||||
}
|
||||
|
||||
if (rcData[axis] < masterConfig.rxConfig.midrc)
|
||||
|
|
|
@ -43,6 +43,11 @@
|
|||
#define MPU6500_CS_PIN GPIO_Pin_4
|
||||
#define MPU6500_SPI_INSTANCE SPI1
|
||||
|
||||
#define MPU6000_CS_GPIO_CLK_PERIPHERAL RCC_AHBPeriph_GPIOA
|
||||
#define MPU6000_CS_GPIO GPIOA
|
||||
#define MPU6000_CS_PIN GPIO_Pin_4
|
||||
#define MPU6000_SPI_INSTANCE SPI1
|
||||
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_1
|
||||
|
||||
|
@ -60,11 +65,15 @@
|
|||
#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready
|
||||
|
||||
#define GYRO
|
||||
#define USE_GYRO_SPI_MPU6000
|
||||
#define GYRO_MPU6000_ALIGN CW270_DEG
|
||||
#define USE_GYRO_MPU6500
|
||||
#define USE_GYRO_SPI_MPU6500
|
||||
#define GYRO_MPU6500_ALIGN CW270_DEG
|
||||
|
||||
#define ACC
|
||||
#define USE_ACC_SPI_MPU6000
|
||||
#define ACC_MPU6000_ALIGN CW270_DEG
|
||||
#define USE_ACC_MPU6500
|
||||
#define USE_ACC_SPI_MPU6500
|
||||
#define ACC_MPU6500_ALIGN CW270_DEG
|
||||
|
@ -73,7 +82,9 @@
|
|||
#define USE_BARO_MS5611
|
||||
|
||||
#define MAG
|
||||
#define USE_MPU9250_MAG
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_AK8963
|
||||
#define USE_MAG_AK8975
|
||||
|
||||
#define BEEPER
|
||||
|
@ -155,6 +166,7 @@
|
|||
#define GPS
|
||||
//#define GTUNE
|
||||
#define LED_STRIP
|
||||
#define USE_COLIBTI_RACE_LED_DEFAULT_CONFIG
|
||||
|
||||
#define LED_STRIP_TIMER TIM16
|
||||
|
||||
|
|
|
@ -40,11 +40,11 @@
|
|||
|
||||
|
||||
#define GYRO
|
||||
//#define USE_FAKE_GYRO
|
||||
#define USE_GYRO_MPU6500
|
||||
#define USE_GYRO_SPI_MPU6500
|
||||
|
||||
#define ACC
|
||||
//#define USE_FAKE_ACC
|
||||
#define USE_ACC_MPU6500
|
||||
#define USE_ACC_SPI_MPU6500
|
||||
|
||||
#define ACC_MPU6500_ALIGN CW180_DEG
|
||||
|
@ -53,12 +53,12 @@
|
|||
#define BARO
|
||||
#define USE_BARO_BMP280
|
||||
|
||||
#define MAG
|
||||
#define USE_MPU9250_MAG // Enables bypass configuration
|
||||
#define USE_MAG_AK8963
|
||||
//#define MAG
|
||||
//#define USE_MPU9250_MAG // Enables bypass configuration
|
||||
//#define USE_MAG_AK8963
|
||||
//#define USE_MAG_HMC5883 // External
|
||||
|
||||
#define MAG_AK8963_ALIGN CW90_DEG_FLIP
|
||||
//#define MAG_AK8963_ALIGN CW90_DEG_FLIP
|
||||
|
||||
//#define SONAR
|
||||
#define BEEPER
|
||||
|
|
|
@ -17,7 +17,7 @@
|
|||
|
||||
#define FC_VERSION_MAJOR 2 // increment when a major release is made (big new feature, etc)
|
||||
#define FC_VERSION_MINOR 6 // increment when a minor release is made (small new feature, change etc)
|
||||
#define FC_VERSION_PATCH_LEVEL 1 // increment when a bug is fixed
|
||||
#define FC_VERSION_PATCH_LEVEL 2 // increment when a bug is fixed
|
||||
|
||||
#define STR_HELPER(x) #x
|
||||
#define STR(x) STR_HELPER(x)
|
||||
|
|
|
@ -32,7 +32,7 @@ clean_motolab motolab : opts := TARGET=MOTOLAB
|
|||
clean_rmdo rmdo : opts := TARGET=RMDO
|
||||
clean_ircfusionf3 ircfusionf3 : opts := TARGET=IRCFUSIONF3
|
||||
clean_afromini afromini : opts := TARGET=AFROMINI
|
||||
clean_afromini doge : opts := TARGET=DOGE
|
||||
clean_doge doge : opts := TARGET=DOGE
|
||||
|
||||
|
||||
.PHONY: all clean
|
||||
|
|
Loading…
Reference in New Issue