Merge remote-tracking branch 'betaflight/betaflight' into development

This commit is contained in:
blckmn 2016-06-26 08:52:28 +10:00
commit 00c0ca7c71
3 changed files with 10 additions and 8 deletions

View File

@ -180,7 +180,7 @@ static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims)
accelerometerTrims->values.yaw = 0;
}
static void resetPidProfile(pidProfile_t *pidProfile)
void resetPidProfile(pidProfile_t *pidProfile)
{
#if (defined(STM32F10X))
@ -195,7 +195,7 @@ static void resetPidProfile(pidProfile_t *pidProfile)
pidProfile->P8[PITCH] = 50;
pidProfile->I8[PITCH] = 40;
pidProfile->D8[PITCH] = 18;
pidProfile->P8[YAW] = 90;
pidProfile->P8[YAW] = 80;
pidProfile->I8[YAW] = 45;
pidProfile->D8[YAW] = 20;
pidProfile->P8[PIDALT] = 50;
@ -220,10 +220,10 @@ static void resetPidProfile(pidProfile_t *pidProfile)
pidProfile->yaw_p_limit = YAW_P_LIMIT_MAX;
pidProfile->yaw_lpf_hz = 80;
pidProfile->rollPitchItermIgnoreRate = 200;
pidProfile->rollPitchItermIgnoreRate = 180;
pidProfile->yawItermIgnoreRate = 35;
pidProfile->dterm_lpf_hz = 50; // filtering ON by default
pidProfile->deltaMethod = DELTA_FROM_ERROR;
pidProfile->dterm_lpf_hz = 100; // filtering ON by default
pidProfile->deltaMethod = DELTA_FROM_MEASUREMENT;
pidProfile->dynamic_pid = 1;
#ifdef GTUNE

View File

@ -1272,11 +1272,10 @@ static bool processOutCommand(uint8_t cmdMSP)
serialize16(currentProfile->pidProfile.yaw_lpf_hz);
break;
case MSP_ADVANCED_TUNING:
headSerialReply(4 * 2 + 2);
headSerialReply(3 * 2 + 2);
serialize16(currentProfile->pidProfile.rollPitchItermIgnoreRate);
serialize16(currentProfile->pidProfile.yawItermIgnoreRate);
serialize16(currentProfile->pidProfile.yaw_p_limit);
serialize16(masterConfig.rxConfig.airModeActivateThreshold);
serialize8(currentProfile->pidProfile.deltaMethod);
serialize8(masterConfig.batteryConfig.vbatPidCompensation);
break;
@ -1516,7 +1515,7 @@ static bool processInCommand(void)
break;
case MSP_SET_RESET_CURR_PID:
//resetPidProfile(&currentProfile->pidProfile);
resetPidProfile(&currentProfile->pidProfile);
break;
case MSP_SET_SENSOR_ALIGNMENT:
@ -1857,6 +1856,7 @@ static bool processInCommand(void)
currentProfile->pidProfile.yawItermIgnoreRate = read16();
currentProfile->pidProfile.yaw_p_limit = read16();
currentProfile->pidProfile.deltaMethod = read8();
masterConfig.batteryConfig.vbatPidCompensation = read8();
break;
case MSP_SET_SPECIAL_PARAMETERS:
currentControlRateProfile->rcYawRate8 = read8();

View File

@ -166,6 +166,8 @@ void gyroUpdate(void)
gyroADCf[axis] = applyBiQuadFilter((float) gyroADC[axis], &gyroFilterState[axis]);
gyroADC[axis] = lrintf(gyroADCf[axis]);
}
} else {
gyroADCf[axis] = gyroADC[axis]; // Otherwise float pid controller will not have gyro input when filter disabled
}
}
}