1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-17 05:15:25 +03:00

Code Cleanup

More code cleanup and BUMP EEPROM

Code Cleanup

Fix loop trigger
This commit is contained in:
borisbstyle 2015-09-19 01:19:53 +02:00
parent 70d04e46d0
commit 0501e5ff91
29 changed files with 7377 additions and 81207 deletions

File diff suppressed because it is too large Load diff

File diff suppressed because it is too large Load diff

File diff suppressed because it is too large Load diff

Binary file not shown.

File diff suppressed because it is too large Load diff

File diff suppressed because it is too large Load diff

File diff suppressed because it is too large Load diff

Binary file not shown.

File diff suppressed because it is too large Load diff

Binary file not shown.

File diff suppressed because it is too large Load diff

File diff suppressed because it is too large Load diff

File diff suppressed because it is too large Load diff

File diff suppressed because it is too large Load diff

Binary file not shown.

File diff suppressed because it is too large Load diff

File diff suppressed because it is too large Load diff

View file

@ -128,7 +128,7 @@ static uint32_t activeFeaturesLatch = 0;
static uint8_t currentControlRateProfileIndex = 0; static uint8_t currentControlRateProfileIndex = 0;
controlRateConfig_t *currentControlRateProfile; controlRateConfig_t *currentControlRateProfile;
static const uint8_t EEPROM_CONF_VERSION = 105; static const uint8_t EEPROM_CONF_VERSION = 106;
static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims) static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims)
{ {
@ -453,9 +453,7 @@ static void resetConf(void)
resetSerialConfig(&masterConfig.serialConfig); resetSerialConfig(&masterConfig.serialConfig);
masterConfig.looptime = 0;
masterConfig.emf_avoidance = 0; masterConfig.emf_avoidance = 0;
masterConfig.syncGyroToLoop = 1;
masterConfig.rcSmoothing = 1; masterConfig.rcSmoothing = 1;
resetPidProfile(&currentProfile->pidProfile); resetPidProfile(&currentProfile->pidProfile);

View file

@ -25,9 +25,7 @@ typedef struct master_t {
uint8_t mixerMode; uint8_t mixerMode;
uint32_t enabledFeatures; uint32_t enabledFeatures;
uint16_t looptime; // imu loop time in us
uint8_t emf_avoidance; // change pll settings to avoid noise in the uhf band uint8_t emf_avoidance; // change pll settings to avoid noise in the uhf band
uint8_t syncGyroToLoop; // Enable interrupt based loop
uint8_t rcSmoothing; // Enable Interpolation of RC command uint8_t rcSmoothing; // Enable Interpolation of RC command
motorMixer_t customMotorMixer[MAX_SUPPORTED_MOTORS]; motorMixer_t customMotorMixer[MAX_SUPPORTED_MOTORS];

View file

@ -43,11 +43,10 @@ bool gyroSyncCheckUpdate(void) {
return getMpuDataStatus(&gyro); return getMpuDataStatus(&gyro);
} }
void gyroUpdateSampleRate(uint32_t looptime, uint8_t lpf, uint8_t syncGyroToLoop) { void gyroUpdateSampleRate(uint8_t lpf) {
int gyroSamplePeriod; int gyroSamplePeriod;
int minLooptime; int minLooptime;
if (syncGyroToLoop) {
#if defined(SPRACINGF3) || defined(ALIENWIIF3) || defined(NAZE32PRO) || defined(STM32F3DISCOVERY) || defined(CHEBUZZF3) || defined(PORT103R) || defined(MOTOLAB) || defined(SPARKY) #if defined(SPRACINGF3) || defined(ALIENWIIF3) || defined(NAZE32PRO) || defined(STM32F3DISCOVERY) || defined(CHEBUZZF3) || defined(PORT103R) || defined(MOTOLAB) || defined(SPARKY)
if (lpf == INV_FILTER_256HZ_NOLPF2) { if (lpf == INV_FILTER_256HZ_NOLPF2) {
gyroSamplePeriod = 125; gyroSamplePeriod = 125;
@ -106,13 +105,8 @@ void gyroUpdateSampleRate(uint32_t looptime, uint8_t lpf, uint8_t syncGyroToLoop
} }
} }
#endif #endif
looptime = constrain(looptime, minLooptime, 4000); mpuDividerDrops = (minLooptime + gyroSamplePeriod -1 ) / gyroSamplePeriod - 1;
mpuDividerDrops = (looptime + gyroSamplePeriod -1 ) / gyroSamplePeriod - 1;
targetLooptime = (mpuDividerDrops + 1) * gyroSamplePeriod; targetLooptime = (mpuDividerDrops + 1) * gyroSamplePeriod;
} else {
mpuDividerDrops = 0;
targetLooptime = looptime;
}
} }
uint8_t gyroMPU6xxxGetDividerDrops(void) { uint8_t gyroMPU6xxxGetDividerDrops(void) {

View file

@ -9,4 +9,4 @@ extern uint32_t targetLooptime;
bool gyroSyncCheckUpdate(void); bool gyroSyncCheckUpdate(void);
uint8_t gyroMPU6xxxGetDividerDrops(void); uint8_t gyroMPU6xxxGetDividerDrops(void);
void gyroUpdateSampleRate(uint32_t looptime, uint8_t lpf, uint8_t syncGyroToLoop); void gyroUpdateSampleRate(uint8_t lpf);

View file

@ -95,7 +95,7 @@ void pidResetErrorGyro(void)
const angle_index_t rcAliasToAngleIndexMap[] = { AI_ROLL, AI_PITCH }; const angle_index_t rcAliasToAngleIndexMap[] = { AI_ROLL, AI_PITCH };
static filterStatePt1_t PTermState[3], DTermState[3]; static filterStatePt1_t DTermState[3];
#ifdef AUTOTUNE #ifdef AUTOTUNE
bool shouldAutotune(void) bool shouldAutotune(void)

View file

@ -65,7 +65,6 @@ typedef struct pidProfile_s {
uint8_t dterm_cut_hz; // (default 17Hz, Range 1-50Hz) Used for PT1 element in PID1, PID2 and PID5 uint8_t dterm_cut_hz; // (default 17Hz, Range 1-50Hz) Used for PT1 element in PID1, PID2 and PID5
uint8_t pterm_cut_hz; // Used for fitlering Pterm noise on noisy frames uint8_t pterm_cut_hz; // Used for fitlering Pterm noise on noisy frames
uint8_t gyro_cut_hz; // Used for soft gyro filtering uint8_t gyro_cut_hz; // Used for soft gyro filtering
uint8_t gyro_fir_filter_enable; // Switches PT1 filter to 7TapFIRFilter for gyro
} pidProfile_t; } pidProfile_t;
#define DEGREES_TO_DECIDEGREES(angle) (angle * 10) #define DEGREES_TO_DECIDEGREES(angle) (angle * 10)

View file

@ -324,8 +324,6 @@ typedef struct {
} clivalue_t; } clivalue_t;
const clivalue_t valueTable[] = { const clivalue_t valueTable[] = {
{ "looptime", VAR_UINT16 | MASTER_VALUE, &masterConfig.looptime, 0, 4000 },
{ "sync_gyro_to_loop", VAR_UINT8 | MASTER_VALUE, &masterConfig.syncGyroToLoop, 0, 1 },
{ "emf_avoidance", VAR_UINT8 | MASTER_VALUE, &masterConfig.emf_avoidance, 0, 1 }, { "emf_avoidance", VAR_UINT8 | MASTER_VALUE, &masterConfig.emf_avoidance, 0, 1 },
{ "rc_smoothing", VAR_UINT8 | MASTER_VALUE, &masterConfig.rcSmoothing, 0, 1 }, { "rc_smoothing", VAR_UINT8 | MASTER_VALUE, &masterConfig.rcSmoothing, 0, 1 },

View file

@ -225,9 +225,6 @@ static const char * const boardIdentifier = TARGET_BOARD_IDENTIFIER;
#define MSP_DATAFLASH_READ 71 //out message - get content of dataflash chip #define MSP_DATAFLASH_READ 71 //out message - get content of dataflash chip
#define MSP_DATAFLASH_ERASE 72 //in message - erase dataflash chip #define MSP_DATAFLASH_ERASE 72 //in message - erase dataflash chip
#define MSP_LOOP_TIME 73 //out message Returns FC cycle time i.e looptime parameter
#define MSP_SET_LOOP_TIME 74 //in message Sets FC cycle time i.e looptime parameter
#define MSP_FAILSAFE_CONFIG 75 //out message Returns FC Fail-Safe settings #define MSP_FAILSAFE_CONFIG 75 //out message Returns FC Fail-Safe settings
#define MSP_SET_FAILSAFE_CONFIG 76 //in message Sets FC Fail-Safe settings #define MSP_SET_FAILSAFE_CONFIG 76 //in message Sets FC Fail-Safe settings
@ -929,10 +926,6 @@ static bool processOutCommand(uint8_t cmdMSP)
serialize8(masterConfig.auto_disarm_delay); serialize8(masterConfig.auto_disarm_delay);
serialize8(masterConfig.disarm_kill_switch); serialize8(masterConfig.disarm_kill_switch);
break; break;
case MSP_LOOP_TIME:
headSerialReply(2);
serialize16(masterConfig.looptime);
break;
case MSP_RC_TUNING: case MSP_RC_TUNING:
headSerialReply(11); headSerialReply(11);
serialize8(currentControlRateProfile->rcRate8); serialize8(currentControlRateProfile->rcRate8);
@ -1350,9 +1343,6 @@ static bool processInCommand(void)
masterConfig.auto_disarm_delay = read8(); masterConfig.auto_disarm_delay = read8();
masterConfig.disarm_kill_switch = read8(); masterConfig.disarm_kill_switch = read8();
break; break;
case MSP_SET_LOOP_TIME:
masterConfig.looptime = read16();
break;
case MSP_SET_PID_CONTROLLER: case MSP_SET_PID_CONTROLLER:
currentProfile->pidProfile.pidController = read8(); currentProfile->pidProfile.pidController = read8();
pidSetController(currentProfile->pidProfile.pidController); pidSetController(currentProfile->pidProfile.pidController);

View file

@ -371,7 +371,7 @@ void init(void)
} }
#endif #endif
if (!sensorsAutodetect(&masterConfig.sensorAlignmentConfig, masterConfig.gyro_lpf, masterConfig.acc_hardware, masterConfig.mag_hardware, masterConfig.baro_hardware, currentProfile->mag_declination, masterConfig.looptime, masterConfig.syncGyroToLoop)) { if (!sensorsAutodetect(&masterConfig.sensorAlignmentConfig, masterConfig.gyro_lpf, masterConfig.acc_hardware, masterConfig.mag_hardware, masterConfig.baro_hardware, currentProfile->mag_declination)) {
// if gyro was not detected due to whatever reason, we give up now. // if gyro was not detected due to whatever reason, we give up now.
failureMode(FAILURE_MISSING_ACC); failureMode(FAILURE_MISSING_ACC);
} }

View file

@ -723,21 +723,6 @@ void filterRc(void){
} }
} }
// Function for loop trigger
bool runLoop(uint32_t loopTime) {
bool loopTrigger = false;
if (masterConfig.syncGyroToLoop) {
if (gyroSyncCheckUpdate() || (int32_t)(currentTime - (loopTime + GYRO_WATCHDOG_DELAY)) >= 0) {
loopTrigger = true;
}
} else if (masterConfig.looptime == 0 || (int32_t)(currentTime - loopTime) >= 0){
loopTrigger = true;
}
return loopTrigger;
}
void loop(void) void loop(void)
{ {
static uint32_t loopTime; static uint32_t loopTime;
@ -784,7 +769,7 @@ void loop(void)
} }
currentTime = micros(); currentTime = micros();
if (runLoop(loopTime)) { if (gyroSyncCheckUpdate() || (int32_t)(currentTime - (loopTime + GYRO_WATCHDOG_DELAY)) >= 0) {
loopTime = currentTime + targetLooptime; loopTime = currentTime + targetLooptime;

View file

@ -633,7 +633,7 @@ void reconfigureAlignment(sensorAlignmentConfig_t *sensorAlignmentConfig)
} }
} }
bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint16_t gyroLpf, uint8_t accHardwareToUse, uint8_t magHardwareToUse, uint8_t baroHardwareToUse, int16_t magDeclinationFromConfig, uint32_t looptime, uint8_t syncGyroToLoop) bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint16_t gyroLpf, uint8_t accHardwareToUse, uint8_t magHardwareToUse, uint8_t baroHardwareToUse, int16_t magDeclinationFromConfig)
{ {
int16_t deg, min; int16_t deg, min;
@ -651,7 +651,7 @@ bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint16_t
if (sensors(SENSOR_ACC)) if (sensors(SENSOR_ACC))
acc.init(); acc.init();
// this is safe because either mpu6050 or mpu3050 or lg3d20 sets it, and in case of fail, we never get here. // this is safe because either mpu6050 or mpu3050 or lg3d20 sets it, and in case of fail, we never get here.
gyroUpdateSampleRate(looptime, gyroLpf, syncGyroToLoop); // Set gyro refresh rate before initialisation gyroUpdateSampleRate(gyroLpf); // Set gyro refresh rate before initialisation
gyro.init(); gyro.init();
detectMag(magHardwareToUse); detectMag(magHardwareToUse);

View file

@ -17,4 +17,4 @@
#pragma once #pragma once
bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint16_t gyroLpf, uint8_t accHardwareToUse, uint8_t magHardwareToUse, uint8_t baroHardwareToUse, int16_t magDeclinationFromConfig, uint32_t looptime, uint8_t syncGyroToLoop); bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint16_t gyroLpf, uint8_t accHardwareToUse, uint8_t magHardwareToUse, uint8_t baroHardwareToUse, int16_t magDeclinationFromConfig);