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

New defaults // FIX for slow defaults on SPI targets // refactor

This commit is contained in:
borisbstyle 2016-08-05 13:02:06 +02:00
parent 38e812a5a5
commit 2427ad1478
7 changed files with 26 additions and 25 deletions

View file

@ -1230,7 +1230,8 @@ static bool blackboxWriteSysinfo()
BLACKBOX_PRINT_HEADER_LINE("baro_hardware:%d", masterConfig.baro_hardware);
BLACKBOX_PRINT_HEADER_LINE("mag_hardware:%d", masterConfig.mag_hardware);
BLACKBOX_PRINT_HEADER_LINE("gyro_cal_on_first_arm:%d", masterConfig.gyro_cal_on_first_arm);
BLACKBOX_PRINT_HEADER_LINE("rc_smooth_interval:%d", masterConfig.rxConfig.rcSmoothInterval);
BLACKBOX_PRINT_HEADER_LINE("rc_interpolation:%d", masterConfig.rxConfig.rcInterpolation);
BLACKBOX_PRINT_HEADER_LINE("rc_interpolation_interval:%d", masterConfig.rxConfig.rcInterpolationInterval);
BLACKBOX_PRINT_HEADER_LINE("airmode_activate_throttle:%d", masterConfig.rxConfig.airModeActivateThreshold);
BLACKBOX_PRINT_HEADER_LINE("serialrx_provider:%d", masterConfig.rxConfig.serialrx_provider);
BLACKBOX_PRINT_HEADER_LINE("unsynced_fast_pwm:%d", masterConfig.use_unsyncedPwm);

View file

@ -245,9 +245,9 @@ static void resetPidProfile(pidProfile_t *pidProfile)
// Betaflight PID controller parameters
pidProfile->ptermSetpointWeight = 75;
pidProfile->dtermSetpointWeight = 120;
pidProfile->pidMaxVelocityYaw = 200;
pidProfile->pidMaxVelocityYaw = 220;
pidProfile->pidMaxVelocityRollPitch = 0;
pidProfile->toleranceBand = 20;
pidProfile->toleranceBand = 15;
pidProfile->toleranceBandReduction = 40;
pidProfile->zeroCrossAllowanceCount = 2;
pidProfile->itermThrottleGain = 0;
@ -476,14 +476,14 @@ static void resetConf(void)
masterConfig.gyro_sync_denom = 8;
masterConfig.pid_process_denom = 1;
#elif defined(USE_GYRO_SPI_MPU6000) || defined(USE_GYRO_SPI_MPU6500)
masterConfig.gyro_sync_denom = 8;
masterConfig.gyro_sync_denom = 1;
masterConfig.pid_process_denom = 4;
#else
masterConfig.gyro_sync_denom = 4;
masterConfig.pid_process_denom = 2;
#endif
masterConfig.gyro_soft_type = FILTER_PT1;
masterConfig.gyro_soft_lpf_hz = 100;
masterConfig.gyro_soft_lpf_hz = 90;
masterConfig.gyro_soft_notch_hz = 0;
masterConfig.gyro_soft_notch_cutoff = 150;
@ -535,8 +535,8 @@ static void resetConf(void)
masterConfig.rxConfig.rssi_channel = 0;
masterConfig.rxConfig.rssi_scale = RSSI_SCALE_DEFAULT;
masterConfig.rxConfig.rssi_ppm_invert = 0;
masterConfig.rxConfig.rcSmoothing = RC_SMOOTHING_AUTO;
masterConfig.rxConfig.rcSmoothInterval = 9;
masterConfig.rxConfig.rcInterpolation = RC_SMOOTHING_AUTO;
masterConfig.rxConfig.rcInterpolationInterval = 19;
masterConfig.rxConfig.fpvCamAngleDegrees = 0;
masterConfig.rxConfig.max_aux_channel = MAX_AUX_CHANNELS;
masterConfig.rxConfig.airModeActivateThreshold = 1350;

View file

