1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-16 12:55:19 +03:00

Busy wait reduction // Cleanup // New defaults

This commit is contained in:
borisbstyle 2016-08-20 23:24:25 +02:00
parent f21037ad37
commit 0668493ddd
5 changed files with 45 additions and 44 deletions

View file

@ -185,11 +185,11 @@ static void resetControlRateConfig(controlRateConfig_t *controlRateConfig)
{
controlRateConfig->rcRate8 = 100;
controlRateConfig->rcYawRate8 = 100;
controlRateConfig->rcExpo8 = 10;
controlRateConfig->rcExpo8 = 0;
controlRateConfig->thrMid8 = 50;
controlRateConfig->thrExpo8 = 0;
controlRateConfig->dynThrPID = 20;
controlRateConfig->rcYawExpo8 = 10;
controlRateConfig->dynThrPID = 10;
controlRateConfig->rcYawExpo8 = 0;
controlRateConfig->tpa_breakpoint = 1650;
for (uint8_t axis = 0; axis < FLIGHT_DYNAMICS_INDEX_COUNT; axis++) {
@ -205,7 +205,7 @@ static void resetPidProfile(pidProfile_t *pidProfile)
pidProfile->I8[ROLL] = 40;
pidProfile->D8[ROLL] = 20;
pidProfile->P8[PITCH] = 60;
pidProfile->I8[PITCH] = 60;
pidProfile->I8[PITCH] = 65;
pidProfile->D8[PITCH] = 22;
pidProfile->P8[YAW] = 80;
pidProfile->I8[YAW] = 45;
@ -236,11 +236,11 @@ static void resetPidProfile(pidProfile_t *pidProfile)
pidProfile->yawItermIgnoreRate = 32;
pidProfile->dterm_filter_type = FILTER_BIQUAD;
pidProfile->dterm_lpf_hz = 100; // filtering ON by default
pidProfile->dterm_notch_hz = 0;
pidProfile->dterm_notch_cutoff = 150;
pidProfile->dterm_notch_hz = 260;
pidProfile->dterm_notch_cutoff = 160;
pidProfile->deltaMethod = DELTA_FROM_MEASUREMENT;
pidProfile->vbatPidCompensation = 0;
pidProfile->pidAtMinThrottle = PID_STABILISATION_OFF;
pidProfile->pidAtMinThrottle = PID_STABILISATION_ON;
// Betaflight PID controller parameters
pidProfile->ptermSetpointWeight = 75;
@ -504,9 +504,9 @@ void createDefaultConfig(master_t *config)
config->gyroConfig.gyroMovementCalibrationThreshold = 32;
// xxx_hardware: 0:default/autodetect, 1: disable
config->mag_hardware = 0;
config->mag_hardware = 1;
config->baro_hardware = 0;
config->baro_hardware = 1;
resetBatteryConfig(&config->batteryConfig);
@ -585,8 +585,6 @@ void createDefaultConfig(master_t *config)
resetSerialConfig(&config->serialConfig);
config->emf_avoidance = 0; // TODO - needs removal
resetProfile(&config->profile[0]);
resetRollAndPitchTrims(&config->accelerometerTrims);
@ -619,7 +617,7 @@ void createDefaultConfig(master_t *config)
config->failsafeConfig.failsafe_throttle = 1000; // default throttle off.
config->failsafeConfig.failsafe_kill_switch = 0; // default failsafe switch action is identical to rc link loss
config->failsafeConfig.failsafe_throttle_low_delay = 100; // default throttle low delay for "just disarm" on failsafe condition
config->failsafeConfig.failsafe_procedure = 0; // default full failsafe procedure is 0: auto-landing
config->failsafeConfig.failsafe_procedure = FAILSAFE_PROCEDURE_DROP_IT;// default full failsafe procedure is 0: auto-landing
#ifdef USE_SERVOS
// servos

View file

@ -25,7 +25,6 @@ typedef struct master_t {
uint8_t mixerMode;
uint32_t enabledFeatures;
uint8_t emf_avoidance; // change pll settings to avoid noise in the uhf band
// motor/esc/servo related stuff
motorMixer_t customMotorMixer[MAX_SUPPORTED_MOTORS];

View file

@ -517,6 +517,10 @@ static const char * const lookupTableLowpassType[] = {
"NORMAL", "HIGH"
};
static const char * const lookupTableFailsafe[] = {
"AUTO-LAND", "DROP"
};
typedef struct lookupTableEntry_s {
const char * const *values;
const uint8_t valueCount;
@ -555,6 +559,7 @@ typedef enum {
TABLE_DELTA_METHOD,
TABLE_RC_INTERPOLATION,
TABLE_LOWPASS_TYPE,
TABLE_FAILSAFE,
#ifdef OSD
TABLE_OSD,
#endif
@ -593,6 +598,7 @@ static const lookupTableEntry_t lookupTables[] = {
{ lookupTableDeltaMethod, sizeof(lookupTableDeltaMethod) / sizeof(char *) },
{ lookupTableRcInterpolation, sizeof(lookupTableRcInterpolation) / sizeof(char *) },
{ lookupTableLowpassType, sizeof(lookupTableLowpassType) / sizeof(char *) },
{ lookupTableFailsafe, sizeof(lookupTableFailsafe) / sizeof(char *) },
#ifdef OSD
{ lookupTableOsdType, sizeof(lookupTableOsdType) / sizeof(char *) },
#endif
@ -646,7 +652,6 @@ typedef struct {
} clivalue_t;
const clivalue_t valueTable[] = {
// { "emf_avoidance", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.emf_avoidance, .config.lookup = { TABLE_OFF_ON } },
{ "mid_rc", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.midrc, .config.minmax = { 1200, 1700 } },
{ "min_check", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.mincheck, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
{ "max_check", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.maxcheck, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
@ -808,7 +813,7 @@ const clivalue_t valueTable[] = {
{ "failsafe_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_throttle, .config.minmax = { PWM_RANGE_MIN, PWM_RANGE_MAX } },
{ "failsafe_kill_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.failsafeConfig.failsafe_kill_switch, .config.lookup = { TABLE_OFF_ON } },
{ "failsafe_throttle_low_delay",VAR_UINT16 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_throttle_low_delay, .config.minmax = { 0, 300 } },
{ "failsafe_procedure", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.failsafeConfig.failsafe_procedure, .config.lookup = { TABLE_OFF_ON } },
{ "failsafe_procedure", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.failsafeConfig.failsafe_procedure, .config.lookup = { TABLE_FAILSAFE } },
{ "rx_min_usec", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.rx_min_usec, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX } },
{ "rx_max_usec", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.rx_max_usec, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX } },
@ -852,8 +857,8 @@ const clivalue_t valueTable[] = {
{ "yaw_rate_accel_limit", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yawRateAccelLimit, .config.minmax = {0, 1000 } },
{ "rate_accel_limit", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.rateAccelLimit, .config.minmax = {0, 1000 } },
{ "accumulation_threshold", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.rollPitchItermIgnoreRate, .config.minmax = {15, 1000 } },
{ "yaw_accumulation_threshold", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yawItermIgnoreRate, .config.minmax = {15, 1000 } },
{ "accum_threshold", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.rollPitchItermIgnoreRate, .config.minmax = {15, 1000 } },
{ "yaw_accum_threshold", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yawItermIgnoreRate, .config.minmax = {15, 1000 } },
{ "yaw_lowpass", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yaw_lpf_hz, .config.minmax = {0, 500 } },
{ "pid_process_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.pid_process_denom, .config.minmax = { 1, 8 } },

View file

@ -675,7 +675,7 @@ void main_init(void)
/* Setup scheduler */
schedulerInit();
rescheduleTask(TASK_GYROPID, gyro.targetLooptime);
rescheduleTask(TASK_GYROPID, gyro.targetLooptime + 5); // Add a littlebit of extra time to reduce busy wait
setTaskEnabled(TASK_GYROPID, true);
if (sensors(SENSOR_ACC)) {

View file

@ -816,8 +816,6 @@ void taskMainPidLoopCheck(void)
static uint32_t previousTime;
static bool runTaskMainSubprocesses;
const uint32_t currentDeltaTime = getTaskDeltaTime(TASK_SELF);
cycleTime = micros() - previousTime;
previousTime = micros();
@ -827,11 +825,16 @@ void taskMainPidLoopCheck(void)
}
const uint32_t startTime = micros();
while (true) {
if (gyroSyncCheckUpdate(&gyro) || ((currentDeltaTime + (micros() - previousTime)) >= (gyro.targetLooptime + GYRO_WATCHDOG_DELAY))) {
if (gyroSyncCheckUpdate(&gyro)) {
if (debugMode == DEBUG_PIDLOOP) {debug[0] = micros() - startTime;} // time spent busy waiting
break;
}
}
static uint8_t pidUpdateCountdown;
if (debugMode == DEBUG_PIDLOOP) {debug[0] = micros() - startTime;} // time spent busy waiting
if (runTaskMainSubprocesses) {
subTaskMainSubprocesses();
runTaskMainSubprocesses = false;
@ -847,10 +850,6 @@ void taskMainPidLoopCheck(void)
subTaskMotorUpdate();
runTaskMainSubprocesses = true;
}
break;
}
}
}
void taskUpdateAccelerometer(void)