Merge pull request #402 from martinbudden/bf_pid_declaration
Moved declaration of pidControllerFuncPtr into pid.h
This commit is contained in:
commit
8149508352
|
@ -68,11 +68,8 @@ static float errorGyroIf[3], errorGyroIfLimit[3];
|
|||
|
||||
static bool lowThrottlePidReduction;
|
||||
|
||||
static void pidMultiWiiRewrite(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig,
|
||||
uint16_t max_angle_inclination, rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig);
|
||||
|
||||
typedef void (*pidControllerFuncPtr)(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig,
|
||||
uint16_t max_angle_inclination, rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig); // pid controller function prototype
|
||||
static void pidMultiWiiRewrite(const pidProfile_t *pidProfile, const controlRateConfig_t *controlRateConfig,
|
||||
uint16_t max_angle_inclination, const rollAndPitchTrims_t *angleTrim, const rxConfig_t *rxConfig);
|
||||
|
||||
pidControllerFuncPtr pid_controller = pidMultiWiiRewrite; // which pid controller are we using, defaultMultiWii
|
||||
|
||||
|
@ -80,7 +77,7 @@ void setTargetPidLooptime(uint8_t pidProcessDenom) {
|
|||
targetPidLooptime = targetLooptime * pidProcessDenom;
|
||||
}
|
||||
|
||||
float calculateExpoPlus(int axis, rxConfig_t *rxConfig) {
|
||||
float calculateExpoPlus(int axis, const rxConfig_t *rxConfig) {
|
||||
float propFactor;
|
||||
float superExpoFactor;
|
||||
|
||||
|
@ -94,7 +91,7 @@ float calculateExpoPlus(int axis, rxConfig_t *rxConfig) {
|
|||
return propFactor;
|
||||
}
|
||||
|
||||
uint16_t getDynamicKp(int axis, pidProfile_t *pidProfile) {
|
||||
uint16_t getDynamicKp(int axis, const pidProfile_t *pidProfile) {
|
||||
uint16_t dynamicKp;
|
||||
|
||||
uint32_t dynamicFactor = constrain(ABS(rcCommand[axis] << 8) / DYNAMIC_PTERM_STICK_THRESHOLD, 0, 1 << 7);
|
||||
|
@ -136,8 +133,8 @@ static filterStatePt1_t deltaFilterState[3];
|
|||
static filterStatePt1_t yawFilterState;
|
||||
|
||||
#ifndef SKIP_PID_LUXFLOAT
|
||||
static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig,
|
||||
uint16_t max_angle_inclination, rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig)
|
||||
static void pidLuxFloat(const pidProfile_t *pidProfile, const controlRateConfig_t *controlRateConfig,
|
||||
uint16_t max_angle_inclination, const rollAndPitchTrims_t *angleTrim, const rxConfig_t *rxConfig)
|
||||
{
|
||||
float RateError, AngleRate, gyroRate;
|
||||
float ITerm,PTerm,DTerm;
|
||||
|
@ -277,11 +274,9 @@ static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
|
|||
}
|
||||
#endif
|
||||
|
||||
static void pidMultiWiiRewrite(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig, uint16_t max_angle_inclination,
|
||||
rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig)
|
||||
static void pidMultiWiiRewrite(const pidProfile_t *pidProfile, const controlRateConfig_t *controlRateConfig, uint16_t max_angle_inclination,
|
||||
const rollAndPitchTrims_t *angleTrim, const rxConfig_t *rxConfig)
|
||||
{
|
||||
UNUSED(rxConfig);
|
||||
|
||||
int axis;
|
||||
int32_t PTerm, ITerm, DTerm, delta;
|
||||
static int32_t lastRate[3];
|
||||
|
|
|
@ -90,6 +90,12 @@ typedef struct pidProfile_s {
|
|||
#endif
|
||||
} pidProfile_t;
|
||||
|
||||
struct controlRateConfig_s;
|
||||
union rollAndPitchTrims_u;
|
||||
struct rxConfig_s;
|
||||
typedef void (*pidControllerFuncPtr)(const pidProfile_t *pidProfile, const struct controlRateConfig_s *controlRateConfig,
|
||||
uint16_t max_angle_inclination, const union rollAndPitchTrims_u *angleTrim, const struct rxConfig_s *rxConfig); // pid controller function prototype
|
||||
|
||||
extern int16_t axisPID[XYZ_AXIS_COUNT];
|
||||
extern int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3];
|
||||
bool antiWindupProtection;
|
||||
|
|
|
@ -119,9 +119,6 @@ uint16_t filteredCycleTime;
|
|||
static bool isRXDataNew;
|
||||
static bool armingCalibrationWasInitialised;
|
||||
|
||||
typedef void (*pidControllerFuncPtr)(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig,
|
||||
uint16_t max_angle_inclination, rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig); // pid controller function prototype
|
||||
|
||||
extern pidControllerFuncPtr pid_controller;
|
||||
|
||||
void applyAndSaveAccelerometerTrimsDelta(rollAndPitchTrims_t *rollAndPitchTrimsDelta)
|
||||
|
|
|
@ -45,7 +45,7 @@ typedef struct rollAndPitchTrims_s {
|
|||
int16_t pitch;
|
||||
} rollAndPitchTrims_t_def;
|
||||
|
||||
typedef union {
|
||||
typedef union rollAndPitchTrims_u {
|
||||
int16_t raw[2];
|
||||
rollAndPitchTrims_t_def values;
|
||||
} rollAndPitchTrims_t;
|
||||
|
|
Loading…
Reference in New Issue