@ -51,7 +51,7 @@ typedef enum {
DEBUG_AIRMODE,
DEBUG_PIDLOOP,
DEBUG_NOTCH,
DEBUG_RC_SMOOTHING,
DEBUG_RC_INTERPOLATION,
DEBUG_VELOCITY,
DEBUG_DTERM_FILTER,
DEBUG_COUNT

View file

@ -467,7 +467,7 @@ static const char * const lookupTableDebug[DEBUG_COUNT] = {
"AIRMODE",
"PIDLOOP",
"NOTCH",
"RC_SMOOTHING",
"RC_INTERPOLATION",
"VELOCITY",
"DFILTER",
};
@ -492,8 +492,8 @@ static const char * const lookupTableDeltaMethod[] = {
"ERROR", "MEASUREMENT"
};
static const char * const lookupTableRcSmoothing[] = {
"OFF", "DEFAULT", "AUTO", "MANUAL"
static const char * const lookupTableRcInterpolation[] = {
"OFF", "PRESET", "AUTO", "MANUAL"
};
static const char * const lookupTableLowpassType[] = {
@ -536,7 +536,7 @@ typedef enum {
TABLE_SUPEREXPO_YAW,
TABLE_MOTOR_PWM_PROTOCOL,
TABLE_DELTA_METHOD,
TABLE_RC_SMOOTHING,
TABLE_RC_INTERPOLATION,
TABLE_LOWPASS_TYPE,
#ifdef OSD
TABLE_OSD,
@ -574,7 +574,7 @@ static const lookupTableEntry_t lookupTables[] = {
{ lookupTableSuperExpoYaw, sizeof(lookupTableSuperExpoYaw) / sizeof(char *) },
{ lookupTablePwmProtocol, sizeof(lookupTablePwmProtocol) / sizeof(char *) },
{ lookupTableDeltaMethod, sizeof(lookupTableDeltaMethod) / sizeof(char *) },
{ lookupTableRcSmoothing, sizeof(lookupTableRcSmoothing) / sizeof(char *) },
{ lookupTableRcInterpolation, sizeof(lookupTableRcInterpolation) / sizeof(char *) },
{ lookupTableLowpassType, sizeof(lookupTableLowpassType) / sizeof(char *) },
#ifdef OSD
{ lookupTableOsdType, sizeof(lookupTableOsdType) / sizeof(char *) },
@ -635,8 +635,8 @@ const clivalue_t valueTable[] = {
{ "max_check", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.maxcheck, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
{ "rssi_channel", VAR_INT8 | MASTER_VALUE, &masterConfig.rxConfig.rssi_channel, .config.minmax = { 0, MAX_SUPPORTED_RC_CHANNEL_COUNT } },
{ "rssi_scale", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.rssi_scale, .config.minmax = { RSSI_SCALE_MIN, RSSI_SCALE_MAX } },
{ "rc_smoothing", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.rcSmoothing, .config.lookup = { TABLE_RC_SMOOTHING } },
{ "rc_smooth_interval_ms", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.rcSmoothInterval, .config.minmax = { 1, 50 } },
{ "rc_interpolation", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.rcInterpolation, .config.lookup = { TABLE_RC_INTERPOLATION } },
{ "rc_interpolation_interval", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.rcInterpolationInterval, .config.minmax = { 1, 50 } },
{ "rssi_ppm_invert", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.rssi_ppm_invert, .config.lookup = { TABLE_OFF_ON } },
{ "input_filtering_mode", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.inputFilteringMode, .config.lookup = { TABLE_OFF_ON } },
{ "roll_yaw_cam_mix_degrees", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.fpvCamAngleDegrees, .config.minmax = { 0, 50 } },

View file

@ -1041,8 +1041,8 @@ static bool processOutCommand(uint8_t cmdMSP)
serialize8(masterConfig.rxConfig.spektrum_sat_bind);
serialize16(masterConfig.rxConfig.rx_min_usec);
serialize16(masterConfig.rxConfig.rx_max_usec);
serialize8(masterConfig.rxConfig.rcSmoothing);
serialize8(masterConfig.rxConfig.rcSmoothInterval);
serialize8(masterConfig.rxConfig.rcInterpolation);
serialize8(masterConfig.rxConfig.rcInterpolationInterval);
serialize16(masterConfig.rxConfig.airModeActivateThreshold);
break;
@ -1688,8 +1688,8 @@ static bool processInCommand(void)
masterConfig.rxConfig.rx_max_usec = read16();
}
if (currentPort->dataSize > 12) {
masterConfig.rxConfig.rcSmoothing = read8();
masterConfig.rxConfig.rcSmoothInterval = read8();
masterConfig.rxConfig.rcInterpolation = read8();
masterConfig.rxConfig.rcInterpolationInterval = read8();
masterConfig.rxConfig.airModeActivateThreshold = read16();
}
break;

View file

@ -217,15 +217,15 @@ void processRcCommand(void)
uint16_t rxRefreshRate;
bool readyToCalculateRate = false;
if (masterConfig.rxConfig.rcSmoothing || flightModeFlags) {
if (masterConfig.rxConfig.rcInterpolation || flightModeFlags) {
if (isRXDataNew) {
// Set RC refresh rate for sampling and channels to filter
switch (masterConfig.rxConfig.rcSmoothing) {
switch (masterConfig.rxConfig.rcInterpolation) {
case(RC_SMOOTHING_AUTO):
rxRefreshRate = constrain(getTaskDeltaTime(TASK_RX), 1000, 20000) + 1000; // Add slight overhead to prevent ramps
break;
case(RC_SMOOTHING_MANUAL):
rxRefreshRate = 1000 * masterConfig.rxConfig.rcSmoothInterval;
rxRefreshRate = 1000 * masterConfig.rxConfig.rcInterpolationInterval;
break;
case(RC_SMOOTHING_OFF):
case(RC_SMOOTHING_DEFAULT):
@ -235,7 +235,7 @@ void processRcCommand(void)
rcInterpolationFactor = rxRefreshRate / targetPidLooptime + 1;
if (debugMode == DEBUG_RC_SMOOTHING) {
if (debugMode == DEBUG_RC_INTERPOLATION) {
for (int axis = 0; axis < 2; axis++) debug[axis] = rcCommand[axis];
debug[3] = rxRefreshRate;
}

View file

@ -121,8 +121,8 @@ typedef struct rxConfig_s {
uint16_t midrc; // Some radios have not a neutral point centered on 1500. can be changed here
uint16_t mincheck; // minimum rc end
uint16_t maxcheck; // maximum rc end
uint8_t rcSmoothing;
uint8_t rcSmoothInterval;
uint8_t rcInterpolation;
uint8_t rcInterpolationInterval;
uint8_t fpvCamAngleDegrees; // Camera angle to be scaled into rc commands
uint8_t max_aux_channel;
uint16_t airModeActivateThreshold; // Throttle setpoint where airmode gets activated