1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-24 00:35:39 +03:00

Renaming getRcStickPosition to getRcStickDeflection and moving to

rc_controls.c.
This commit is contained in:
Dominic Clifton 2015-01-16 01:00:40 +00:00
parent b7462c0b3d
commit b64c71264c
5 changed files with 21 additions and 16 deletions

View file

@ -97,7 +97,8 @@ static uint32_t disarmAt; // Time of automatic disarm when "Don't spin the m
extern uint8_t dynP8[3], dynI8[3], dynD8[3];
extern failsafe_t *failsafe;
typedef void (*pidControllerFuncPtr)(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig, uint16_t max_angle_inclination, rollAndPitchTrims_t *accelerometerTrims);
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;
@ -355,11 +356,6 @@ void mwArm(void)
}
}
int32_t getRcStickPosition(int32_t axis) {
return min(abs(rcData[axis] - masterConfig.rxConfig.midrc), 500);
}
// Automatic ACC Offset Calibration
bool AccInflightCalibrationArmed = false;
bool AccInflightCalibrationMeasurementDone = false;
@ -714,7 +710,8 @@ void loop(void)
&currentProfile->pidProfile,
currentControlRateProfile,
masterConfig.max_angle_inclination,
&currentProfile->accelerometerTrims
&currentProfile->accelerometerTrims,
&masterConfig.rxConfig
);
mixTable();