Warning fixes

This commit is contained in:
blckmn 2016-06-23 20:25:31 +10:00
parent cd9a97006f
commit 86459a77ed
4 changed files with 27 additions and 21 deletions

View File

@ -98,19 +98,22 @@ __IO USB_OTG_DCTL_TypeDef SET_TEST_MODE;
USBD_DCD_INT_cb_TypeDef USBD_DCD_INT_cb = USBD_DCD_INT_cb_TypeDef USBD_DCD_INT_cb =
{ {
USBD_DataOutStage, USBD_DataOutStage,
USBD_DataInStage, USBD_DataInStage,
USBD_SetupStage, USBD_SetupStage,
USBD_SOF, USBD_SOF,
USBD_Reset, USBD_Reset,
USBD_Suspend, USBD_Suspend,
USBD_Resume, USBD_Resume,
USBD_IsoINIncomplete, USBD_IsoINIncomplete,
USBD_IsoOUTIncomplete, USBD_IsoOUTIncomplete,
#ifdef VBUS_SENSING_ENABLED #ifdef VBUS_SENSING_ENABLED
USBD_DevConnected, USBD_DevConnected,
USBD_DevDisconnected, USBD_DevDisconnected,
#endif #else
NULL,
NULL,
#endif
}; };
USBD_DCD_INT_cb_TypeDef *USBD_DCD_INT_fops = &USBD_DCD_INT_cb; USBD_DCD_INT_cb_TypeDef *USBD_DCD_INT_fops = &USBD_DCD_INT_cb;

View File

@ -63,7 +63,7 @@ typedef struct _USBD_DCD_INT
uint8_t (* DevConnected) (USB_OTG_CORE_HANDLE *pdev); uint8_t (* DevConnected) (USB_OTG_CORE_HANDLE *pdev);
uint8_t (* DevDisconnected) (USB_OTG_CORE_HANDLE *pdev); uint8_t (* DevDisconnected) (USB_OTG_CORE_HANDLE *pdev);
}USBD_DCD_INT_cb_TypeDef; } USBD_DCD_INT_cb_TypeDef;
extern USBD_DCD_INT_cb_TypeDef *USBD_DCD_INT_fops; extern USBD_DCD_INT_cb_TypeDef *USBD_DCD_INT_fops;
/** /**

View File

@ -72,11 +72,13 @@ static void pidInteger(const pidProfile_t *pidProfile, uint16_t max_angle_inclin
pidControllerFuncPtr pid_controller = pidInteger; // which pid controller are we using pidControllerFuncPtr pid_controller = pidInteger; // which pid controller are we using
void setTargetPidLooptime(uint8_t pidProcessDenom) { void setTargetPidLooptime(uint8_t pidProcessDenom)
targetPidLooptime = targetLooptime * pidProcessDenom; {
targetPidLooptime = targetLooptime * pidProcessDenom;
} }
uint16_t getDynamicKi(int axis, const pidProfile_t *pidProfile, int32_t angleRate) { uint16_t getDynamicKi(int axis, const pidProfile_t *pidProfile, int32_t angleRate)
{
uint16_t dynamicKi; uint16_t dynamicKi;
uint16_t resetRate; uint16_t resetRate;
@ -101,7 +103,8 @@ void pidResetErrorGyroState(void)
} }
} }
float getdT (void) { float getdT (void)
{
static float dT; static float dT;
if (!dT) dT = (float)targetPidLooptime * 0.000001f; if (!dT) dT = (float)targetPidLooptime * 0.000001f;
@ -117,7 +120,7 @@ static filterStatePt1_t yawFilterState;
static void pidFloat(const pidProfile_t *pidProfile, uint16_t max_angle_inclination, static void pidFloat(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, gyroRate, RateErrorSmooth; float RateError = 0, gyroRate = 0, RateErrorSmooth = 0;
float ITerm,PTerm,DTerm; float ITerm,PTerm,DTerm;
static float lastRateError[2]; static float lastRateError[2];
float delta; float delta;
@ -257,7 +260,7 @@ static void pidInteger(const pidProfile_t *pidProfile, uint16_t max_angle_inclin
int axis; int axis;
int32_t PTerm, ITerm, DTerm, delta; int32_t PTerm, ITerm, DTerm, delta;
static int32_t lastRateError[3]; static int32_t lastRateError[3];
int32_t AngleRateTmp, AngleRateTmpSmooth, RateError, gyroRate, RateErrorSmooth; int32_t AngleRateTmp = 0, AngleRateTmpSmooth = 0, RateError = 0, gyroRate = 0, RateErrorSmooth = 0;
int8_t horizonLevelStrength = 100; int8_t horizonLevelStrength = 100;

View File

@ -148,13 +148,13 @@ void setGyroSamplingSpeed(uint16_t looptime) {
gyroSampleRate = 125; gyroSampleRate = 125;
maxDivider = 8; maxDivider = 8;
masterConfig.pid_process_denom = 1; masterConfig.pid_process_denom = 1;
if (currentProfile->pidProfile.pidController == PID_CONTROLLER_LUX_FLOAT) { if (currentProfile->pidProfile.pidController == PID_CONTROLLER_FLOAT) {
masterConfig.pid_process_denom = 2; masterConfig.pid_process_denom = 2;
} }
if (looptime < 250) { if (looptime < 250) {
masterConfig.pid_process_denom = 4; masterConfig.pid_process_denom = 4;
} else if (looptime < 375) { } else if (looptime < 375) {
if (currentProfile->pidProfile.pidController == PID_CONTROLLER_LUX_FLOAT) { if (currentProfile->pidProfile.pidController == PID_CONTROLLER_FLOAT) {
masterConfig.pid_process_denom = 3; masterConfig.pid_process_denom = 3;
} else { } else {
masterConfig.pid_process_denom = 2; masterConfig.pid_process_denom = 2;