mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-19 06:15:16 +03:00
Initial PID controller separation // Betaflight pidc for future development
This commit is contained in:
parent
16c9ca75d6
commit
37fd2e5adc
13 changed files with 113 additions and 61 deletions
|
@ -1211,7 +1211,7 @@ static bool blackboxWriteSysinfo()
|
||||||
BLACKBOX_PRINT_HEADER_LINE("yaw_p_limit:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.yaw_p_limit);
|
BLACKBOX_PRINT_HEADER_LINE("yaw_p_limit:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.yaw_p_limit);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("yaw_lpf_hz:%d", (int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.yaw_lpf_hz * 100.0f));
|
BLACKBOX_PRINT_HEADER_LINE("yaw_lpf_hz:%d", (int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.yaw_lpf_hz * 100.0f));
|
||||||
BLACKBOX_PRINT_HEADER_LINE("dterm_average_count:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_average_count);
|
BLACKBOX_PRINT_HEADER_LINE("dterm_average_count:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_average_count);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("dynamic_pid:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.dynamic_pid);
|
BLACKBOX_PRINT_HEADER_LINE("vbat_pid_compensation:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.vbatPidCompensation);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("rollPitchItermIgnoreRate:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.rollPitchItermIgnoreRate);
|
BLACKBOX_PRINT_HEADER_LINE("rollPitchItermIgnoreRate:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.rollPitchItermIgnoreRate);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("yawItermIgnoreRate:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.yawItermIgnoreRate);
|
BLACKBOX_PRINT_HEADER_LINE("yawItermIgnoreRate:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.yawItermIgnoreRate);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("dterm_lpf_hz:%d", (int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_lpf_hz * 100.0f));
|
BLACKBOX_PRINT_HEADER_LINE("dterm_lpf_hz:%d", (int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_lpf_hz * 100.0f));
|
||||||
|
@ -1226,7 +1226,6 @@ static bool blackboxWriteSysinfo()
|
||||||
BLACKBOX_PRINT_HEADER_LINE("baro_hardware:%d", masterConfig.baro_hardware);
|
BLACKBOX_PRINT_HEADER_LINE("baro_hardware:%d", masterConfig.baro_hardware);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("mag_hardware:%d", masterConfig.mag_hardware);
|
BLACKBOX_PRINT_HEADER_LINE("mag_hardware:%d", masterConfig.mag_hardware);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("gyro_cal_on_first_arm:%d", masterConfig.gyro_cal_on_first_arm);
|
BLACKBOX_PRINT_HEADER_LINE("gyro_cal_on_first_arm:%d", masterConfig.gyro_cal_on_first_arm);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("vbat_pid_compensation:%d", masterConfig.batteryConfig.vbatPidCompensation);
|
|
||||||
BLACKBOX_PRINT_HEADER_LINE("rc_smooth_interval:%d", masterConfig.rxConfig.rcSmoothInterval);
|
BLACKBOX_PRINT_HEADER_LINE("rc_smooth_interval:%d", masterConfig.rxConfig.rcSmoothInterval);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("airmode_activate_throttle:%d", masterConfig.rxConfig.airModeActivateThreshold);
|
BLACKBOX_PRINT_HEADER_LINE("airmode_activate_throttle:%d", masterConfig.rxConfig.airModeActivateThreshold);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("features:%d", masterConfig.enabledFeatures);
|
BLACKBOX_PRINT_HEADER_LINE("features:%d", masterConfig.enabledFeatures);
|
||||||
|
|
|
@ -182,12 +182,7 @@ static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims)
|
||||||
|
|
||||||
void resetPidProfile(pidProfile_t *pidProfile)
|
void resetPidProfile(pidProfile_t *pidProfile)
|
||||||
{
|
{
|
||||||
|
pidProfile->pidController = PID_CONTROLLER_BETAFLIGHT;
|
||||||
#if (defined(STM32F10X))
|
|
||||||
pidProfile->pidController = PID_CONTROLLER_INTEGER;
|
|
||||||
#else
|
|
||||||
pidProfile->pidController = PID_CONTROLLER_FLOAT;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
pidProfile->P8[ROLL] = 45;
|
pidProfile->P8[ROLL] = 45;
|
||||||
pidProfile->I8[ROLL] = 40;
|
pidProfile->I8[ROLL] = 40;
|
||||||
|
@ -224,7 +219,14 @@ void resetPidProfile(pidProfile_t *pidProfile)
|
||||||
pidProfile->yawItermIgnoreRate = 50;
|
pidProfile->yawItermIgnoreRate = 50;
|
||||||
pidProfile->dterm_lpf_hz = 100; // filtering ON by default
|
pidProfile->dterm_lpf_hz = 100; // filtering ON by default
|
||||||
pidProfile->deltaMethod = DELTA_FROM_MEASUREMENT;
|
pidProfile->deltaMethod = DELTA_FROM_MEASUREMENT;
|
||||||
pidProfile->dynamic_pid = 1;
|
pidProfile->vbatPidCompensation = 0;
|
||||||
|
|
||||||
|
// Betaflight PID controller parameters
|
||||||
|
pidProfile->toleranceBand = 15;
|
||||||
|
pidProfile->toleranceBandReduction = 35;
|
||||||
|
pidProfile->zeroCrossAllowanceCount = 3;
|
||||||
|
pidProfile->accelerationLimitPercent = 15;
|
||||||
|
pidProfile->itermThrottleGain = 0;
|
||||||
|
|
||||||
#ifdef GTUNE
|
#ifdef GTUNE
|
||||||
pidProfile->gtune_lolimP[ROLL] = 10; // [0..200] Lower limit of ROLL P during G tune.
|
pidProfile->gtune_lolimP[ROLL] = 10; // [0..200] Lower limit of ROLL P during G tune.
|
||||||
|
@ -278,7 +280,6 @@ void resetEscAndServoConfig(escAndServoConfig_t *escAndServoConfig)
|
||||||
#endif
|
#endif
|
||||||
escAndServoConfig->mincommand = 1000;
|
escAndServoConfig->mincommand = 1000;
|
||||||
escAndServoConfig->servoCenterPulse = 1500;
|
escAndServoConfig->servoCenterPulse = 1500;
|
||||||
escAndServoConfig->accelerationLimitPercent = 15;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void resetFlight3DConfig(flight3DConfig_t *flight3DConfig)
|
void resetFlight3DConfig(flight3DConfig_t *flight3DConfig)
|
||||||
|
@ -311,7 +312,6 @@ void resetBatteryConfig(batteryConfig_t *batteryConfig)
|
||||||
batteryConfig->vbatmincellvoltage = 33;
|
batteryConfig->vbatmincellvoltage = 33;
|
||||||
batteryConfig->vbatwarningcellvoltage = 35;
|
batteryConfig->vbatwarningcellvoltage = 35;
|
||||||
batteryConfig->vbathysteresis = 1;
|
batteryConfig->vbathysteresis = 1;
|
||||||
batteryConfig->vbatPidCompensation = 0;
|
|
||||||
batteryConfig->currentMeterOffset = 0;
|
batteryConfig->currentMeterOffset = 0;
|
||||||
batteryConfig->currentMeterScale = 400; // for Allegro ACS758LCB-100U (40mV/A)
|
batteryConfig->currentMeterScale = 400; // for Allegro ACS758LCB-100U (40mV/A)
|
||||||
batteryConfig->batteryCapacity = 0;
|
batteryConfig->batteryCapacity = 0;
|
||||||
|
@ -452,15 +452,15 @@ static void resetConf(void)
|
||||||
masterConfig.gyro_lpf = 0; // 256HZ default
|
masterConfig.gyro_lpf = 0; // 256HZ default
|
||||||
#ifdef STM32F10X
|
#ifdef STM32F10X
|
||||||
masterConfig.gyro_sync_denom = 8;
|
masterConfig.gyro_sync_denom = 8;
|
||||||
|
masterConfig.pid_process_denom = 1;
|
||||||
#else
|
#else
|
||||||
masterConfig.gyro_sync_denom = 4;
|
masterConfig.gyro_sync_denom = 4;
|
||||||
|
masterConfig.pid_process_denom = 2;
|
||||||
#endif
|
#endif
|
||||||
masterConfig.gyro_soft_lpf_hz = 100;
|
masterConfig.gyro_soft_lpf_hz = 100;
|
||||||
masterConfig.gyro_soft_notch_hz = 0;
|
masterConfig.gyro_soft_notch_hz = 0;
|
||||||
masterConfig.gyro_soft_notch_q = 5;
|
masterConfig.gyro_soft_notch_q = 5;
|
||||||
|
|
||||||
masterConfig.pid_process_denom = 2;
|
|
||||||
|
|
||||||
masterConfig.debug_mode = 0;
|
masterConfig.debug_mode = 0;
|
||||||
|
|
||||||
resetAccelerometerTrims(&masterConfig.accZero);
|
resetAccelerometerTrims(&masterConfig.accZero);
|
||||||
|
|
|
@ -755,13 +755,14 @@ STATIC_UNIT_TESTED void servoMixer(void)
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
void mixTable(void)
|
void mixTable(void *pidProfilePtr)
|
||||||
{
|
{
|
||||||
uint32_t i = 0;
|
uint32_t i = 0;
|
||||||
fix12_t vbatCompensationFactor = 0;
|
fix12_t vbatCompensationFactor = 0;
|
||||||
static fix12_t mixReduction;
|
static fix12_t mixReduction;
|
||||||
bool use_vbat_compensation = false;
|
bool use_vbat_compensation = false;
|
||||||
if (batteryConfig && batteryConfig->vbatPidCompensation) {
|
pidProfile_t *pidProfile = (pidProfile_t *) pidProfilePtr;
|
||||||
|
if (batteryConfig && pidProfile->vbatPidCompensation) {
|
||||||
use_vbat_compensation = true;
|
use_vbat_compensation = true;
|
||||||
vbatCompensationFactor = calculateVbatPidCompensation();
|
vbatCompensationFactor = calculateVbatPidCompensation();
|
||||||
}
|
}
|
||||||
|
@ -836,9 +837,9 @@ void mixTable(void)
|
||||||
throttleMax = throttleMax - (rollPitchYawMixRange / 2);
|
throttleMax = throttleMax - (rollPitchYawMixRange / 2);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Keep track for motor update timing
|
// Keep track for motor update timing // Only for Betaflight pid controller to keep legacy pidc basic and free from additional float math
|
||||||
float motorDtms;
|
float motorDtms;
|
||||||
if (escAndServoConfig->accelerationLimitPercent) {
|
if (pidProfile->accelerationLimitPercent && pidProfile->pidController == PID_CONTROLLER_BETAFLIGHT) {
|
||||||
static uint32_t previousMotorTime;
|
static uint32_t previousMotorTime;
|
||||||
uint32_t currentMotorTime = micros();
|
uint32_t currentMotorTime = micros();
|
||||||
motorDtms = (float) (currentMotorTime - previousMotorTime) / 1000.0f;
|
motorDtms = (float) (currentMotorTime - previousMotorTime) / 1000.0f;
|
||||||
|
@ -850,13 +851,13 @@ void mixTable(void)
|
||||||
for (i = 0; i < motorCount; i++) {
|
for (i = 0; i < motorCount; i++) {
|
||||||
motor[i] = rollPitchYawMix[i] + constrain(throttle * currentMixer[i].throttle, throttleMin, throttleMax);
|
motor[i] = rollPitchYawMix[i] + constrain(throttle * currentMixer[i].throttle, throttleMin, throttleMax);
|
||||||
|
|
||||||
// Accel limit. Prevent PID controller to output huge ramps to the motors. Only limiting acceleration.
|
// Accel limit. Prevent PID controller to output huge ramps to the motors. Only limiting acceleration. Only for Betaflight pid controller to keep legacy pidc basic
|
||||||
if (escAndServoConfig->accelerationLimitPercent) {
|
if (pidProfile->accelerationLimitPercent && pidProfile->pidController == PID_CONTROLLER_BETAFLIGHT) {
|
||||||
static int16_t lastFilteredMotor[MAX_SUPPORTED_MOTORS];
|
static int16_t lastFilteredMotor[MAX_SUPPORTED_MOTORS];
|
||||||
|
|
||||||
// acceleration limit
|
// acceleration limit
|
||||||
float delta = motor[i] - lastFilteredMotor[i];
|
float delta = motor[i] - lastFilteredMotor[i];
|
||||||
const float maxDeltaPerMs = throttleRange * ((float)escAndServoConfig->accelerationLimitPercent / 100.0f);
|
const float maxDeltaPerMs = throttleRange * ((float)pidProfile->accelerationLimitPercent / 100.0f);
|
||||||
float maxDelta = maxDeltaPerMs * motorDtms;
|
float maxDelta = maxDeltaPerMs * motorDtms;
|
||||||
if (delta > maxDelta) { // accelerating too hard
|
if (delta > maxDelta) { // accelerating too hard
|
||||||
motor[i] = lastFilteredMotor[i] + maxDelta;
|
motor[i] = lastFilteredMotor[i] + maxDelta;
|
||||||
|
|
|
@ -211,7 +211,7 @@ void loadCustomServoMixer(void);
|
||||||
int servoDirection(int servoIndex, int fromChannel);
|
int servoDirection(int servoIndex, int fromChannel);
|
||||||
#endif
|
#endif
|
||||||
void mixerResetDisarmedMotors(void);
|
void mixerResetDisarmedMotors(void);
|
||||||
void mixTable(void);
|
void mixTable(void *pidProfilePtr);
|
||||||
void syncMotors(bool enabled);
|
void syncMotors(bool enabled);
|
||||||
void writeMotors(void);
|
void writeMotors(void);
|
||||||
void stopMotors(void);
|
void stopMotors(void);
|
||||||
|
|
|
@ -62,14 +62,12 @@ int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3];
|
||||||
uint8_t PIDweight[3];
|
uint8_t PIDweight[3];
|
||||||
|
|
||||||
static int32_t errorGyroI[3];
|
static int32_t errorGyroI[3];
|
||||||
#ifndef SKIP_PID_LUXFLOAT
|
|
||||||
static float errorGyroIf[3];
|
static float errorGyroIf[3];
|
||||||
#endif
|
|
||||||
|
|
||||||
static void pidInteger(const pidProfile_t *pidProfile, uint16_t max_angle_inclination,
|
static void pidBetaflight(const pidProfile_t *pidProfile, uint16_t max_angle_inclination,
|
||||||
const rollAndPitchTrims_t *angleTrim, const rxConfig_t *rxConfig);
|
const rollAndPitchTrims_t *angleTrim, const rxConfig_t *rxConfig);
|
||||||
|
|
||||||
pidControllerFuncPtr pid_controller = pidInteger; // which pid controller are we using
|
pidControllerFuncPtr pid_controller = pidBetaflight; // which pid controller are we using
|
||||||
|
|
||||||
void setTargetPidLooptime(uint8_t pidProcessDenom)
|
void setTargetPidLooptime(uint8_t pidProcessDenom)
|
||||||
{
|
{
|
||||||
|
@ -82,9 +80,7 @@ void pidResetErrorGyroState(void)
|
||||||
|
|
||||||
for (axis = 0; axis < 3; axis++) {
|
for (axis = 0; axis < 3; axis++) {
|
||||||
errorGyroI[axis] = 0;
|
errorGyroI[axis] = 0;
|
||||||
#ifndef SKIP_PID_LUXFLOAT
|
|
||||||
errorGyroIf[axis] = 0.0f;
|
errorGyroIf[axis] = 0.0f;
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -101,8 +97,8 @@ const angle_index_t rcAliasToAngleIndexMap[] = { AI_ROLL, AI_PITCH };
|
||||||
static pt1Filter_t deltaFilter[3];
|
static pt1Filter_t deltaFilter[3];
|
||||||
static pt1Filter_t yawFilter;
|
static pt1Filter_t yawFilter;
|
||||||
|
|
||||||
#ifndef SKIP_PID_LUXFLOAT
|
// Experimental betaflight pid controller, which will be maintained in the future with additional features specialised for current (mini) multirotor usage
|
||||||
static void pidFloat(const pidProfile_t *pidProfile, uint16_t max_angle_inclination,
|
static void pidBetaflight(const pidProfile_t *pidProfile, uint16_t max_angle_inclination,
|
||||||
const rollAndPitchTrims_t *angleTrim, const rxConfig_t *rxConfig)
|
const rollAndPitchTrims_t *angleTrim, const rxConfig_t *rxConfig)
|
||||||
{
|
{
|
||||||
float RateError = 0, gyroRate = 0, RateErrorSmooth = 0;
|
float RateError = 0, gyroRate = 0, RateErrorSmooth = 0;
|
||||||
|
@ -133,6 +129,25 @@ static void pidFloat(const pidProfile_t *pidProfile, uint16_t max_angle_inclinat
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Yet Highly experimental and under test and development
|
||||||
|
// Throttle coupled to Igain like inverted TPA // 50hz calculation (should cover all rx protocols)
|
||||||
|
static float kiThrottleGain = 1.0f;
|
||||||
|
|
||||||
|
if (pidProfile->itermThrottleGain) {
|
||||||
|
const uint16_t maxLoopCount = 20000 / targetPidLooptime;
|
||||||
|
const float throttleItermGain = (float)pidProfile->itermThrottleGain * 0.001f;
|
||||||
|
static int16_t previousThrottle;
|
||||||
|
static uint16_t loopIncrement;
|
||||||
|
|
||||||
|
if (loopIncrement >= maxLoopCount) {
|
||||||
|
kiThrottleGain = 1.0f + constrainf((float)(ABS(rcCommand[THROTTLE] - previousThrottle)) * throttleItermGain, 0.0f, 5.0f); // Limit to factor 5
|
||||||
|
previousThrottle = rcCommand[THROTTLE];
|
||||||
|
loopIncrement = 0;
|
||||||
|
} else {
|
||||||
|
loopIncrement++;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
// ----------PID controller----------
|
// ----------PID controller----------
|
||||||
for (axis = 0; axis < 3; axis++) {
|
for (axis = 0; axis < 3; axis++) {
|
||||||
|
|
||||||
|
@ -164,6 +179,34 @@ static void pidFloat(const pidProfile_t *pidProfile, uint16_t max_angle_inclinat
|
||||||
// multiplication of rcCommand corresponds to changing the sticks scaling here
|
// multiplication of rcCommand corresponds to changing the sticks scaling here
|
||||||
RateError = angleRate[axis] - gyroRate;
|
RateError = angleRate[axis] - gyroRate;
|
||||||
|
|
||||||
|
float dynReduction = tpaFactor;
|
||||||
|
// Reduce Hunting effect and jittering near setpoint. Limit multiple zero crossing within deadband and lower PID affect during low error amount
|
||||||
|
if (pidProfile->toleranceBand) {
|
||||||
|
const float minReduction = (float)pidProfile->toleranceBandReduction / 100.0f;
|
||||||
|
static uint8_t zeroCrossCount[3];
|
||||||
|
static uint8_t currentErrorPolarity[3];
|
||||||
|
if (ABS(RateError) < pidProfile->toleranceBand) {
|
||||||
|
if (zeroCrossCount[axis]) {
|
||||||
|
if (currentErrorPolarity[axis] == POSITIVE_ERROR) {
|
||||||
|
if (RateError < 0 ) {
|
||||||
|
zeroCrossCount[axis]--;
|
||||||
|
currentErrorPolarity[axis] = NEGATIVE_ERROR;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
if (RateError > 0 ) {
|
||||||
|
zeroCrossCount[axis]--;
|
||||||
|
currentErrorPolarity[axis] = POSITIVE_ERROR;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
dynReduction *= constrainf(ABS(RateError) / pidProfile->toleranceBand, minReduction, 1.0f);
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
zeroCrossCount[axis] = pidProfile->zeroCrossAllowanceCount;
|
||||||
|
currentErrorPolarity[axis] = (RateError > 0) ? POSITIVE_ERROR : NEGATIVE_ERROR;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
if (pidProfile->deltaMethod == DELTA_FROM_ERROR) {
|
if (pidProfile->deltaMethod == DELTA_FROM_ERROR) {
|
||||||
// Smoothed Error for Derivative when delta from error selected
|
// Smoothed Error for Derivative when delta from error selected
|
||||||
if (flightModeFlags && axis != YAW)
|
if (flightModeFlags && axis != YAW)
|
||||||
|
@ -173,7 +216,7 @@ static void pidFloat(const pidProfile_t *pidProfile, uint16_t max_angle_inclinat
|
||||||
}
|
}
|
||||||
|
|
||||||
// -----calculate P component
|
// -----calculate P component
|
||||||
PTerm = PTermScale * RateError * pidProfile->P8[axis] * tpaFactor;
|
PTerm = PTermScale * RateError * pidProfile->P8[axis] * dynReduction;
|
||||||
|
|
||||||
// Constrain YAW by yaw_p_limit value if not servo driven in that case servolimits apply
|
// Constrain YAW by yaw_p_limit value if not servo driven in that case servolimits apply
|
||||||
if((motorCount >= 4 && pidProfile->yaw_p_limit) && axis == YAW) {
|
if((motorCount >= 4 && pidProfile->yaw_p_limit) && axis == YAW) {
|
||||||
|
@ -185,7 +228,7 @@ static void pidFloat(const pidProfile_t *pidProfile, uint16_t max_angle_inclinat
|
||||||
float accumulationThreshold = (axis == YAW) ? pidProfile->yawItermIgnoreRate : pidProfile->rollPitchItermIgnoreRate;
|
float accumulationThreshold = (axis == YAW) ? pidProfile->yawItermIgnoreRate : pidProfile->rollPitchItermIgnoreRate;
|
||||||
float antiWindupScaler = constrainf(1.0f - (1.5f * (ABS(angleRate[axis]) / accumulationThreshold)), 0.0f, 1.0f);
|
float antiWindupScaler = constrainf(1.0f - (1.5f * (ABS(angleRate[axis]) / accumulationThreshold)), 0.0f, 1.0f);
|
||||||
|
|
||||||
errorGyroIf[axis] = constrainf(errorGyroIf[axis] + ITermScale * RateError * getdT() * pidProfile->I8[axis] * antiWindupScaler, -250.0f, 250.0f);
|
errorGyroIf[axis] = constrainf(errorGyroIf[axis] + ITermScale * RateError * getdT() * pidProfile->I8[axis] * antiWindupScaler * kiThrottleGain, -250.0f, 250.0f);
|
||||||
|
|
||||||
// limit maximum integrator value to prevent WindUp - accumulating extreme values when system is saturated.
|
// limit maximum integrator value to prevent WindUp - accumulating extreme values when system is saturated.
|
||||||
// I coefficient (I8) moved before integration to make limiting independent from PID settings
|
// I coefficient (I8) moved before integration to make limiting independent from PID settings
|
||||||
|
@ -220,7 +263,7 @@ static void pidFloat(const pidProfile_t *pidProfile, uint16_t max_angle_inclinat
|
||||||
// Filter delta
|
// Filter delta
|
||||||
if (pidProfile->dterm_lpf_hz) delta = pt1FilterApply4(&deltaFilter[axis], delta, pidProfile->dterm_lpf_hz, getdT());
|
if (pidProfile->dterm_lpf_hz) delta = pt1FilterApply4(&deltaFilter[axis], delta, pidProfile->dterm_lpf_hz, getdT());
|
||||||
|
|
||||||
DTerm = constrainf(DTermScale * delta * (float)pidProfile->D8[axis] * tpaFactor, -300.0f, 300.0f);
|
DTerm = constrainf(DTermScale * delta * (float)pidProfile->D8[axis] * dynReduction, -300.0f, 300.0f);
|
||||||
|
|
||||||
// -----calculate total PID output
|
// -----calculate total PID output
|
||||||
axisPID[axis] = constrain(lrintf(PTerm + ITerm + DTerm), -1000, 1000);
|
axisPID[axis] = constrain(lrintf(PTerm + ITerm + DTerm), -1000, 1000);
|
||||||
|
@ -239,9 +282,9 @@ static void pidFloat(const pidProfile_t *pidProfile, uint16_t max_angle_inclinat
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
static void pidInteger(const pidProfile_t *pidProfile, uint16_t max_angle_inclination,
|
// Legacy pid controller betaflight evolved pid rewrite based on 2.9 releae. Good for fastest cycletimes for those who believe in that. Don't expect much development in the future
|
||||||
|
static void pidLegacy(const pidProfile_t *pidProfile, uint16_t max_angle_inclination,
|
||||||
const rollAndPitchTrims_t *angleTrim, const rxConfig_t *rxConfig)
|
const rollAndPitchTrims_t *angleTrim, const rxConfig_t *rxConfig)
|
||||||
{
|
{
|
||||||
int axis;
|
int axis;
|
||||||
|
@ -385,13 +428,11 @@ void pidSetController(pidControllerType_e type)
|
||||||
{
|
{
|
||||||
switch (type) {
|
switch (type) {
|
||||||
default:
|
default:
|
||||||
case PID_CONTROLLER_INTEGER:
|
case PID_CONTROLLER_LEGACY:
|
||||||
pid_controller = pidInteger;
|
pid_controller = pidLegacy;
|
||||||
break;
|
break;
|
||||||
#ifndef SKIP_PID_LUXFLOAT
|
case PID_CONTROLLER_BETAFLIGHT:
|
||||||
case PID_CONTROLLER_FLOAT:
|
pid_controller = pidBetaflight;
|
||||||
pid_controller = pidFloat;
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -41,8 +41,8 @@ typedef enum {
|
||||||
} pidIndex_e;
|
} pidIndex_e;
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
PID_CONTROLLER_INTEGER = 1, // Integer math to gain some more performance from F1 targets
|
PID_CONTROLLER_LEGACY = 0, // Legacy PID controller. Old INT / Rewrite with 2.9 status. Fastest performance....least math. Will stay same in the future
|
||||||
PID_CONTROLLER_FLOAT,
|
PID_CONTROLLER_BETAFLIGHT, // Betaflight PID controller. Old luxfloat -> float evolution. More math added and maintained in the future
|
||||||
PID_COUNT
|
PID_COUNT
|
||||||
} pidControllerType_e;
|
} pidControllerType_e;
|
||||||
|
|
||||||
|
@ -57,10 +57,13 @@ typedef enum {
|
||||||
SUPEREXPO_YAW_ALWAYS
|
SUPEREXPO_YAW_ALWAYS
|
||||||
} pidSuperExpoYaw_e;
|
} pidSuperExpoYaw_e;
|
||||||
|
|
||||||
#define IS_PID_CONTROLLER_FP_BASED(pidController) (pidController == 2)
|
typedef enum {
|
||||||
|
NEGATIVE_ERROR = 0,
|
||||||
|
POSITIVE_ERROR
|
||||||
|
} pidErrorPolarity_e;
|
||||||
|
|
||||||
typedef struct pidProfile_s {
|
typedef struct pidProfile_s {
|
||||||
uint8_t pidController; // 1 = rewrite from http://www.multiwii.com/forum/viewtopic.php?f=8&t=3671, 2 = Luggi09s new baseflight pid
|
uint8_t pidController; // 1 = rewrite betaflight evolved from http://www.multiwii.com/forum/viewtopic.php?f=8&t=3671, 2 = Betaflight PIDc (Evolved Luxfloat)
|
||||||
|
|
||||||
uint8_t P8[PID_ITEM_COUNT];
|
uint8_t P8[PID_ITEM_COUNT];
|
||||||
uint8_t I8[PID_ITEM_COUNT];
|
uint8_t I8[PID_ITEM_COUNT];
|
||||||
|
@ -73,7 +76,14 @@ typedef struct pidProfile_s {
|
||||||
uint16_t yawItermIgnoreRate; // Experimental threshold for resetting iterm for yaw on certain rates
|
uint16_t yawItermIgnoreRate; // Experimental threshold for resetting iterm for yaw on certain rates
|
||||||
uint16_t yaw_p_limit;
|
uint16_t yaw_p_limit;
|
||||||
uint8_t dterm_average_count; // Configurable delta count for dterm
|
uint8_t dterm_average_count; // Configurable delta count for dterm
|
||||||
uint8_t dynamic_pid; // Dynamic PID implementation (currently only P and I)
|
uint8_t vbatPidCompensation; // Scale PIDsum to battery voltage
|
||||||
|
|
||||||
|
// Betaflight PID controller parameters
|
||||||
|
uint8_t toleranceBand; // Error tolerance area where toleranceBandReduction is applied under certain circumstances
|
||||||
|
uint8_t toleranceBandReduction; // Lowest possible P and D reduction in percentage
|
||||||
|
uint8_t zeroCrossAllowanceCount; // Amount of bouncebacks within tolerance band allowed before reduction kicks in
|
||||||
|
uint16_t accelerationLimitPercent; // Percentage that motor is allowed to increase or decrease in a period of 1ms
|
||||||
|
uint8_t itermThrottleGain; // Throttle coupling to iterm. Quick throttle changes will bump iterm
|
||||||
|
|
||||||
#ifdef GTUNE
|
#ifdef GTUNE
|
||||||
uint8_t gtune_lolimP[3]; // [0..200] Lower limit of P during G tune
|
uint8_t gtune_lolimP[3]; // [0..200] Lower limit of P during G tune
|
||||||
|
|
|
@ -24,5 +24,4 @@ typedef struct escAndServoConfig_s {
|
||||||
uint16_t maxthrottle; // This is the maximum value for the ESCs at full power this value can be increased up to 2000
|
uint16_t maxthrottle; // This is the maximum value for the ESCs at full power this value can be increased up to 2000
|
||||||
uint16_t mincommand; // This is the value for the ESCs when they are not armed. In some cases, this value must be lowered down to 900 for some specific ESCs
|
uint16_t mincommand; // This is the value for the ESCs when they are not armed. In some cases, this value must be lowered down to 900 for some specific ESCs
|
||||||
uint16_t servoCenterPulse; // This is the value for servos when they should be in the middle. e.g. 1500.
|
uint16_t servoCenterPulse; // This is the value for servos when they should be in the middle. e.g. 1500.
|
||||||
uint16_t accelerationLimitPercent; // Percentage that motor is allowed to increase or decrease in a period of 1ms
|
|
||||||
} escAndServoConfig_t;
|
} escAndServoConfig_t;
|
||||||
|
|
|
@ -389,7 +389,7 @@ static const char * const lookupTableBlackboxDevice[] = {
|
||||||
|
|
||||||
|
|
||||||
static const char * const lookupTablePidController[] = {
|
static const char * const lookupTablePidController[] = {
|
||||||
"UNUSED", "INT", "FLOAT"
|
"LEGACY", "BETAFLIGHT"
|
||||||
};
|
};
|
||||||
|
|
||||||
static const char * const lookupTableSerialRX[] = {
|
static const char * const lookupTableSerialRX[] = {
|
||||||
|
@ -601,7 +601,6 @@ const clivalue_t valueTable[] = {
|
||||||
{ "min_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.minthrottle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
|
{ "min_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.minthrottle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
|
||||||
{ "max_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.maxthrottle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
|
{ "max_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.maxthrottle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
|
||||||
{ "min_command", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.mincommand, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
|
{ "min_command", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.mincommand, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
|
||||||
{ "motor_accel_limit_percent", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.accelerationLimitPercent, .config.minmax = { 0, 10000 } },
|
|
||||||
{ "servo_center_pulse", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.servoCenterPulse, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
|
{ "servo_center_pulse", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.servoCenterPulse, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
|
||||||
|
|
||||||
{ "3d_deadband_low", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_low, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, // FIXME upper limit should match code in the mixer, 1500 currently
|
{ "3d_deadband_low", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_low, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, // FIXME upper limit should match code in the mixer, 1500 currently
|
||||||
|
@ -680,7 +679,6 @@ const clivalue_t valueTable[] = {
|
||||||
{ "vbat_min_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatmincellvoltage, .config.minmax = { 10, 50 } },
|
{ "vbat_min_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatmincellvoltage, .config.minmax = { 10, 50 } },
|
||||||
{ "vbat_warning_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatwarningcellvoltage, .config.minmax = { 10, 50 } },
|
{ "vbat_warning_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatwarningcellvoltage, .config.minmax = { 10, 50 } },
|
||||||
{ "vbat_hysteresis", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbathysteresis, .config.minmax = { 0, 250 } },
|
{ "vbat_hysteresis", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbathysteresis, .config.minmax = { 0, 250 } },
|
||||||
{ "vbat_pid_compensation", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.batteryConfig.vbatPidCompensation, .config.lookup = { TABLE_OFF_ON } },
|
|
||||||
{ "current_meter_scale", VAR_INT16 | MASTER_VALUE, &masterConfig.batteryConfig.currentMeterScale, .config.minmax = { -10000, 10000 } },
|
{ "current_meter_scale", VAR_INT16 | MASTER_VALUE, &masterConfig.batteryConfig.currentMeterScale, .config.minmax = { -10000, 10000 } },
|
||||||
{ "current_meter_offset", VAR_UINT16 | MASTER_VALUE, &masterConfig.batteryConfig.currentMeterOffset, .config.minmax = { 0, 3300 } },
|
{ "current_meter_offset", VAR_UINT16 | MASTER_VALUE, &masterConfig.batteryConfig.currentMeterOffset, .config.minmax = { 0, 3300 } },
|
||||||
{ "multiwii_current_meter_output", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.batteryConfig.multiwiiCurrentMeterOutput, .config.lookup = { TABLE_OFF_ON } },
|
{ "multiwii_current_meter_output", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.batteryConfig.multiwiiCurrentMeterOutput, .config.lookup = { TABLE_OFF_ON } },
|
||||||
|
@ -767,7 +765,13 @@ const clivalue_t valueTable[] = {
|
||||||
{ "mag_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mag_hardware, .config.lookup = { TABLE_MAG_HARDWARE } },
|
{ "mag_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mag_hardware, .config.lookup = { TABLE_MAG_HARDWARE } },
|
||||||
{ "mag_declination", VAR_INT16 | MASTER_VALUE, &masterConfig.mag_declination, .config.minmax = { -18000, 18000 } },
|
{ "mag_declination", VAR_INT16 | MASTER_VALUE, &masterConfig.mag_declination, .config.minmax = { -18000, 18000 } },
|
||||||
{ "dterm_lowpass", VAR_INT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dterm_lpf_hz, .config.minmax = {0, 500 } },
|
{ "dterm_lowpass", VAR_INT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dterm_lpf_hz, .config.minmax = {0, 500 } },
|
||||||
{ "dynamic_iterm", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.dynamic_pid, .config.lookup = { TABLE_OFF_ON } },
|
{ "vbat_pid_compensation", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.vbatPidCompensation, .config.lookup = { TABLE_OFF_ON } },
|
||||||
|
{ "motor_accel_limit_percent", VAR_UINT16 | MASTER_VALUE, &masterConfig.profile[0].pidProfile.accelerationLimitPercent, .config.minmax = { 0, 10000 } },
|
||||||
|
{ "pid_tolerance_band", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.toleranceBand, .config.minmax = {0, 200 } },
|
||||||
|
{ "tolerance_band_reduction", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.toleranceBandReduction, .config.minmax = {0, 100 } },
|
||||||
|
{ "zero_cross_allowance", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.zeroCrossAllowanceCount, .config.minmax = {0, 50 } },
|
||||||
|
{ "iterm_throttle_gain", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.itermThrottleGain, .config.minmax = {0, 200 } },
|
||||||
|
|
||||||
{ "iterm_ignore_threshold", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.rollPitchItermIgnoreRate, .config.minmax = {15, 1000 } },
|
{ "iterm_ignore_threshold", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.rollPitchItermIgnoreRate, .config.minmax = {15, 1000 } },
|
||||||
{ "yaw_iterm_ignore_threshold", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yawItermIgnoreRate, .config.minmax = {15, 1000 } },
|
{ "yaw_iterm_ignore_threshold", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yawItermIgnoreRate, .config.minmax = {15, 1000 } },
|
||||||
{ "yaw_lowpass", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yaw_lpf_hz, .config.minmax = {0, 500 } },
|
{ "yaw_lowpass", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yaw_lpf_hz, .config.minmax = {0, 500 } },
|
||||||
|
|
|
@ -1219,14 +1219,14 @@ static bool processOutCommand(uint8_t cmdMSP)
|
||||||
serialize16(currentProfile->pidProfile.yawItermIgnoreRate);
|
serialize16(currentProfile->pidProfile.yawItermIgnoreRate);
|
||||||
serialize16(currentProfile->pidProfile.yaw_p_limit);
|
serialize16(currentProfile->pidProfile.yaw_p_limit);
|
||||||
serialize8(currentProfile->pidProfile.deltaMethod);
|
serialize8(currentProfile->pidProfile.deltaMethod);
|
||||||
serialize8(masterConfig.batteryConfig.vbatPidCompensation);
|
serialize8(currentProfile->pidProfile.vbatPidCompensation);
|
||||||
break;
|
break;
|
||||||
case MSP_SPECIAL_PARAMETERS:
|
case MSP_SPECIAL_PARAMETERS:
|
||||||
headSerialReply(1 + 2 + 1 + 2);
|
headSerialReply(1 + 2 + 1 + 2);
|
||||||
serialize8(currentControlRateProfile->rcYawRate8);
|
serialize8(currentControlRateProfile->rcYawRate8);
|
||||||
serialize16(masterConfig.rxConfig.airModeActivateThreshold);
|
serialize16(masterConfig.rxConfig.airModeActivateThreshold);
|
||||||
serialize8(masterConfig.rxConfig.rcSmoothInterval);
|
serialize8(masterConfig.rxConfig.rcSmoothInterval);
|
||||||
serialize16(masterConfig.escAndServoConfig.accelerationLimitPercent);
|
serialize16(currentProfile->pidProfile.accelerationLimitPercent);
|
||||||
break;
|
break;
|
||||||
case MSP_SENSOR_CONFIG:
|
case MSP_SENSOR_CONFIG:
|
||||||
headSerialReply(3);
|
headSerialReply(3);
|
||||||
|
@ -1295,7 +1295,7 @@ static bool processInCommand(void)
|
||||||
read16();
|
read16();
|
||||||
break;
|
break;
|
||||||
case MSP_SET_PID_CONTROLLER:
|
case MSP_SET_PID_CONTROLLER:
|
||||||
currentProfile->pidProfile.pidController = constrain(read8(), 1, 2);
|
currentProfile->pidProfile.pidController = constrain(read8(), 0, 1);
|
||||||
pidSetController(currentProfile->pidProfile.pidController);
|
pidSetController(currentProfile->pidProfile.pidController);
|
||||||
break;
|
break;
|
||||||
case MSP_SET_PID:
|
case MSP_SET_PID:
|
||||||
|
@ -1795,13 +1795,13 @@ static bool processInCommand(void)
|
||||||
currentProfile->pidProfile.yawItermIgnoreRate = read16();
|
currentProfile->pidProfile.yawItermIgnoreRate = read16();
|
||||||
currentProfile->pidProfile.yaw_p_limit = read16();
|
currentProfile->pidProfile.yaw_p_limit = read16();
|
||||||
currentProfile->pidProfile.deltaMethod = read8();
|
currentProfile->pidProfile.deltaMethod = read8();
|
||||||
masterConfig.batteryConfig.vbatPidCompensation = read8();
|
currentProfile->pidProfile.vbatPidCompensation = read8();
|
||||||
break;
|
break;
|
||||||
case MSP_SET_SPECIAL_PARAMETERS:
|
case MSP_SET_SPECIAL_PARAMETERS:
|
||||||
currentControlRateProfile->rcYawRate8 = read8();
|
currentControlRateProfile->rcYawRate8 = read8();
|
||||||
masterConfig.rxConfig.airModeActivateThreshold = read16();
|
masterConfig.rxConfig.airModeActivateThreshold = read16();
|
||||||
masterConfig.rxConfig.rcSmoothInterval = read8();
|
masterConfig.rxConfig.rcSmoothInterval = read8();
|
||||||
masterConfig.escAndServoConfig.accelerationLimitPercent = read16();
|
currentProfile->pidProfile.accelerationLimitPercent = read16();
|
||||||
break;
|
break;
|
||||||
case MSP_SET_SENSOR_CONFIG:
|
case MSP_SET_SENSOR_CONFIG:
|
||||||
masterConfig.acc_hardware = read8();
|
masterConfig.acc_hardware = read8();
|
||||||
|
|
|
@ -184,7 +184,7 @@ float calculateRate(int axis, int16_t rc) {
|
||||||
angleRate = (float)((currentControlRateProfile->rates[axis] + 27) * rc) / 16.0f;
|
angleRate = (float)((currentControlRateProfile->rates[axis] + 27) * rc) / 16.0f;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (currentProfile->pidProfile.pidController == PID_CONTROLLER_INTEGER)
|
if (currentProfile->pidProfile.pidController == PID_CONTROLLER_LEGACY)
|
||||||
return constrainf(angleRate, -8190.0f, 8190.0f); // Rate limit protection
|
return constrainf(angleRate, -8190.0f, 8190.0f); // Rate limit protection
|
||||||
else
|
else
|
||||||
return constrainf(angleRate / 4.1f, -1997.0f, 1997.0f); // Rate limit protection (deg/sec)
|
return constrainf(angleRate / 4.1f, -1997.0f, 1997.0f); // Rate limit protection (deg/sec)
|
||||||
|
@ -765,7 +765,7 @@ void subTaskMotorUpdate(void)
|
||||||
previousMotorUpdateTime = startTime;
|
previousMotorUpdateTime = startTime;
|
||||||
}
|
}
|
||||||
|
|
||||||
mixTable();
|
mixTable(¤tProfile->pidProfile);
|
||||||
|
|
||||||
#ifdef USE_SERVOS
|
#ifdef USE_SERVOS
|
||||||
filterServos();
|
filterServos();
|
||||||
|
|
|
@ -212,7 +212,7 @@ void updateCurrentMeter(int32_t lastUpdateAt, rxConfig_t *rxConfig, uint16_t dea
|
||||||
|
|
||||||
fix12_t calculateVbatPidCompensation(void) {
|
fix12_t calculateVbatPidCompensation(void) {
|
||||||
fix12_t batteryScaler;
|
fix12_t batteryScaler;
|
||||||
if (batteryConfig->vbatPidCompensation && feature(FEATURE_VBAT) && batteryCellCount > 1) {
|
if (feature(FEATURE_VBAT) && batteryCellCount > 1) {
|
||||||
uint16_t maxCalculatedVoltage = batteryConfig->vbatmaxcellvoltage * batteryCellCount;
|
uint16_t maxCalculatedVoltage = batteryConfig->vbatmaxcellvoltage * batteryCellCount;
|
||||||
batteryScaler = qConstruct(maxCalculatedVoltage, constrain(vbat, maxCalculatedVoltage - batteryConfig->vbatmaxcellvoltage, maxCalculatedVoltage));
|
batteryScaler = qConstruct(maxCalculatedVoltage, constrain(vbat, maxCalculatedVoltage - batteryConfig->vbatmaxcellvoltage, maxCalculatedVoltage));
|
||||||
} else {
|
} else {
|
||||||
|
|
|
@ -43,7 +43,6 @@ typedef struct batteryConfig_s {
|
||||||
uint8_t vbatmincellvoltage; // minimum voltage per cell, this triggers battery critical alarm, in 0.1V units, default is 33 (3.3V)
|
uint8_t vbatmincellvoltage; // minimum voltage per cell, this triggers battery critical alarm, in 0.1V units, default is 33 (3.3V)
|
||||||
uint8_t vbatwarningcellvoltage; // warning voltage per cell, this triggers battery warning alarm, in 0.1V units, default is 35 (3.5V)
|
uint8_t vbatwarningcellvoltage; // warning voltage per cell, this triggers battery warning alarm, in 0.1V units, default is 35 (3.5V)
|
||||||
uint8_t vbathysteresis; // hysteresis for alarm, default 1 = 0.1V
|
uint8_t vbathysteresis; // hysteresis for alarm, default 1 = 0.1V
|
||||||
uint8_t vbatPidCompensation; // Scale PIDsum to battery voltage
|
|
||||||
|
|
||||||
int16_t currentMeterScale; // scale the current sensor output voltage to milliamps. Value in 1/10th mV/A
|
int16_t currentMeterScale; // scale the current sensor output voltage to milliamps. Value in 1/10th mV/A
|
||||||
uint16_t currentMeterOffset; // offset of the current sensor in millivolt steps
|
uint16_t currentMeterOffset; // offset of the current sensor in millivolt steps
|
||||||
|
|
|
@ -121,7 +121,6 @@
|
||||||
|
|
||||||
#ifdef CC3D_OPBL
|
#ifdef CC3D_OPBL
|
||||||
#define SKIP_CLI_COMMAND_HELP
|
#define SKIP_CLI_COMMAND_HELP
|
||||||
//#define SKIP_PID_LUXFLOAT
|
|
||||||
#undef DISPLAY
|
#undef DISPLAY
|
||||||
#undef SONAR
|
#undef SONAR
|
||||||
#endif
|
#endif
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue