// alternative defaults settings for AlienFlight targets void targetConfiguration(void) { featureClear(FEATURE_ONESHOT125); masterConfig.mag_hardware = MAG_NONE; // disabled by default masterConfig.rxConfig.spektrum_sat_bind = 5; masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1; masterConfig.motor_pwm_rate = 32000; masterConfig.failsafeConfig.failsafe_delay = 2; masterConfig.failsafeConfig.failsafe_off_delay = 0; masterConfig.gyro_sync_denom = 2; masterConfig.pid_process_denom = 1; currentProfile->pidProfile.P8[ROLL] = 90; currentProfile->pidProfile.I8[ROLL] = 44; currentProfile->pidProfile.D8[ROLL] = 60; currentProfile->pidProfile.P8[PITCH] = 90; currentProfile->pidProfile.I8[PITCH] = 44; currentProfile->pidProfile.D8[PITCH] = 60; parseRcChannels("TAER1234", &masterConfig.rxConfig); masterConfig.customMotorMixer[0] = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R masterConfig.customMotorMixer[1] = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R masterConfig.customMotorMixer[2] = (motorMixer_t){ 1.0f, 0.414178f, 1.0f, 1.0f }; // REAR_L masterConfig.customMotorMixer[3] = (motorMixer_t){ 1.0f, 0.414178f, -1.0f, -1.0f }; // FRONT_L masterConfig.customMotorMixer[4] = (motorMixer_t){ 1.0f, -1.0f, -0.414178f, -1.0f }; // MIDFRONT_R masterConfig.customMotorMixer[5] = (motorMixer_t){ 1.0f, 1.0f, -0.414178f, 1.0f }; // MIDFRONT_L masterConfig.customMotorMixer[6] = (motorMixer_t){ 1.0f, -1.0f, 0.414178f, 1.0f }; // MIDREAR_R masterConfig.customMotorMixer[7] = (motorMixer_t){ 1.0f, 1.0f, 0.414178f, -1.0f }; // MIDREAR_L#endif }
static void cliMap(char *cmdline) { uint32_t len; uint32_t i; char out[rxRuntimeConfig.channelCount + 1]; len = strlen(cmdline); if (len == rxRuntimeConfig.channelCount) { // uppercase it for (i = 0; i < len; i++) cmdline[i] = toupper((unsigned char)cmdline[i]); //TODO: rewrite input sequence check /*for (i = 0; i < 8; i++) { if (strchr(rcChannelLetters, cmdline[i]) && !strchr(cmdline + i + 1, cmdline[i])) continue; cliPrint("Must be any order of AETR1234\r\n"); return; }*/ parseRcChannels(cmdline, &masterConfig.rxConfig); } cliPrint("Current assignment: "); for (i = 0; i < rxRuntimeConfig.channelCount; i++) out[i] = '-'; out[i] = '\0'; for (i = 0; i < 12; i++) if (masterConfig.rxConfig.rcmap[i] != -1) out[masterConfig.rxConfig.rcmap[i]] = rcChannelLetters[i]; printf("%s\r\n", out); }
static void cliMap(char *cmdline) { uint32_t len; uint32_t i; char out[9]; len = strlen(cmdline); if (len == mcfg.rc_channel_count) { // uppercase it for (i = 0; i < mcfg.rc_channel_count; i++) cmdline[i] = toupper((unsigned char)cmdline[i]); for (i = 0; i < mcfg.rc_channel_count; i++) { if (strchr(rcChannelLetters, cmdline[i]) && !strchr(cmdline + i + 1, cmdline[i])) continue; cliPrint("Must be any order of AETR1234\r\n"); return; } parseRcChannels(cmdline); } cliPrint("Current assignment: "); for (i = 0; i < mcfg.rc_channel_count; i++) out[mcfg.rcmap[i]] = rcChannelLetters[i]; out[i] = '\0'; printf("%s\r\n", out); }
void targetConfiguration(void) { if (hardwareMotorType == MOTOR_BRUSHED) { motorConfigMutable()->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE; motorConfigMutable()->minthrottle = 1049; #if defined(FF_ACROWHOOPSP) rxConfigMutable()->serialrx_provider = SERIALRX_SPEKTRUM2048; rxConfigMutable()->spektrum_sat_bind = 5; rxConfigMutable()->spektrum_sat_bind_autoreset = 1; #else serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART2)].functionMask = FUNCTION_TELEMETRY_FRSKY_HUB; rxConfigMutable()->serialrx_inverted = true; featureSet(FEATURE_TELEMETRY); #endif parseRcChannels("TAER1234", rxConfigMutable()); for (uint8_t pidProfileIndex = 0; pidProfileIndex < MAX_PROFILE_COUNT; pidProfileIndex++) { pidProfile_t *pidProfile = pidProfilesMutable(pidProfileIndex); pidProfile->pid[PID_ROLL].P = 80; pidProfile->pid[PID_ROLL].I = 37; pidProfile->pid[PID_ROLL].D = 35; pidProfile->pid[PID_PITCH].P = 100; pidProfile->pid[PID_PITCH].I = 37; pidProfile->pid[PID_PITCH].D = 35; pidProfile->pid[PID_YAW].P = 180; pidProfile->pid[PID_YAW].D = 45; } for (uint8_t rateProfileIndex = 0; rateProfileIndex < CONTROL_RATE_PROFILE_COUNT; rateProfileIndex++) { controlRateConfig_t *controlRateConfig = controlRateProfilesMutable(rateProfileIndex); controlRateConfig->rcRates[FD_ROLL] = 100; controlRateConfig->rcRates[FD_PITCH] = 100; controlRateConfig->rcRates[FD_YAW] = 100; controlRateConfig->rcExpo[FD_ROLL] = 15; controlRateConfig->rcExpo[FD_PITCH] = 15; controlRateConfig->rcExpo[FD_YAW] = 15; controlRateConfig->rates[PID_ROLL] = 80; controlRateConfig->rates[PID_PITCH] = 80; controlRateConfig->rates[PID_YAW] = 80; } } }
// alternative defaults settings for AlienFlight targets void targetConfiguration(void) { featureClear(FEATURE_ONESHOT125); masterConfig.rxConfig.spektrum_sat_bind = 5; masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1; masterConfig.motor_pwm_rate = 32000; masterConfig.failsafeConfig.failsafe_delay = 2; masterConfig.failsafeConfig.failsafe_off_delay = 0; parseRcChannels("TAER1234", &masterConfig.rxConfig); masterConfig.customMotorMixer[0] = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R masterConfig.customMotorMixer[1] = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R masterConfig.customMotorMixer[2] = (motorMixer_t){ 1.0f, 0.414178f, 1.0f, 1.0f }; // REAR_L masterConfig.customMotorMixer[3] = (motorMixer_t){ 1.0f, 0.414178f, -1.0f, -1.0f }; // FRONT_L masterConfig.customMotorMixer[4] = (motorMixer_t){ 1.0f, -1.0f, -0.414178f, -1.0f }; // MIDFRONT_R masterConfig.customMotorMixer[5] = (motorMixer_t){ 1.0f, 1.0f, -0.414178f, 1.0f }; // MIDFRONT_L masterConfig.customMotorMixer[6] = (motorMixer_t){ 1.0f, -1.0f, 0.414178f, 1.0f }; // MIDREAR_R masterConfig.customMotorMixer[7] = (motorMixer_t){ 1.0f, 1.0f, 0.414178f, -1.0f }; // MIDREAR_L#endif }
void checkFirstTime(bool eepromReset) { uint8_t test_val; test_val = *(uint8_t *)FLASH_WRITE_EEPROM_ADDR; if (eepromReset || test_val != checkNewEEPROMConf) { // Default settings eepromConfig.version = checkNewEEPROMConf; /////////////////////////////// eepromConfig.accelBiasMPU[XAXIS] = 0.0f; eepromConfig.accelBiasMPU[YAXIS] = 0.0f; eepromConfig.accelBiasMPU[ZAXIS] = 0.0f; /////////////////////////////// eepromConfig.accelScaleFactorMPU[XAXIS] = 0.00119708f; // (1/8192) * 9.8065 (8192 LSB = 1 G) eepromConfig.accelScaleFactorMPU[YAXIS] = 0.00119708f; // (1/8192) * 9.8065 (8192 LSB = 1 G) eepromConfig.accelScaleFactorMPU[ZAXIS] = 0.00119708f; // (1/8192) * 9.8065 (8192 LSB = 1 G) /////////////////////////////// eepromConfig.accelBiasMXR[XAXIS] = 2048.0f; eepromConfig.accelBiasMXR[YAXIS] = 2048.0f; eepromConfig.accelBiasMXR[ZAXIS] = 2048.0f; /////////////////////////////// eepromConfig.accelScaleFactorMXR[XAXIS] = 0.04937965f; // (3.3 / 4096) / 0.16 * 9.8065 eepromConfig.accelScaleFactorMXR[YAXIS] = 0.04937965f; // (3.3 / 4096) / 0.16 * 9.8065 eepromConfig.accelScaleFactorMXR[ZAXIS] = 0.04937965f; // (3.3 / 4096) / 0.16 * 9.8065 /////////////////////////////// eepromConfig.accelTCBiasSlope[XAXIS] = 0.0f; eepromConfig.accelTCBiasSlope[YAXIS] = 0.0f; eepromConfig.accelTCBiasSlope[ZAXIS] = 0.0f; /////////////////////////////// eepromConfig.accelTCBiasIntercept[XAXIS] = 0.0f; eepromConfig.accelTCBiasIntercept[YAXIS] = 0.0f; eepromConfig.accelTCBiasIntercept[ZAXIS] = 0.0f; /////////////////////////////// eepromConfig.gyroTCBiasSlope[ROLL ] = 0.0f; eepromConfig.gyroTCBiasSlope[PITCH] = 0.0f; eepromConfig.gyroTCBiasSlope[YAW ] = 0.0f; /////////////////////////////// eepromConfig.gyroTCBiasIntercept[ROLL ] = 0.0f; eepromConfig.gyroTCBiasIntercept[PITCH] = 0.0f; eepromConfig.gyroTCBiasIntercept[YAW ] = 0.0f; /////////////////////////////// eepromConfig.magBias[XAXIS] = 0.0f; // Internal Mag Bias eepromConfig.magBias[YAXIS] = 0.0f; // Internal Mag Bias eepromConfig.magBias[ZAXIS] = 0.0f; // Internal Mag Bias eepromConfig.magBias[XAXIS + 3] = 0.0f; // External Mag Bias eepromConfig.magBias[YAXIS + 3] = 0.0f; // External Mag Bias eepromConfig.magBias[ZAXIS + 3] = 0.0f; // External Mag Bias /////////////////////////////// eepromConfig.accelCutoff = 1.0f; /////////////////////////////// eepromConfig.KpAcc = 5.0f; // proportional gain governs rate of convergence to accelerometer eepromConfig.KiAcc = 0.0f; // integral gain governs rate of convergence of gyroscope biases eepromConfig.KpMag = 5.0f; // proportional gain governs rate of convergence to magnetometer eepromConfig.KiMag = 0.0f; // integral gain governs rate of convergence of gyroscope biases /////////////////////////////// eepromConfig.compFilterA = 2.0f; eepromConfig.compFilterB = 1.0f; /////////////////////////////// eepromConfig.dlpfSetting = BITS_DLPF_CFG_98HZ; /////////////////////////////////// eepromConfig.rollAndPitchRateScaling = 100.0 / 180000.0 * PI; // Stick to rate scaling for 100 DPS eepromConfig.yawRateScaling = 100.0 / 180000.0 * PI; // Stick to rate scaling for 100 DPS eepromConfig.attitudeScaling = 60.0 / 180000.0 * PI; // Stick to att scaling for 60 degrees eepromConfig.nDotEdotScaling = 0.009f; // Stick to nDot/eDot scaling (9 mps)/(1000 RX PWM Steps) = 0.009 eepromConfig.hDotScaling = 0.003f; // Stick to hDot scaling (3 mps)/(1000 RX PWM Steps) = 0.003 /////////////////////////////// eepromConfig.receiverType = SPEKTRUM; eepromConfig.slaveSpektrum = false; parseRcChannels("TAER2134"); eepromConfig.escPwmRate = 450; eepromConfig.servoPwmRate = 50; eepromConfig.mixerConfiguration = MIXERTYPE_TRI; eepromConfig.yawDirection = 1.0f; eepromConfig.triYawServoPwmRate = 50; eepromConfig.triYawServoMin = 2000.0f; eepromConfig.triYawServoMid = 3000.0f; eepromConfig.triYawServoMax = 4000.0f; eepromConfig.triCopterYawCmd500HzLowPassTau = 0.05f; // Free Mix Defaults to Quad X eepromConfig.freeMixMotors = 4; eepromConfig.freeMix[0][ROLL ] = 1.0f; eepromConfig.freeMix[0][PITCH] = -1.0f; eepromConfig.freeMix[0][YAW ] = -1.0f; eepromConfig.freeMix[1][ROLL ] = -1.0f; eepromConfig.freeMix[1][PITCH] = -1.0f; eepromConfig.freeMix[1][YAW ] = 1.0f; eepromConfig.freeMix[2][ROLL ] = -1.0f; eepromConfig.freeMix[2][PITCH] = 1.0f; eepromConfig.freeMix[2][YAW ] = -1.0f; eepromConfig.freeMix[3][ROLL ] = 1.0f; eepromConfig.freeMix[3][PITCH] = 1.0f; eepromConfig.freeMix[3][YAW ] = 1.0f; eepromConfig.freeMix[4][ROLL ] = 0.0f; eepromConfig.freeMix[4][PITCH] = 0.0f; eepromConfig.freeMix[4][YAW ] = 0.0f; eepromConfig.freeMix[5][ROLL ] = 0.0f; eepromConfig.freeMix[5][PITCH] = 0.0f; eepromConfig.freeMix[5][YAW ] = 0.0f; eepromConfig.midCommand = 3000.0f; eepromConfig.minCheck = (float)(MINCOMMAND + 200); eepromConfig.maxCheck = (float)(MAXCOMMAND - 200); eepromConfig.minThrottle = (float)(MINCOMMAND + 200); eepromConfig.maxThrottle = (float)(MAXCOMMAND); eepromConfig.PID[ROLL_RATE_PID].B = 1.0f; eepromConfig.PID[ROLL_RATE_PID].P = 250.0f; eepromConfig.PID[ROLL_RATE_PID].I = 100.0f; eepromConfig.PID[ROLL_RATE_PID].D = 0.0f; eepromConfig.PID[ROLL_RATE_PID].iTerm = 0.0f; eepromConfig.PID[ROLL_RATE_PID].windupGuard = 100.0f; // PWMs eepromConfig.PID[ROLL_RATE_PID].lastDcalcValue = 0.0f; eepromConfig.PID[ROLL_RATE_PID].lastDterm = 0.0f; eepromConfig.PID[ROLL_RATE_PID].lastLastDterm = 0.0f; eepromConfig.PID[ROLL_RATE_PID].dErrorCalc = D_ERROR; eepromConfig.PID[ROLL_RATE_PID].type = OTHER; eepromConfig.PID[PITCH_RATE_PID].B = 1.0f; eepromConfig.PID[PITCH_RATE_PID].P = 250.0f; eepromConfig.PID[PITCH_RATE_PID].I = 100.0f; eepromConfig.PID[PITCH_RATE_PID].D = 0.0f; eepromConfig.PID[PITCH_RATE_PID].iTerm = 0.0f; eepromConfig.PID[PITCH_RATE_PID].windupGuard = 100.0f; // PWMs eepromConfig.PID[PITCH_RATE_PID].lastDcalcValue = 0.0f; eepromConfig.PID[PITCH_RATE_PID].lastDterm = 0.0f; eepromConfig.PID[PITCH_RATE_PID].lastLastDterm = 0.0f; eepromConfig.PID[PITCH_RATE_PID].dErrorCalc = D_ERROR; eepromConfig.PID[PITCH_RATE_PID].type = OTHER; eepromConfig.PID[YAW_RATE_PID].B = 1.0f; eepromConfig.PID[YAW_RATE_PID].P = 350.0f; eepromConfig.PID[YAW_RATE_PID].I = 100.0f; eepromConfig.PID[YAW_RATE_PID].D = 0.0f; eepromConfig.PID[YAW_RATE_PID].iTerm = 0.0f; eepromConfig.PID[YAW_RATE_PID].windupGuard = 100.0f; // PWMs eepromConfig.PID[YAW_RATE_PID].lastDcalcValue = 0.0f; eepromConfig.PID[YAW_RATE_PID].lastDterm = 0.0f; eepromConfig.PID[YAW_RATE_PID].lastLastDterm = 0.0f; eepromConfig.PID[YAW_RATE_PID].dErrorCalc = D_ERROR; eepromConfig.PID[YAW_RATE_PID].type = OTHER; eepromConfig.PID[ROLL_ATT_PID].B = 1.0f; eepromConfig.PID[ROLL_ATT_PID].P = 2.0f; eepromConfig.PID[ROLL_ATT_PID].I = 0.0f; eepromConfig.PID[ROLL_ATT_PID].D = 0.0f; eepromConfig.PID[ROLL_ATT_PID].iTerm = 0.0f; eepromConfig.PID[ROLL_ATT_PID].windupGuard = 0.5f; // radians/sec eepromConfig.PID[ROLL_ATT_PID].lastDcalcValue = 0.0f; eepromConfig.PID[ROLL_ATT_PID].lastDterm = 0.0f; eepromConfig.PID[ROLL_ATT_PID].lastLastDterm = 0.0f; eepromConfig.PID[ROLL_ATT_PID].dErrorCalc = D_ERROR; eepromConfig.PID[ROLL_ATT_PID].type = ANGULAR; eepromConfig.PID[PITCH_ATT_PID].B = 1.0f; eepromConfig.PID[PITCH_ATT_PID].P = 2.0f; eepromConfig.PID[PITCH_ATT_PID].I = 0.0f; eepromConfig.PID[PITCH_ATT_PID].D = 0.0f; eepromConfig.PID[PITCH_ATT_PID].iTerm = 0.0f; eepromConfig.PID[PITCH_ATT_PID].windupGuard = 0.5f; // radians/sec eepromConfig.PID[PITCH_ATT_PID].lastDcalcValue = 0.0f; eepromConfig.PID[PITCH_ATT_PID].lastDterm = 0.0f; eepromConfig.PID[PITCH_ATT_PID].lastLastDterm = 0.0f; eepromConfig.PID[PITCH_ATT_PID].dErrorCalc = D_ERROR; eepromConfig.PID[PITCH_ATT_PID].type = ANGULAR; eepromConfig.PID[HEADING_PID].B = 1.0f; eepromConfig.PID[HEADING_PID].P = 3.0f; eepromConfig.PID[HEADING_PID].I = 0.0f; eepromConfig.PID[HEADING_PID].D = 0.0f; eepromConfig.PID[HEADING_PID].iTerm = 0.0f; eepromConfig.PID[HEADING_PID].windupGuard = 0.5f; // radians/sec eepromConfig.PID[HEADING_PID].lastDcalcValue = 0.0f; eepromConfig.PID[HEADING_PID].lastDterm = 0.0f; eepromConfig.PID[HEADING_PID].lastLastDterm = 0.0f; eepromConfig.PID[HEADING_PID].dErrorCalc = D_ERROR; eepromConfig.PID[HEADING_PID].type = ANGULAR; eepromConfig.PID[NDOT_PID].B = 1.0f; eepromConfig.PID[NDOT_PID].P = 3.0f; eepromConfig.PID[NDOT_PID].I = 0.0f; eepromConfig.PID[NDOT_PID].D = 0.0f; eepromConfig.PID[NDOT_PID].iTerm = 0.0f; eepromConfig.PID[NDOT_PID].windupGuard = 0.5f; eepromConfig.PID[NDOT_PID].lastDcalcValue = 0.0f; eepromConfig.PID[NDOT_PID].lastDterm = 0.0f; eepromConfig.PID[NDOT_PID].lastLastDterm = 0.0f; eepromConfig.PID[NDOT_PID].dErrorCalc = D_ERROR; eepromConfig.PID[NDOT_PID].type = OTHER; eepromConfig.PID[EDOT_PID].B = 1.0f; eepromConfig.PID[EDOT_PID].P = 3.0f; eepromConfig.PID[EDOT_PID].I = 0.0f; eepromConfig.PID[EDOT_PID].D = 0.0f; eepromConfig.PID[EDOT_PID].iTerm = 0.0f; eepromConfig.PID[EDOT_PID].windupGuard = 0.5f; eepromConfig.PID[EDOT_PID].lastDcalcValue = 0.0f; eepromConfig.PID[EDOT_PID].lastDterm = 0.0f; eepromConfig.PID[EDOT_PID].lastLastDterm = 0.0f; eepromConfig.PID[EDOT_PID].dErrorCalc = D_ERROR; eepromConfig.PID[EDOT_PID].type = OTHER; eepromConfig.PID[HDOT_PID].B = 1.0f; eepromConfig.PID[HDOT_PID].P = 2.0f; eepromConfig.PID[HDOT_PID].I = 0.0f; eepromConfig.PID[HDOT_PID].D = 0.0f; eepromConfig.PID[HDOT_PID].iTerm = 0.0f; eepromConfig.PID[HDOT_PID].windupGuard = 5.0f; eepromConfig.PID[HDOT_PID].lastDcalcValue = 0.0f; eepromConfig.PID[HDOT_PID].lastDterm = 0.0f; eepromConfig.PID[HDOT_PID].lastLastDterm = 0.0f; eepromConfig.PID[HDOT_PID].dErrorCalc = D_ERROR; eepromConfig.PID[HDOT_PID].type = OTHER; eepromConfig.PID[N_PID].B = 1.0f; eepromConfig.PID[N_PID].P = 3.0f; eepromConfig.PID[N_PID].I = 0.0f; eepromConfig.PID[N_PID].D = 0.0f; eepromConfig.PID[N_PID].iTerm = 0.0f; eepromConfig.PID[N_PID].windupGuard = 0.5f; eepromConfig.PID[N_PID].lastDcalcValue = 0.0f; eepromConfig.PID[N_PID].lastDterm = 0.0f; eepromConfig.PID[N_PID].lastLastDterm = 0.0f; eepromConfig.PID[N_PID].dErrorCalc = D_ERROR; eepromConfig.PID[N_PID].type = OTHER; eepromConfig.PID[E_PID].B = 1.0f; eepromConfig.PID[E_PID].P = 3.0f; eepromConfig.PID[E_PID].I = 0.0f; eepromConfig.PID[E_PID].D = 0.0f; eepromConfig.PID[E_PID].iTerm = 0.0f; eepromConfig.PID[E_PID].windupGuard = 0.5f; eepromConfig.PID[E_PID].lastDcalcValue = 0.0f; eepromConfig.PID[E_PID].lastDterm = 0.0f; eepromConfig.PID[E_PID].lastLastDterm = 0.0f; eepromConfig.PID[E_PID].dErrorCalc = D_ERROR; eepromConfig.PID[E_PID].type = OTHER; eepromConfig.PID[H_PID].B = 1.0f; eepromConfig.PID[H_PID].P = 2.0f; eepromConfig.PID[H_PID].I = 0.0f; eepromConfig.PID[H_PID].D = 0.0f; eepromConfig.PID[H_PID].iTerm = 0.0f; eepromConfig.PID[H_PID].windupGuard = 5.0f; eepromConfig.PID[H_PID].lastDcalcValue = 0.0f; eepromConfig.PID[H_PID].lastDterm = 0.0f; eepromConfig.PID[H_PID].lastLastDterm = 0.0f; eepromConfig.PID[H_PID].dErrorCalc = D_ERROR; eepromConfig.PID[H_PID].type = OTHER; eepromConfig.batteryCells = 3; eepromConfig.voltageMonitorScale = 11.5f / 1.5f; eepromConfig.voltageMonitorBias = 0.0f; eepromConfig.batteryLow = 3.30f; eepromConfig.batteryVeryLow = 3.20f; eepromConfig.batteryMaxLow = 3.10f; eepromConfig.armCount = 50; eepromConfig.disarmCount = 0; eepromConfig.activeTelemetry = 0; eepromConfig.mavlinkEnabled = false; eepromConfig.verticalVelocityHoldOnly = true; eepromConfig.externalHMC5883 = 0; eepromConfig.externalMS5611 = false; eepromConfig.useMXR9150 = false; writeEEPROM(); } }
void checkSystemEEPROM(bool eepromReset) { uint8_t version; systemConfigaddr.value = SYSTEM_EEPROM_ADDR; ENABLE_EEPROM; spiTransfer(EEPROM_SPI, READ_DATA); spiTransfer(EEPROM_SPI, systemConfigaddr.bytes[2]); spiTransfer(EEPROM_SPI, systemConfigaddr.bytes[1]); spiTransfer(EEPROM_SPI, systemConfigaddr.bytes[0]); version = spiTransfer(EEPROM_SPI, 0x00); DISABLE_EEPROM; delayMicroseconds(2); /////////////////////////////////// if (eepromReset || version != systemVersion) { // Default settings systemConfig.version = systemVersion; /////////////////////////////////// systemConfig.rollAndPitchRateScaling = 100.0 / 180000.0 * PI; // Stick to rate scaling for 100 DPS systemConfig.yawRateScaling = 300.0 / 180000.0 * PI; // Stick to rate scaling for 100 DPS systemConfig.rollRateCmdLowPassTau = 0.1f; systemConfig.pitchRateCmdLowPassTau = 0.1f; systemConfig.attitudeScaling = 60.0 / 180000.0 * PI; // Stick to att scaling for 60 degrees systemConfig.rollAttCmdLowPassTau = 0.1f; systemConfig.pitchAttCmdLowPassTau = 0.1f; systemConfig.nDotEdotScaling = 0.009f; // Stick to nDot/eDot scaling (9 mps)/(1000 RX PWM Steps) = 0.009 systemConfig.hDotScaling = 0.003f; // Stick to hDot scaling (3 mps)/(1000 RX PWM Steps) = 0.003 /////////////////////////////////// systemConfig.receiverType = SPEKTRUM; systemConfig.slaveSpektrum = false; parseRcChannels("TAER2134"); systemConfig.escPwmRate = 450; systemConfig.servoPwmRate = 50; /////////////////////////////////// systemConfig.mixerConfiguration = MIXERTYPE_TRI; systemConfig.yawDirection = 1.0f; systemConfig.triYawServoPwmRate = 50; systemConfig.triYawServoMin = 2000.0f; systemConfig.triYawServoMid = 3000.0f; systemConfig.triYawServoMax = 4000.0f; systemConfig.triCopterYawCmd500HzLowPassTau = 0.05f; // Free Mix Defaults to Quad X systemConfig.freeMixMotors = 4; systemConfig.freeMix[0][ROLL ] = 1.0f; systemConfig.freeMix[0][PITCH] = -1.0f; systemConfig.freeMix[0][YAW ] = -1.0f; systemConfig.freeMix[1][ROLL ] = -1.0f; systemConfig.freeMix[1][PITCH] = -1.0f; systemConfig.freeMix[1][YAW ] = 1.0f; systemConfig.freeMix[2][ROLL ] = -1.0f; systemConfig.freeMix[2][PITCH] = 1.0f; systemConfig.freeMix[2][YAW ] = -1.0f; systemConfig.freeMix[3][ROLL ] = 1.0f; systemConfig.freeMix[3][PITCH] = 1.0f; systemConfig.freeMix[3][YAW ] = 1.0f; systemConfig.freeMix[4][ROLL ] = 0.0f; systemConfig.freeMix[4][PITCH] = 0.0f; systemConfig.freeMix[4][YAW ] = 0.0f; systemConfig.freeMix[5][ROLL ] = 0.0f; systemConfig.freeMix[5][PITCH] = 0.0f; systemConfig.freeMix[5][YAW ] = 0.0f; /////////////////////////////// systemConfig.rollAttAltCompensationGain = 1.0f; systemConfig.rollAttAltCompensationLimit = 0.0f * D2R; systemConfig.pitchAttAltCompensationGain = 1.0f; systemConfig.pitchAttAltCompensationLimit = 0.0f * D2R; /////////////////////////////////// systemConfig.midCommand = 3000.0f; systemConfig.minCheck = (float)(MINCOMMAND + 200); systemConfig.maxCheck = (float)(MAXCOMMAND - 200); systemConfig.minThrottle = (float)(MINCOMMAND + 200); systemConfig.maxThrottle = (float)(MAXCOMMAND); /////////////////////////////// systemConfig.PID[ROLL_RATE_PID].P = 250.0f; systemConfig.PID[ROLL_RATE_PID].I = 100.0f; systemConfig.PID[ROLL_RATE_PID].D = 0.0f; systemConfig.PID[ROLL_RATE_PID].N = 100.0f; systemConfig.PID[ROLL_RATE_PID].integratorState = 0.0f; systemConfig.PID[ROLL_RATE_PID].filterState = 0.0f; systemConfig.PID[ROLL_RATE_PID].prevResetState = false; systemConfig.PID[PITCH_RATE_PID].P = 250.0f; systemConfig.PID[PITCH_RATE_PID].I = 100.0f; systemConfig.PID[PITCH_RATE_PID].D = 0.0f; systemConfig.PID[PITCH_RATE_PID].N = 100.0f; systemConfig.PID[PITCH_RATE_PID].integratorState = 0.0f; systemConfig.PID[PITCH_RATE_PID].filterState = 0.0f; systemConfig.PID[PITCH_RATE_PID].prevResetState = false; systemConfig.PID[YAW_RATE_PID].P = 350.0f; systemConfig.PID[YAW_RATE_PID].I = 100.0f; systemConfig.PID[YAW_RATE_PID].D = 0.0f; systemConfig.PID[YAW_RATE_PID].N = 100.0f; systemConfig.PID[YAW_RATE_PID].integratorState = 0.0f; systemConfig.PID[YAW_RATE_PID].filterState = 0.0f; systemConfig.PID[YAW_RATE_PID].prevResetState = false; systemConfig.PID[ROLL_ATT_PID].P = 2.0f; systemConfig.PID[ROLL_ATT_PID].I = 0.0f; systemConfig.PID[ROLL_ATT_PID].D = 0.0f; systemConfig.PID[ROLL_ATT_PID].N = 100.0f; systemConfig.PID[ROLL_ATT_PID].integratorState = 0.0f; systemConfig.PID[ROLL_ATT_PID].filterState = 0.0f; systemConfig.PID[ROLL_ATT_PID].prevResetState = false; systemConfig.PID[PITCH_ATT_PID].P = 2.0f; systemConfig.PID[PITCH_ATT_PID].I = 0.0f; systemConfig.PID[PITCH_ATT_PID].D = 0.0f; systemConfig.PID[PITCH_ATT_PID].N = 100.0f; systemConfig.PID[PITCH_ATT_PID].integratorState = 0.0f; systemConfig.PID[PITCH_ATT_PID].filterState = 0.0f; systemConfig.PID[PITCH_ATT_PID].prevResetState = false; systemConfig.PID[HEADING_PID].P = 3.0f; systemConfig.PID[HEADING_PID].I = 0.0f; systemConfig.PID[HEADING_PID].D = 0.0f; systemConfig.PID[HEADING_PID].N = 100.0f; systemConfig.PID[HEADING_PID].integratorState = 0.0f; systemConfig.PID[HEADING_PID].filterState = 0.0f; systemConfig.PID[HEADING_PID].prevResetState = false; systemConfig.PID[NDOT_PID].P = 3.0f; systemConfig.PID[NDOT_PID].I = 0.0f; systemConfig.PID[NDOT_PID].D = 0.0f; systemConfig.PID[NDOT_PID].N = 100.0f; systemConfig.PID[NDOT_PID].integratorState = 0.0f; systemConfig.PID[NDOT_PID].filterState = 0.0f; systemConfig.PID[NDOT_PID].prevResetState = false; systemConfig.PID[EDOT_PID].P = 3.0f; systemConfig.PID[EDOT_PID].I = 0.0f; systemConfig.PID[EDOT_PID].D = 0.0f; systemConfig.PID[EDOT_PID].N = 100.0f; systemConfig.PID[EDOT_PID].integratorState = 0.0f; systemConfig.PID[EDOT_PID].filterState = 0.0f; systemConfig.PID[EDOT_PID].prevResetState = false; systemConfig.PID[HDOT_PID].P = 2.0f; systemConfig.PID[HDOT_PID].I = 0.0f; systemConfig.PID[HDOT_PID].D = 0.0f; systemConfig.PID[HDOT_PID].N = 100.0f; systemConfig.PID[HDOT_PID].integratorState = 0.0f; systemConfig.PID[HDOT_PID].filterState = 0.0f; systemConfig.PID[HDOT_PID].prevResetState = false; systemConfig.PID[N_PID].P = 3.0f; systemConfig.PID[N_PID].I = 0.0f; systemConfig.PID[N_PID].D = 0.0f; systemConfig.PID[N_PID].N = 100.0f; systemConfig.PID[N_PID].integratorState = 0.0f; systemConfig.PID[N_PID].filterState = 0.0f; systemConfig.PID[N_PID].prevResetState = false; systemConfig.PID[E_PID].P = 3.0f; systemConfig.PID[E_PID].I = 0.0f; systemConfig.PID[E_PID].D = 0.0f; systemConfig.PID[E_PID].N = 100.0f; systemConfig.PID[E_PID].integratorState = 0.0f; systemConfig.PID[E_PID].filterState = 0.0f; systemConfig.PID[E_PID].prevResetState = false; systemConfig.PID[H_PID].P = 2.0f; systemConfig.PID[H_PID].I = 0.0f; systemConfig.PID[H_PID].D = 0.0f; systemConfig.PID[H_PID].N = 100.0f; systemConfig.PID[H_PID].integratorState = 0.0f; systemConfig.PID[H_PID].filterState = 0.0f; systemConfig.PID[H_PID].prevResetState = false; /////////////////////////////// systemConfig.armCount = 50; systemConfig.disarmCount = 0; /////////////////////////////////// systemConfig.activeTelemetry = 0; systemConfig.mavlinkEnabled = false; /////////////////////////////////// systemConfig.CRCFlags = 0; /////////////////////////////////// writeSystemEEPROM(); } }
void createDefaultConfig(master_t *config) { // Clear all configuration memset(config, 0, sizeof(master_t)); uint32_t *featuresPtr = &config->enabledFeatures; intFeatureClearAll(featuresPtr); intFeatureSet(DEFAULT_RX_FEATURE | FEATURE_FAILSAFE , featuresPtr); #ifdef DEFAULT_FEATURES intFeatureSet(DEFAULT_FEATURES, featuresPtr); #endif #ifdef OSD intFeatureSet(FEATURE_OSD, featuresPtr); osdResetConfig(&config->osdProfile); #endif #ifdef BOARD_HAS_VOLTAGE_DIVIDER // only enable the VBAT feature by default if the board has a voltage divider otherwise // the user may see incorrect readings and unexpected issues with pin mappings may occur. intFeatureSet(FEATURE_VBAT, featuresPtr); #endif config->version = EEPROM_CONF_VERSION; config->mixerMode = MIXER_QUADX; // global settings config->current_profile_index = 0; // default profile config->dcm_kp = 2500; // 1.0 * 10000 config->dcm_ki = 0; // 0.003 * 10000 config->gyro_lpf = 0; // 256HZ default #ifdef STM32F10X config->gyro_sync_denom = 8; config->pid_process_denom = 1; #elif defined(USE_GYRO_SPI_MPU6000) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_ICM20689) config->gyro_sync_denom = 1; config->pid_process_denom = 4; #else config->gyro_sync_denom = 4; config->pid_process_denom = 2; #endif config->gyro_soft_type = FILTER_PT1; config->gyro_soft_lpf_hz = 90; config->gyro_soft_notch_hz_1 = 400; config->gyro_soft_notch_cutoff_1 = 300; config->gyro_soft_notch_hz_2 = 200; config->gyro_soft_notch_cutoff_2 = 100; config->debug_mode = DEBUG_NONE; resetAccelerometerTrims(&config->accZero); resetSensorAlignment(&config->sensorAlignmentConfig); config->boardAlignment.rollDegrees = 0; config->boardAlignment.pitchDegrees = 0; config->boardAlignment.yawDegrees = 0; config->acc_hardware = ACC_DEFAULT; // default/autodetect config->max_angle_inclination = 700; // 70 degrees config->yaw_control_direction = 1; config->gyroConfig.gyroMovementCalibrationThreshold = 32; // xxx_hardware: 0:default/autodetect, 1: disable config->mag_hardware = 1; config->baro_hardware = 1; resetBatteryConfig(&config->batteryConfig); #ifndef SKIP_RX_PWM_PPM resetPpmConfig(&config->ppmConfig); resetPwmConfig(&config->pwmConfig); #endif #ifdef TELEMETRY resetTelemetryConfig(&config->telemetryConfig); #endif #ifdef USE_ADC resetAdcConfig(&config->adcConfig); #endif #ifdef BEEPER resetBeeperConfig(&config->beeperConfig); #endif #ifdef SONAR resetSonarConfig(&config->sonarConfig); #endif #ifdef USE_SDCARD intFeatureSet(FEATURE_SDCARD, featuresPtr); resetsdcardConfig(&config->sdcardConfig); #endif #ifdef SERIALRX_PROVIDER config->rxConfig.serialrx_provider = SERIALRX_PROVIDER; #else config->rxConfig.serialrx_provider = 0; #endif config->rxConfig.rx_spi_protocol = RX_SPI_DEFAULT_PROTOCOL; config->rxConfig.sbus_inversion = 1; config->rxConfig.spektrum_sat_bind = 0; config->rxConfig.spektrum_sat_bind_autoreset = 1; config->rxConfig.midrc = 1500; config->rxConfig.mincheck = 1100; config->rxConfig.maxcheck = 1900; config->rxConfig.rx_min_usec = 885; // any of first 4 channels below this value will trigger rx loss detection config->rxConfig.rx_max_usec = 2115; // any of first 4 channels above this value will trigger rx loss detection for (int i = 0; i < MAX_SUPPORTED_RC_CHANNEL_COUNT; i++) { rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration = &config->rxConfig.failsafe_channel_configurations[i]; channelFailsafeConfiguration->mode = (i < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_MODE_AUTO : RX_FAILSAFE_MODE_HOLD; channelFailsafeConfiguration->step = (i == THROTTLE) ? CHANNEL_VALUE_TO_RXFAIL_STEP(config->rxConfig.rx_min_usec) : CHANNEL_VALUE_TO_RXFAIL_STEP(config->rxConfig.midrc); } config->rxConfig.rssi_channel = 0; config->rxConfig.rssi_scale = RSSI_SCALE_DEFAULT; config->rxConfig.rssi_ppm_invert = 0; config->rxConfig.rcInterpolation = RC_SMOOTHING_AUTO; config->rxConfig.rcInterpolationInterval = 19; config->rxConfig.fpvCamAngleDegrees = 0; config->rxConfig.max_aux_channel = MAX_AUX_CHANNELS; config->rxConfig.airModeActivateThreshold = 1350; resetAllRxChannelRangeConfigurations(config->rxConfig.channelRanges); config->inputFilteringMode = INPUT_FILTERING_DISABLED; config->gyro_cal_on_first_arm = 0; // TODO - Cleanup retarded arm support config->disarm_kill_switch = 1; config->auto_disarm_delay = 5; config->small_angle = 25; config->airplaneConfig.fixedwing_althold_dir = 1; // Motor/ESC/Servo resetMixerConfig(&config->mixerConfig); resetMotorConfig(&config->motorConfig); #ifdef USE_SERVOS resetServoMixerConfig(&config->servoMixerConfig); resetServoConfig(&config->servoConfig); #endif resetFlight3DConfig(&config->flight3DConfig); #ifdef LED_STRIP resetLedStripConfig(&config->ledStripConfig); #endif #ifdef GPS // gps/nav stuff config->gpsConfig.provider = GPS_NMEA; config->gpsConfig.sbasMode = SBAS_AUTO; config->gpsConfig.autoConfig = GPS_AUTOCONFIG_ON; config->gpsConfig.autoBaud = GPS_AUTOBAUD_OFF; #endif resetSerialConfig(&config->serialConfig); resetProfile(&config->profile[0]); resetRollAndPitchTrims(&config->accelerometerTrims); config->mag_declination = 0; config->acc_lpf_hz = 10.0f; config->accDeadband.xy = 40; config->accDeadband.z = 40; config->acc_unarmedcal = 1; #ifdef BARO resetBarometerConfig(&config->barometerConfig); #endif // Radio #ifdef RX_CHANNELS_TAER parseRcChannels("TAER1234", &config->rxConfig); #else parseRcChannels("AETR1234", &config->rxConfig); #endif resetRcControlsConfig(&config->rcControlsConfig); config->throttle_correction_value = 0; // could 10 with althold or 40 for fpv config->throttle_correction_angle = 800; // could be 80.0 deg with atlhold or 45.0 for fpv // Failsafe Variables config->failsafeConfig.failsafe_delay = 10; // 1sec config->failsafeConfig.failsafe_off_delay = 10; // 1sec 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 = FAILSAFE_PROCEDURE_DROP_IT;// default full failsafe procedure is 0: auto-landing #ifdef USE_SERVOS // servos for (int i = 0; i < MAX_SUPPORTED_SERVOS; i++) { config->servoConf[i].min = DEFAULT_SERVO_MIN; config->servoConf[i].max = DEFAULT_SERVO_MAX; config->servoConf[i].middle = DEFAULT_SERVO_MIDDLE; config->servoConf[i].rate = 100; config->servoConf[i].angleAtMin = DEFAULT_SERVO_MIN_ANGLE; config->servoConf[i].angleAtMax = DEFAULT_SERVO_MAX_ANGLE; config->servoConf[i].forwardFromChannel = CHANNEL_FORWARDING_DISABLED; } // gimbal config->gimbalConfig.mode = GIMBAL_MODE_NORMAL; #endif #ifdef GPS resetGpsProfile(&config->gpsProfile); #endif // custom mixer. clear by defaults. for (int i = 0; i < MAX_SUPPORTED_MOTORS; i++) { config->customMotorMixer[i].throttle = 0.0f; } #ifdef VTX config->vtx_band = 4; //Fatshark/Airwaves config->vtx_channel = 1; //CH1 config->vtx_mode = 0; //CH+BAND mode config->vtx_mhz = 5740; //F0 #endif #ifdef TRANSPONDER static const uint8_t defaultTransponderData[6] = { 0x12, 0x34, 0x56, 0x78, 0x9A, 0xBC }; // Note, this is NOT a valid transponder code, it's just for testing production hardware memcpy(config->transponderData, &defaultTransponderData, sizeof(defaultTransponderData)); #endif #ifdef BLACKBOX #if defined(ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT) intFeatureSet(FEATURE_BLACKBOX, featuresPtr); config->blackbox_device = BLACKBOX_DEVICE_FLASH; #elif defined(ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT) intFeatureSet(FEATURE_BLACKBOX, featuresPtr); config->blackbox_device = BLACKBOX_DEVICE_SDCARD; #else config->blackbox_device = BLACKBOX_DEVICE_SERIAL; #endif config->blackbox_rate_num = 1; config->blackbox_rate_denom = 1; config->blackbox_on_motor_test = 0; // default off #endif // BLACKBOX #ifdef SERIALRX_UART if (featureConfigured(FEATURE_RX_SERIAL)) { int serialIndex = findSerialPortIndexByIdentifier(SERIALRX_UART); if (serialIndex >= 0) { config->serialConfig.portConfigs[serialIndex].functionMask = FUNCTION_RX_SERIAL; } } #endif #if defined(TARGET_CONFIG) targetConfiguration(config); #endif // copy first profile into remaining profile for (int i = 1; i < MAX_PROFILE_COUNT; i++) { memcpy(&config->profile[i], &config->profile[0], sizeof(profile_t)); } }
void checkFirstTime(bool reset) { uint8_t test_val, i; test_val = *(uint8_t *) FLASH_WRITE_ADDR; if (!reset && test_val == checkNewConf) return; // Default settings cfg.version = checkNewConf; cfg.mixerConfiguration = MULTITYPE_QUADX; featureClearAll(); featureSet(FEATURE_VBAT); cfg.looptime = 0; cfg.P8[ROLL] = 40; cfg.I8[ROLL] = 30; cfg.D8[ROLL] = 23; cfg.P8[PITCH] = 40; cfg.I8[PITCH] = 30; cfg.D8[PITCH] = 23; cfg.P8[YAW] = 85; cfg.I8[YAW] = 45; cfg.D8[YAW] = 0; cfg.P8[PIDALT] = 16; cfg.I8[PIDALT] = 15; cfg.D8[PIDALT] = 7; cfg.P8[PIDPOS] = 11; // POSHOLD_P * 100; cfg.I8[PIDPOS] = 0; // POSHOLD_I * 100; cfg.D8[PIDPOS] = 0; cfg.P8[PIDPOSR] = 20; // POSHOLD_RATE_P * 10; cfg.I8[PIDPOSR] = 8; // POSHOLD_RATE_I * 100; cfg.D8[PIDPOSR] = 45; // POSHOLD_RATE_D * 1000; cfg.P8[PIDNAVR] = 14; // NAV_P * 10; cfg.I8[PIDNAVR] = 20; // NAV_I * 100; cfg.D8[PIDNAVR] = 80; // NAV_D * 1000; cfg.P8[PIDLEVEL] = 70; cfg.I8[PIDLEVEL] = 10; cfg.D8[PIDLEVEL] = 20; cfg.P8[PIDMAG] = 40; cfg.P8[PIDVEL] = 0; cfg.I8[PIDVEL] = 0; cfg.D8[PIDVEL] = 0; cfg.rcRate8 = 90; cfg.rcExpo8 = 65; cfg.rollPitchRate = 0; cfg.yawRate = 0; cfg.dynThrPID = 0; cfg.thrMid8 = 50; cfg.thrExpo8 = 0; for (i = 0; i < CHECKBOXITEMS; i++) cfg.activate[i] = 0; cfg.angleTrim[0] = 0; cfg.angleTrim[1] = 0; cfg.accZero[0] = 0; cfg.accZero[1] = 0; cfg.accZero[2] = 0; cfg.mag_declination = 0; // For example, -6deg 37min, = -637 Japan, format is [sign]dddmm (degreesminutes) default is zero. cfg.acc_hardware = ACC_DEFAULT; // default/autodetect cfg.acc_lpf_factor = 4; cfg.acc_lpf_for_velocity = 10; cfg.accz_deadband = 50; cfg.gyro_cmpf_factor = 400; // default MWC cfg.gyro_lpf = 42; cfg.mpu6050_scale = 1; // f**k invensense cfg.baro_tab_size = 21; cfg.baro_noise_lpf = 0.6f; cfg.baro_cf = 0.985f; cfg.gyro_smoothing_factor = 0x00141403; // default factors of 20, 20, 3 for R/P/Y cfg.vbatscale = 110; cfg.vbatmaxcellvoltage = 43; cfg.vbatmincellvoltage = 33; // Radio parseRcChannels("AETR1234"); cfg.deadband = 0; cfg.yawdeadband = 0; cfg.alt_hold_throttle_neutral = 20; cfg.spektrum_hires = 0; cfg.midrc = 1500; cfg.mincheck = 1100; cfg.maxcheck = 1900; cfg.retarded_arm = 0; // disable arm/disarm on roll left/right // Failsafe Variables cfg.failsafe_delay = 10; // 1sec cfg.failsafe_off_delay = 200; // 20sec cfg.failsafe_throttle = 1200; // decent default which should always be below hover throttle for people. // Motor/ESC/Servo cfg.minthrottle = 1150; cfg.maxthrottle = 1850; cfg.mincommand = 1000; cfg.motor_pwm_rate = 400; cfg.servo_pwm_rate = 50; // servos cfg.yaw_direction = 1; cfg.tri_yaw_middle = 1500; cfg.tri_yaw_min = 1020; cfg.tri_yaw_max = 2000; // flying wing cfg.wing_left_min = 1020; cfg.wing_left_mid = 1500; cfg.wing_left_max = 2000; cfg.wing_right_min = 1020; cfg.wing_right_mid = 1500; cfg.wing_right_max = 2000; cfg.pitch_direction_l = 1; cfg.pitch_direction_r = -1; cfg.roll_direction_l = 1; cfg.roll_direction_r = 1; // gimbal cfg.gimbal_pitch_gain = 10; cfg.gimbal_roll_gain = 10; cfg.gimbal_flags = GIMBAL_NORMAL; cfg.gimbal_pitch_min = 1020; cfg.gimbal_pitch_max = 2000; cfg.gimbal_pitch_mid = 1500; cfg.gimbal_roll_min = 1020; cfg.gimbal_roll_max = 2000; cfg.gimbal_roll_mid = 1500; // gps/nav stuff cfg.gps_type = GPS_NMEA; cfg.gps_baudrate = 115200; cfg.gps_wp_radius = 200; cfg.gps_lpf = 20; cfg.nav_slew_rate = 30; cfg.nav_controls_heading = 1; cfg.nav_speed_min = 100; cfg.nav_speed_max = 300; // serial (USART1) baudrate cfg.serial_baudrate = 115200; // custom mixer. clear by defaults. for (i = 0; i < MAX_MOTORS; i++) cfg.customMixer[i].throttle = 0.0f; writeParams(0); }
// Default settings static void resetConf(void) { int i; const int8_t default_align[3][3] = { /* GYRO */ { 0, 0, 0 }, /* ACC */ { 0, 0, 0 }, /* MAG */ { -2, -3, 1 } }; // Clear all configuration memset(&mcfg, 0, sizeof(master_t)); memset(&cfg, 0, sizeof(config_t)); mcfg.version = EEPROM_CONF_VERSION; mcfg.mixerConfiguration = MULTITYPE_QUADX; featureClearAll(); featureSet(FEATURE_VBAT); featureSet(FEATURE_PPM); // global settings mcfg.current_profile = 0; // default profile mcfg.gyro_cmpf_factor = 600; // default MWC mcfg.gyro_cmpfm_factor = 250; // default MWC mcfg.gyro_lpf = 20; // supported by all gyro drivers now. In case of ST gyro, will default to 32Hz instead mcfg.accZero[0] = 0; mcfg.accZero[1] = 0; mcfg.accZero[2] = 0; memcpy(&mcfg.align, default_align, sizeof(mcfg.align)); mcfg.acc_hardware = ACC_DEFAULT; // default/autodetect mcfg.moron_threshold = 32; mcfg.gyro_smoothing_factor = 0x00141403; // default factors of 20, 20, 3 for R/P/Y mcfg.vbatscale = 110; mcfg.vbatmaxcellvoltage = 43; mcfg.vbatmincellvoltage = 33; mcfg.power_adc_channel = 0; mcfg.spektrum_hires = 0; mcfg.midrc = 1500; mcfg.mincheck = 1100; mcfg.maxcheck = 1900; mcfg.retarded_arm = 0; // disable arm/disarm on roll left/right // Motor/ESC/Servo mcfg.minthrottle = 1250; mcfg.maxthrottle = 1850; mcfg.mincommand = 1000; mcfg.motor_pwm_rate = 400; mcfg.servo_pwm_rate = 50; // gps/nav stuff mcfg.gps_type = GPS_NMEA; mcfg.gps_baudrate = 115200; // serial (USART1) baudrate mcfg.serial_baudrate = 115200; mcfg.looptime = 3000; cfg.pidController = 0; cfg.P8[ROLL] = 40; cfg.I8[ROLL] = 30; cfg.D8[ROLL] = 23; cfg.P8[PITCH] = 40; cfg.I8[PITCH] = 30; cfg.D8[PITCH] = 23; cfg.P8[YAW] = 85; cfg.I8[YAW] = 45; cfg.D8[YAW] = 0; cfg.P8[PIDALT] = 64; cfg.I8[PIDALT] = 25; cfg.D8[PIDALT] = 24; cfg.P8[PIDPOS] = 11; // POSHOLD_P * 100; cfg.I8[PIDPOS] = 0; // POSHOLD_I * 100; cfg.D8[PIDPOS] = 0; cfg.P8[PIDPOSR] = 20; // POSHOLD_RATE_P * 10; cfg.I8[PIDPOSR] = 8; // POSHOLD_RATE_I * 100; cfg.D8[PIDPOSR] = 45; // POSHOLD_RATE_D * 1000; cfg.P8[PIDNAVR] = 14; // NAV_P * 10; cfg.I8[PIDNAVR] = 20; // NAV_I * 100; cfg.D8[PIDNAVR] = 80; // NAV_D * 1000; cfg.P8[PIDLEVEL] = 90; cfg.I8[PIDLEVEL] = 10; cfg.D8[PIDLEVEL] = 100; cfg.P8[PIDMAG] = 40; cfg.P8[PIDVEL] = 0; cfg.I8[PIDVEL] = 0; cfg.D8[PIDVEL] = 0; cfg.rcRate8 = 90; cfg.rcExpo8 = 65; cfg.rollPitchRate = 0; cfg.yawRate = 0; cfg.dynThrPID = 0; cfg.thrMid8 = 50; cfg.thrExpo8 = 0; // for (i = 0; i < CHECKBOXITEMS; i++) // cfg.activate[i] = 0; cfg.angleTrim[0] = 0; cfg.angleTrim[1] = 0; cfg.mag_declination = 625; // For example, -6deg 37min, = -637 Japan, format is [sign]dddmm (degreesminutes) default is zero. cfg.acc_lpf_factor = 20; cfg.accz_deadband = 10; cfg.baro_tab_size = 21; cfg.baro_noise_lpf = 0.6f; cfg.baro_cf = 0.985f; // Radio parseRcChannels("AETR1234"); cfg.deadband = 20; cfg.yawdeadband = 20; cfg.alt_hold_throttle_neutral = 40; cfg.alt_hold_fast_change = 1; // Failsafe Variables cfg.failsafe_delay = 10; // 1sec cfg.failsafe_off_delay = 200; // 20sec cfg.failsafe_throttle = 1200; // decent default which should always be below hover throttle for people. cfg.failsafe_detect_threshold = 985; // any of first 4 channels below this value will trigger failsafe // servos cfg.yaw_direction = 1; cfg.tri_yaw_middle = 1500; cfg.tri_yaw_min = 1020; cfg.tri_yaw_max = 2000; // flying wing cfg.wing_left_min = 1020; cfg.wing_left_mid = 1500; cfg.wing_left_max = 2000; cfg.wing_right_min = 1020; cfg.wing_right_mid = 1500; cfg.wing_right_max = 2000; cfg.pitch_direction_l = 1; cfg.pitch_direction_r = -1; cfg.roll_direction_l = 1; cfg.roll_direction_r = 1; // gimbal cfg.gimbal_pitch_gain = 10; cfg.gimbal_roll_gain = 10; cfg.gimbal_flags = GIMBAL_NORMAL; cfg.gimbal_pitch_min = 1020; cfg.gimbal_pitch_max = 2000; cfg.gimbal_pitch_mid = 1500; cfg.gimbal_roll_min = 1020; cfg.gimbal_roll_max = 2000; cfg.gimbal_roll_mid = 1500; // gps/nav stuff cfg.gps_wp_radius = 200; cfg.gps_lpf = 20; cfg.nav_slew_rate = 30; cfg.nav_controls_heading = 1; cfg.nav_speed_min = 100; cfg.nav_speed_max = 300; cfg.ap_mode = 40; // custom mixer. clear by defaults. for (i = 0; i < MAX_MOTORS; i++) mcfg.customMixer[i].throttle = 0.0f; // copy default config into all 3 profiles for (i = 0; i < 3; i++) memcpy(&mcfg.profile[i], &cfg, sizeof(config_t)); }
void targetConfiguration(void) { if (getDetectedMotorType() == MOTOR_BRUSHED) { motorConfigMutable()->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE; motorConfigMutable()->minthrottle = 1050; // for 6mm and 7mm brushed } /* Default to Spektrum */ rxConfigMutable()->serialrx_provider = SERIALRX_SPEKTRUM2048; // all DSM* except DSM2 22ms rxConfigMutable()->spektrum_sat_bind = 5; // DSM2 11ms rxConfigMutable()->spektrum_sat_bind_autoreset = 1; rxConfigMutable()->mincheck = 1025; rxConfigMutable()->rcInterpolation = RC_SMOOTHING_MANUAL; rxConfigMutable()->rcInterpolationInterval = 14; parseRcChannels("TAER1234", rxConfigMutable()); mixerConfigMutable()->yaw_motors_reversed = true; imuConfigMutable()->small_angle = 180; blackboxConfigMutable()->p_ratio = 128; /* Breadboard-specific settings for development purposes only */ #if defined(BREADBOARD) boardAlignmentMutable()->pitchDegrees = 90; // vertical breakout board barometerConfigMutable()->baro_hardware = BARO_DEFAULT; // still testing not on V1 or V2 pcb #else barometerConfigMutable()->baro_hardware = BARO_NONE; #endif compassConfigMutable()->mag_hardware = MAG_NONE; systemConfigMutable()->cpu_overclock = 2; //216MHZ pidConfigMutable()->runaway_takeoff_prevention = false; featureEnable((FEATURE_DYNAMIC_FILTER | FEATURE_AIRMODE | FEATURE_ANTI_GRAVITY) ^ FEATURE_RX_PARALLEL_PWM); /* AlienWhoop PIDs tested with 6mm and 7mm motors on most frames */ for (uint8_t pidProfileIndex = 0; pidProfileIndex < PID_PROFILE_COUNT; pidProfileIndex++) { pidProfile_t *pidProfile = pidProfilesMutable(pidProfileIndex); pidProfile->pidSumLimit = 1000; pidProfile->pidSumLimitYaw = 1000; /* AlienWhoop PIDs tested with 6mm and 7mm motors on most frames */ pidProfile->pid[PID_PITCH].P = 115; pidProfile->pid[PID_PITCH].I = 75; pidProfile->pid[PID_PITCH].D = 95; pidProfile->pid[PID_ROLL].P = 110; pidProfile->pid[PID_ROLL].I = 75; pidProfile->pid[PID_ROLL].D = 85; pidProfile->pid[PID_YAW].P = 220; pidProfile->pid[PID_YAW].I = 75; pidProfile->pid[PID_YAW].D = 20; pidProfile->pid[PID_LEVEL].P = 65; pidProfile->pid[PID_LEVEL].I = 65; pidProfile->pid[PID_LEVEL].D = 55; /* Setpoints */ pidProfile->dterm_filter_type = FILTER_BIQUAD; pidProfile->dterm_notch_hz = 0; pidProfile->pid[PID_PITCH].F = 100; pidProfile->pid[PID_ROLL].F = 100; pidProfile->feedForwardTransition = 0; /* Anti-Gravity */ pidProfile->itermThrottleThreshold = 500; pidProfile->itermAcceleratorGain = 5000; pidProfile->levelAngleLimit = 65; } for (uint8_t rateProfileIndex = 0; rateProfileIndex < CONTROL_RATE_PROFILE_COUNT; rateProfileIndex++) { controlRateConfig_t *controlRateConfig = controlRateProfilesMutable(rateProfileIndex); /* RC Rates */ controlRateConfig->rcRates[FD_ROLL] = 218; controlRateConfig->rcRates[FD_PITCH] = 218; controlRateConfig->rcRates[FD_YAW] = 218; /* Classic Expo */ controlRateConfig->rcExpo[FD_ROLL] = 45; controlRateConfig->rcExpo[FD_PITCH] = 45; controlRateConfig->rcExpo[FD_YAW] = 45; /* Super Expo Rates */ controlRateConfig->rates[FD_ROLL] = 0; controlRateConfig->rates[FD_PITCH] = 0; controlRateConfig->rates[FD_YAW] = 0; /* Throttle PID Attenuation (TPA) */ controlRateConfig->dynThrPID = 0; // tpa_rate off controlRateConfig->tpa_breakpoint = 1600; /* Force the clipping mixer at 100% seems better for brushed than default (off) and scaling)? */ controlRateConfig->throttle_limit_type = THROTTLE_LIMIT_TYPE_CLIP; //controlRateConfig->throttle_limit_percent = 100; controlRateConfig->thrExpo8 = 20; // 20% throttle expo } }
// Default settings static void resetConf(void) { int32_t i; memset(&cfg, 0, sizeof(config_t)); cfg.version = EEPROM_CONF_VERSION; // Default settings cfg.version = EEPROM_CONF_VERSION; cfg.mixerConfiguration = MULTITYPE_QUADX; featureClearAll(); featureSet(FEATURE_VBAT); featureSet(FEATURE_PPM); parseRcChannels("AETR1234"); // Motor/ESC cfg.escPwmRate = 400; cfg.servoPwmRate = 50; // Failsafe cfg.failsafeOnDelay = 50; // Number of command loops (50Hz) until failsafe kicks in cfg.failsafeOffDelay = 20000; // Number of command loops until failsafe stops cfg.failsafeThrottle = 1200; cfg.commandRate = 90; cfg.commandExpo = 65; cfg.rollPitchRate = 0; cfg.yawRate = 0; //cfg.dynThrPID = 0; cfg.throttleMid = 50; cfg.throttleExpo = 0; // Command Settings for(i = 0; i < AUX_OPTIONS; ++i) cfg.auxActivate[i] = 0; cfg.minCommand = 1000; cfg.midCommand = 1500; cfg.maxCommand = 2000; cfg.minCheck = 1100; cfg.maxCheck = 1900; cfg.minThrottle = 1150; cfg.maxThrottle = 1850; cfg.spektrumHiRes = false; cfg.deadBand[ROLL] = 12; cfg.deadBand[PITCH] = 12; cfg.deadBand[YAW] = 12; // Servos // Tricopter cfg.yawDirection = 1; cfg.triYawServoMin = 1000; cfg.triYawServoMid = 1500; cfg.triYawServoMax = 2000; // Bicopter cfg.biLeftServoMin = 1000; cfg.biLeftServoMid = 1500; cfg.biLeftServoMax = 2000; cfg.biRightServoMin = 1000; cfg.biRightServoMid = 1500; cfg.biRightServoMax = 2000; // Flying wing cfg.wingLeftMin = 1020; cfg.wingLeftMid = 1500; cfg.wingLeftMax = 2000; cfg.wingRightMin = 1020; cfg.wingRightMid = 1500; cfg.wingRightMax = 2000; cfg.pitchDirectionLeft = 1; cfg.pitchDirectionRight = -1; cfg.rollDirectionLeft = 1; cfg.rollDirectionRight = 1; cfg.gimbalFlags = GIMBAL_NORMAL; cfg.gimbalSmoothFactor = 0.95f; cfg.gimbalRollServoMin = 1000; cfg.gimbalRollServoMid = 1500; cfg.gimbalRollServoMax = 2000; cfg.gimbalRollServoGain = 1.0f; cfg.gimbalPitchServoMin = 1000; cfg.gimbalPitchServoMid = 1500; cfg.gimbalPitchServoMax = 2000; cfg.gimbalPitchServoGain = 1.0f; // PIDs cfg.pids[ROLL_RATE_PID].p = 100.0f; cfg.pids[ROLL_RATE_PID].i = 0.0f; cfg.pids[ROLL_RATE_PID].d = 0.0f; cfg.pids[ROLL_RATE_PID].iLim = 100.0f; // PWMs cfg.pids[PITCH_RATE_PID].p = 100.0f; cfg.pids[PITCH_RATE_PID].i = 0.0f; cfg.pids[PITCH_RATE_PID].d = 0.0f; cfg.pids[PITCH_RATE_PID].iLim = 100.0f; // PWMs cfg.pids[YAW_RATE_PID].p = 200.0f; cfg.pids[YAW_RATE_PID].i = 0.0f; cfg.pids[YAW_RATE_PID].d = 0.0f; cfg.pids[YAW_RATE_PID].iLim = 100.0f; // PWMs cfg.pids[ROLL_LEVEL_PID].p = 2.0f; cfg.pids[ROLL_LEVEL_PID].i = 0.0f; cfg.pids[ROLL_LEVEL_PID].d = 0.0f; cfg.pids[ROLL_LEVEL_PID].iLim = 0.5f; // radians/sec cfg.pids[PITCH_LEVEL_PID].p = 2.0f; cfg.pids[PITCH_LEVEL_PID].i = 0.0f; cfg.pids[PITCH_LEVEL_PID].d = 0.0f; cfg.pids[PITCH_LEVEL_PID].iLim = 0.5f; // radians/sec cfg.pids[HEADING_PID].p = 1.5f; cfg.pids[HEADING_PID].i = 0.0f; cfg.pids[HEADING_PID].d = 0.0f; cfg.pids[HEADING_PID].iLim = 0.5f; // radians/sec cfg.pids[ALTITUDE_PID].p = 20.0f; cfg.pids[ALTITUDE_PID].i = 17.0f; cfg.pids[ALTITUDE_PID].d = 7.0f; cfg.pids[ALTITUDE_PID].iLim = 30000.0f; // 0.1 m cfg.angleTrim[ROLL] = 0.0f; cfg.angleTrim[PITCH] = 0.0f; cfg.accelLPF = false; cfg.accelSmoothFactor = 0.75f; cfg.accelCalibrated = false; cfg.accelBias[XAXIS] = 0; cfg.accelBias[YAXIS] = 0; cfg.accelBias[ZAXIS] = 0; cfg.gyroBiasOnStartup = false; cfg.gyroSmoothFactor = 0.95f; cfg.gyroTCBiasSlope[ROLL] = 0.0f; cfg.gyroTCBiasSlope[PITCH] = 0.0f; cfg.gyroTCBiasSlope[YAW] = 0.0f; cfg.gyroTCBiasIntercept[ROLL] = 0.0f; cfg.gyroTCBiasIntercept[PITCH] = 0.0f; cfg.gyroTCBiasIntercept[YAW] = 0.0f; cfg.magCalibrated = false; cfg.magBias[ROLL] = 0; cfg.magBias[PITCH] = 0; cfg.magBias[YAW] = 0; cfg.mpu6050Scale = false; // Shitty hack // For Mahony AHRS cfg.accelKp = 2.0f; cfg.accelKi = 0.01f; cfg.magKp = 1.0f; cfg.magKi = 0.01f; cfg.magDriftCompensation = false; // Get your magnetic decliniation from here : http://magnetic-declination.com/ // For example, -6deg 37min, = -6.37 Japan, format is [sign]ddd.mm (degreesminutes) cfg.magDeclination = 10.59f; cfg.batScale = 11.0f; cfg.batMinCellVoltage = 3.3f; cfg.batMaxCellVoltage = 4.2f; cfg.startupDelay = 1000; // custom mixer. clear by defaults. for (i = 0; i < MAX_MOTORS; i++) cfg.customMixer[i].throttle = 0.0f; writeParams(); }
// alternative defaults settings for AlienFlight targets void targetConfiguration(void) { /* depending on revision ... depends on the LEDs to be utilised. */ if (hardwareRevision == AFF3_REV_2) { statusLedConfigMutable()->inversion = 0 #ifdef LED0_A_INVERTED | BIT(0) #endif #ifdef LED1_A_INVERTED | BIT(1) #endif #ifdef LED2_A_INVERTED | BIT(2) #endif ; for (int i = 0; i < STATUS_LED_NUMBER; i++) { statusLedConfigMutable()->ioTags[i] = IO_TAG_NONE; } #ifdef LED0_A statusLedConfigMutable()->ioTags[0] = IO_TAG(LED0_A); #endif #ifdef LED1_A statusLedConfigMutable()->ioTags[1] = IO_TAG(LED1_A); #endif #ifdef LED2_A statusLedConfigMutable()->ioTags[2] = IO_TAG(LED2_A); #endif } else { gyroConfigMutable()->gyro_sync_denom = 2; pidConfigMutable()->pid_process_denom = 2; } if (!haveFrSkyRX) { rxConfigMutable()->serialrx_provider = SERIALRX_SPEKTRUM2048; rxConfigMutable()->spektrum_sat_bind = 5; rxConfigMutable()->spektrum_sat_bind_autoreset = 1; parseRcChannels("TAER1234", rxConfigMutable()); } else { rxConfigMutable()->serialrx_provider = SERIALRX_SBUS; rxConfigMutable()->serialrx_inverted = true; serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIALRX_UART)].functionMask = FUNCTION_TELEMETRY_FRSKY_HUB | FUNCTION_RX_SERIAL; telemetryConfigMutable()->telemetry_inverted = false; featureSet(FEATURE_TELEMETRY); beeperDevConfigMutable()->isOpenDrain = false; beeperDevConfigMutable()->isInverted = true; parseRcChannels("AETR1234", rxConfigMutable()); } if (hardwareMotorType == MOTOR_BRUSHED) { motorConfigMutable()->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE; pidConfigMutable()->pid_process_denom = 1; } for (uint8_t pidProfileIndex = 0; pidProfileIndex < MAX_PROFILE_COUNT; pidProfileIndex++) { pidProfile_t *pidProfile = pidProfilesMutable(pidProfileIndex); pidProfile->pid[PID_ROLL].P = 90; pidProfile->pid[PID_ROLL].I = 44; pidProfile->pid[PID_ROLL].D = 60; pidProfile->pid[PID_PITCH].P = 90; pidProfile->pid[PID_PITCH].I = 44; pidProfile->pid[PID_PITCH].D = 60; } *customMotorMixerMutable(0) = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R *customMotorMixerMutable(1) = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R *customMotorMixerMutable(2) = (motorMixer_t){ 1.0f, 0.414178f, 1.0f, 1.0f }; // REAR_L *customMotorMixerMutable(3) = (motorMixer_t){ 1.0f, 0.414178f, -1.0f, -1.0f }; // FRONT_L *customMotorMixerMutable(4) = (motorMixer_t){ 1.0f, -1.0f, -0.414178f, -1.0f }; // MIDFRONT_R *customMotorMixerMutable(5) = (motorMixer_t){ 1.0f, 1.0f, -0.414178f, 1.0f }; // MIDFRONT_L *customMotorMixerMutable(6) = (motorMixer_t){ 1.0f, -1.0f, 0.414178f, 1.0f }; // MIDREAR_R *customMotorMixerMutable(7) = (motorMixer_t){ 1.0f, 1.0f, 0.414178f, -1.0f }; // MIDREAR_L }
void checkFirstTime(bool eepromReset) { uint8_t test_val; test_val = *(uint8_t *)FLASH_WRITE_EEPROM_ADDR; if (eepromReset || test_val != checkNewEEPROMConf) { // Default settings eepromConfig.version = checkNewEEPROMConf; /////////////////////////////// eepromConfig.accelTCBiasSlope[XAXIS] = 0.0f; eepromConfig.accelTCBiasSlope[YAXIS] = 0.0f; eepromConfig.accelTCBiasSlope[ZAXIS] = 0.0f; /////////////////////////////// eepromConfig.accelTCBiasIntercept[XAXIS] = 0.0f; eepromConfig.accelTCBiasIntercept[YAXIS] = 0.0f; eepromConfig.accelTCBiasIntercept[ZAXIS] = 0.0f; /////////////////////////////// eepromConfig.gyroTCBiasSlope[ROLL ] = 0.0f; eepromConfig.gyroTCBiasSlope[PITCH] = 0.0f; eepromConfig.gyroTCBiasSlope[YAW ] = 0.0f; /////////////////////////////// eepromConfig.gyroTCBiasIntercept[ROLL ] = 0.0f; eepromConfig.gyroTCBiasIntercept[PITCH] = 0.0f; eepromConfig.gyroTCBiasIntercept[YAW ] = 0.0f; /////////////////////////////// eepromConfig.magBias[XAXIS] = 0.0f; eepromConfig.magBias[YAXIS] = 0.0f; eepromConfig.magBias[ZAXIS] = 0.0f; /////////////////////////////// eepromConfig.accelCutoff = 1.0f; /////////////////////////////// eepromConfig.KpAcc = 5.0f; // proportional gain governs rate of convergence to accelerometer eepromConfig.KiAcc = 0.0f; // integral gain governs rate of convergence of gyroscope biases eepromConfig.KpMag = 5.0f; // proportional gain governs rate of convergence to magnetometer eepromConfig.KiMag = 0.0f; // integral gain governs rate of convergence of gyroscope biases /////////////////////////////// eepromConfig.compFilterA = 0.005f; eepromConfig.compFilterB = 0.005f; /////////////////////////////// eepromConfig.dlpfSetting = BITS_DLPF_CFG_98HZ; /////////////////////////////////// eepromConfig.rateScaling = 300.0 / 180000.0 * PI; // Stick to rate scaling for 300 DPS eepromConfig.attitudeScaling = 60.0 / 180000.0 * PI; // Stick to att scaling for 60 degrees eepromConfig.nDotEdotScaling = 0.009f; // Stick to nDot/eDot scaling (9 mps)/(1000 RX PWM Steps) = 0.009 eepromConfig.hDotScaling = 0.003f; // Stick to hDot scaling (3 mps)/(1000 RX PWM Steps) = 0.003 /////////////////////////////// eepromConfig.receiverType = PARALLEL_PWM; eepromConfig.spektrumChannels = 7; eepromConfig.spektrumHires = 0; parseRcChannels("TAER1234"); eepromConfig.escPwmRate = 450; eepromConfig.servoPwmRate = 50; eepromConfig.mixerConfiguration = MIXERTYPE_QUADX; eepromConfig.yawDirection = 1.0f; eepromConfig.midCommand = 3000.0f; eepromConfig.minCheck = (float)(MINCOMMAND + 200); eepromConfig.maxCheck = (float)(MAXCOMMAND - 200); eepromConfig.minThrottle = (float)(MINCOMMAND + 200); eepromConfig.maxThrottle = (float)(MAXCOMMAND); eepromConfig.PID[ROLL_RATE_PID].B = 1.0f; eepromConfig.PID[ROLL_RATE_PID].P = 250.0f; eepromConfig.PID[ROLL_RATE_PID].I = 100.0f; eepromConfig.PID[ROLL_RATE_PID].D = 0.0f; eepromConfig.PID[ROLL_RATE_PID].iTerm = 0.0f; eepromConfig.PID[ROLL_RATE_PID].windupGuard = 100.0f; // PWMs eepromConfig.PID[ROLL_RATE_PID].lastDcalcValue = 0.0f; eepromConfig.PID[ROLL_RATE_PID].lastDterm = 0.0f; eepromConfig.PID[ROLL_RATE_PID].lastLastDterm = 0.0f; eepromConfig.PID[ROLL_RATE_PID].dErrorCalc = D_ERROR; eepromConfig.PID[ROLL_RATE_PID].type = OTHER; eepromConfig.PID[PITCH_RATE_PID].B = 1.0f; eepromConfig.PID[PITCH_RATE_PID].P = 250.0f; eepromConfig.PID[PITCH_RATE_PID].I = 100.0f; eepromConfig.PID[PITCH_RATE_PID].D = 0.0f; eepromConfig.PID[PITCH_RATE_PID].iTerm = 0.0f; eepromConfig.PID[PITCH_RATE_PID].windupGuard = 100.0f; // PWMs eepromConfig.PID[PITCH_RATE_PID].lastDcalcValue = 0.0f; eepromConfig.PID[PITCH_RATE_PID].lastDterm = 0.0f; eepromConfig.PID[PITCH_RATE_PID].lastLastDterm = 0.0f; eepromConfig.PID[PITCH_RATE_PID].dErrorCalc = D_ERROR; eepromConfig.PID[PITCH_RATE_PID].type = OTHER; eepromConfig.PID[YAW_RATE_PID].B = 1.0f; eepromConfig.PID[YAW_RATE_PID].P = 350.0f; eepromConfig.PID[YAW_RATE_PID].I = 100.0f; eepromConfig.PID[YAW_RATE_PID].D = 0.0f; eepromConfig.PID[YAW_RATE_PID].iTerm = 0.0f; eepromConfig.PID[YAW_RATE_PID].windupGuard = 100.0f; // PWMs eepromConfig.PID[YAW_RATE_PID].lastDcalcValue = 0.0f; eepromConfig.PID[YAW_RATE_PID].lastDterm = 0.0f; eepromConfig.PID[YAW_RATE_PID].lastLastDterm = 0.0f; eepromConfig.PID[YAW_RATE_PID].dErrorCalc = D_ERROR; eepromConfig.PID[YAW_RATE_PID].type = OTHER; eepromConfig.PID[ROLL_ATT_PID].B = 1.0f; eepromConfig.PID[ROLL_ATT_PID].P = 2.0f; eepromConfig.PID[ROLL_ATT_PID].I = 0.0f; eepromConfig.PID[ROLL_ATT_PID].D = 0.0f; eepromConfig.PID[ROLL_ATT_PID].iTerm = 0.0f; eepromConfig.PID[ROLL_ATT_PID].windupGuard = 0.5f; // radians/sec eepromConfig.PID[ROLL_ATT_PID].lastDcalcValue = 0.0f; eepromConfig.PID[ROLL_ATT_PID].lastDterm = 0.0f; eepromConfig.PID[ROLL_ATT_PID].lastLastDterm = 0.0f; eepromConfig.PID[ROLL_ATT_PID].dErrorCalc = D_ERROR; eepromConfig.PID[ROLL_ATT_PID].type = ANGULAR; eepromConfig.PID[PITCH_ATT_PID].B = 1.0f; eepromConfig.PID[PITCH_ATT_PID].P = 2.0f; eepromConfig.PID[PITCH_ATT_PID].I = 0.0f; eepromConfig.PID[PITCH_ATT_PID].D = 0.0f; eepromConfig.PID[PITCH_ATT_PID].iTerm = 0.0f; eepromConfig.PID[PITCH_ATT_PID].windupGuard = 0.5f; // radians/sec eepromConfig.PID[PITCH_ATT_PID].lastDcalcValue = 0.0f; eepromConfig.PID[PITCH_ATT_PID].lastDterm = 0.0f; eepromConfig.PID[PITCH_ATT_PID].lastLastDterm = 0.0f; eepromConfig.PID[PITCH_ATT_PID].dErrorCalc = D_ERROR; eepromConfig.PID[PITCH_ATT_PID].type = ANGULAR; eepromConfig.PID[HEADING_PID].B = 1.0f; eepromConfig.PID[HEADING_PID].P = 3.0f; eepromConfig.PID[HEADING_PID].I = 0.0f; eepromConfig.PID[HEADING_PID].D = 0.0f; eepromConfig.PID[HEADING_PID].iTerm = 0.0f; eepromConfig.PID[HEADING_PID].windupGuard = 0.5f; // radians/sec eepromConfig.PID[HEADING_PID].lastDcalcValue = 0.0f; eepromConfig.PID[HEADING_PID].lastDterm = 0.0f; eepromConfig.PID[HEADING_PID].lastLastDterm = 0.0f; eepromConfig.PID[HEADING_PID].dErrorCalc = D_ERROR; eepromConfig.PID[HEADING_PID].type = ANGULAR; eepromConfig.PID[NDOT_PID].B = 1.0f; eepromConfig.PID[NDOT_PID].P = 3.0f; eepromConfig.PID[NDOT_PID].I = 0.0f; eepromConfig.PID[NDOT_PID].D = 0.0f; eepromConfig.PID[NDOT_PID].iTerm = 0.0f; eepromConfig.PID[NDOT_PID].windupGuard = 0.5f; eepromConfig.PID[NDOT_PID].lastDcalcValue = 0.0f; eepromConfig.PID[NDOT_PID].lastDterm = 0.0f; eepromConfig.PID[NDOT_PID].lastLastDterm = 0.0f; eepromConfig.PID[NDOT_PID].dErrorCalc = D_ERROR; eepromConfig.PID[NDOT_PID].type = OTHER; eepromConfig.PID[EDOT_PID].B = 1.0f; eepromConfig.PID[EDOT_PID].P = 3.0f; eepromConfig.PID[EDOT_PID].I = 0.0f; eepromConfig.PID[EDOT_PID].D = 0.0f; eepromConfig.PID[EDOT_PID].iTerm = 0.0f; eepromConfig.PID[EDOT_PID].windupGuard = 0.5f; eepromConfig.PID[EDOT_PID].lastDcalcValue = 0.0f; eepromConfig.PID[EDOT_PID].lastDterm = 0.0f; eepromConfig.PID[EDOT_PID].lastLastDterm = 0.0f; eepromConfig.PID[EDOT_PID].dErrorCalc = D_ERROR; eepromConfig.PID[EDOT_PID].type = OTHER; eepromConfig.PID[HDOT_PID].B = 1.0f; eepromConfig.PID[HDOT_PID].P = 2.0f; eepromConfig.PID[HDOT_PID].I = 0.0f; eepromConfig.PID[HDOT_PID].D = 0.0f; eepromConfig.PID[HDOT_PID].iTerm = 0.0f; eepromConfig.PID[HDOT_PID].windupGuard = 5.0f; eepromConfig.PID[HDOT_PID].lastDcalcValue = 0.0f; eepromConfig.PID[HDOT_PID].lastDterm = 0.0f; eepromConfig.PID[HDOT_PID].lastLastDterm = 0.0f; eepromConfig.PID[HDOT_PID].dErrorCalc = D_ERROR; eepromConfig.PID[HDOT_PID].type = OTHER; eepromConfig.PID[N_PID].B = 1.0f; eepromConfig.PID[N_PID].P = 3.0f; eepromConfig.PID[N_PID].I = 0.0f; eepromConfig.PID[N_PID].D = 0.0f; eepromConfig.PID[N_PID].iTerm = 0.0f; eepromConfig.PID[N_PID].windupGuard = 0.5f; eepromConfig.PID[N_PID].lastDcalcValue = 0.0f; eepromConfig.PID[N_PID].lastDterm = 0.0f; eepromConfig.PID[N_PID].lastLastDterm = 0.0f; eepromConfig.PID[N_PID].dErrorCalc = D_ERROR; eepromConfig.PID[N_PID].type = OTHER; eepromConfig.PID[E_PID].B = 1.0f; eepromConfig.PID[E_PID].P = 3.0f; eepromConfig.PID[E_PID].I = 0.0f; eepromConfig.PID[E_PID].D = 0.0f; eepromConfig.PID[E_PID].iTerm = 0.0f; eepromConfig.PID[E_PID].windupGuard = 0.5f; eepromConfig.PID[E_PID].lastDcalcValue = 0.0f; eepromConfig.PID[E_PID].lastDterm = 0.0f; eepromConfig.PID[E_PID].lastLastDterm = 0.0f; eepromConfig.PID[E_PID].dErrorCalc = D_ERROR; eepromConfig.PID[E_PID].type = OTHER; eepromConfig.PID[H_PID].B = 1.0f; eepromConfig.PID[H_PID].P = 2.0f; eepromConfig.PID[H_PID].I = 0.0f; eepromConfig.PID[H_PID].D = 0.0f; eepromConfig.PID[H_PID].iTerm = 0.0f; eepromConfig.PID[H_PID].windupGuard = 5.0f; eepromConfig.PID[H_PID].lastDcalcValue = 0.0f; eepromConfig.PID[H_PID].lastDterm = 0.0f; eepromConfig.PID[H_PID].lastLastDterm = 0.0f; eepromConfig.PID[H_PID].dErrorCalc = D_ERROR; eepromConfig.PID[H_PID].type = OTHER; eepromConfig.gimbalRollServoMin = 2000.0f; eepromConfig.gimbalRollServoMid = 3000.0f; eepromConfig.gimbalRollServoMax = 4000.0f; eepromConfig.gimbalRollServoGain = 1.0f; eepromConfig.gimbalPitchServoMin = 2000.0f; eepromConfig.gimbalPitchServoMid = 3000.0f; eepromConfig.gimbalPitchServoMax = 4000.0f; eepromConfig.gimbalPitchServoGain = 1.0f; eepromConfig.rollDirectionLeft = -1.0f; eepromConfig.rollDirectionRight = 1.0f; eepromConfig.pitchDirectionLeft = -1.0f; eepromConfig.pitchDirectionRight = 1.0f; eepromConfig.wingLeftMinimum = 2000.0f; eepromConfig.wingLeftMaximum = 4000.0f; eepromConfig.wingRightMinimum = 2000.0f; eepromConfig.wingRightMaximum = 4000.0f; eepromConfig.biLeftServoMin = 2000.0f; eepromConfig.biLeftServoMid = 3000.0f; eepromConfig.biLeftServoMax = 4000.0f; eepromConfig.biRightServoMin = 2000.0f; eepromConfig.biRightServoMid = 3000.0f; eepromConfig.biRightServoMax = 4000.0f; eepromConfig.triYawServoMin = 2000.0f; eepromConfig.triYawServoMid = 3000.0f; eepromConfig.triYawServoMax = 4000.0f; eepromConfig.vTailAngle = 40.0f; // Free Mix Defaults to Quad X eepromConfig.freeMixMotors = 4; eepromConfig.freeMix[0][ROLL ] = 1.0f; eepromConfig.freeMix[0][PITCH] = -1.0f; eepromConfig.freeMix[0][YAW ] = -1.0f; eepromConfig.freeMix[1][ROLL ] = -1.0f; eepromConfig.freeMix[1][PITCH] = -1.0f; eepromConfig.freeMix[1][YAW ] = 1.0f; eepromConfig.freeMix[2][ROLL ] = -1.0f; eepromConfig.freeMix[2][PITCH] = 1.0f; eepromConfig.freeMix[2][YAW ] = -1.0f; eepromConfig.freeMix[3][ROLL ] = 1.0f; eepromConfig.freeMix[3][PITCH] = 1.0f; eepromConfig.freeMix[3][YAW ] = 1.0f; eepromConfig.freeMix[4][ROLL ] = 0.0f; eepromConfig.freeMix[4][PITCH] = 0.0f; eepromConfig.freeMix[4][YAW ] = 0.0f; eepromConfig.freeMix[5][ROLL ] = 0.0f; eepromConfig.freeMix[5][PITCH] = 0.0f; eepromConfig.freeMix[5][YAW ] = 0.0f; eepromConfig.osdEnabled = false; eepromConfig.defaultVideoStandard = NTSC; eepromConfig.metricUnits = false; eepromConfig.osdDisplayAlt = true; eepromConfig.osdDisplayAH = true; eepromConfig.osdDisplayAtt = false; eepromConfig.osdDisplayHdg = true; eepromConfig.gpsType = NO_GPS; eepromConfig.gpsBaudRate = 38400; eepromConfig.magVar = 9.033333f * D2R; // Albuquerque, NM Mag Var 9 degrees 2 minutes (+East, - West) eepromConfig.batteryVoltageDivider = (10.0f + 1.5f) / 1.5f; eepromConfig.armCount = 50; eepromConfig.disarmCount = 0; writeEEPROM(); } }
// Default settings STATIC_UNIT_TESTED void resetConf(void) { pgResetAll(MAX_PROFILE_COUNT); setProfile(0); pgActivateProfile(0); setControlRateProfile(0); parseRcChannels("AETR1234", rxConfig()); featureClearAll(); featureSet(DEFAULT_RX_FEATURE | FEATURE_FAILSAFE | FEATURE_BLACKBOX); #ifdef DEFAULT_FEATURES featureSet(DEFAULT_FEATURES); #endif #ifdef BOARD_HAS_VOLTAGE_DIVIDER // only enable the feature by default if the board has supporting hardware featureSet(FEATURE_VBAT); #endif #ifdef BOARD_HAS_AMPERAGE_METER // only enable the feature by default if the board has supporting hardware featureSet(FEATURE_AMPERAGE_METER); batteryConfig()->amperageMeterSource = AMPERAGE_METER_ADC; #endif // alternative defaults settings for ALIENFLIGHTF1 and ALIENFLIGHTF3 targets #ifdef ALIENFLIGHT #ifdef ALIENFLIGHTF3 serialConfig()->portConfigs[2].functionMask = FUNCTION_RX_SERIAL; getVoltageMeterConfig(ADC_BATTERY)->vbatscale = 20; sensorSelectionConfig()->mag_hardware = MAG_NONE; // disabled by default # else serialConfig()->portConfigs[1].functionMask = FUNCTION_RX_SERIAL; # endif rxConfig()->serialrx_provider = SERIALRX_SPEKTRUM2048; rxConfig()->spektrum_sat_bind = 5; motorConfig()->minthrottle = 1000; motorConfig()->maxthrottle = 2000; motorConfig()->motor_pwm_rate = 32000; failsafeConfig()->failsafe_delay = 2; failsafeConfig()->failsafe_off_delay = 0; mixerConfig()->yaw_jump_prevention_limit = YAW_JUMP_PREVENTION_LIMIT_HIGH; currentControlRateProfile->rcRate8 = 100; currentControlRateProfile->rates[PITCH] = 20; currentControlRateProfile->rates[ROLL] = 20; currentControlRateProfile->rates[YAW] = 20; parseRcChannels("TAER1234", rxConfig()); *customMotorMixer(0) = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R *customMotorMixer(1) = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R *customMotorMixer(2) = (motorMixer_t){ 1.0f, 0.414178f, 1.0f, 1.0f }; // REAR_L *customMotorMixer(3) = (motorMixer_t){ 1.0f, 0.414178f, -1.0f, -1.0f }; // FRONT_L *customMotorMixer(4) = (motorMixer_t){ 1.0f, -1.0f, -0.414178f, -1.0f }; // MIDFRONT_R *customMotorMixer(5) = (motorMixer_t){ 1.0f, 1.0f, -0.414178f, 1.0f }; // MIDFRONT_L *customMotorMixer(6) = (motorMixer_t){ 1.0f, -1.0f, 0.414178f, 1.0f }; // MIDREAR_R *customMotorMixer(7) = (motorMixer_t){ 1.0f, 1.0f, 0.414178f, -1.0f }; // MIDREAR_L #endif // copy first profile into remaining profile PG_FOREACH_PROFILE(reg) { for (int i = 1; i < MAX_PROFILE_COUNT; i++) { memcpy(reg->address + i * pgSize(reg), reg->address, pgSize(reg)); } } for (int i = 1; i < MAX_PROFILE_COUNT; i++) { configureRateProfileSelection(i, i % MAX_CONTROL_RATE_PROFILE_COUNT); } }
// Default settings STATIC_UNIT_TESTED void resetConf(void) { pgResetAll(MAX_PROFILE_COUNT); setProfile(0); pgActivateProfile(0); setControlRateProfile(0); featureClearAll(); featureSet(DEFAULT_RX_FEATURE); #ifdef BOARD_HAS_VOLTAGE_DIVIDER // only enable the VBAT feature by default if the board has a voltage divider otherwise // the user may see incorrect readings and unexpected issues with pin mappings may occur. featureSet(FEATURE_VBAT); #endif featureSet(FEATURE_FAILSAFE); parseRcChannels("AETR1234", rxConfig()); featureSet(FEATURE_BLACKBOX); #if defined(COLIBRI_RACE) // alternative defaults settings for COLIBRI RACE targets imuConfig()->looptime = 1000; featureSet(FEATURE_ONESHOT125); featureSet(FEATURE_LED_STRIP); #endif #ifdef SPRACINGF3EVO featureSet(FEATURE_TRANSPONDER); featureSet(FEATURE_RSSI_ADC); featureSet(FEATURE_CURRENT_METER); featureSet(FEATURE_TELEMETRY); #endif // alternative defaults settings for ALIENWIIF1 and ALIENWIIF3 targets #ifdef ALIENWII32 featureSet(FEATURE_RX_SERIAL); featureSet(FEATURE_MOTOR_STOP); # ifdef ALIENWIIF3 serialConfig()->portConfigs[2].functionMask = FUNCTION_RX_SERIAL; batteryConfig()->vbatscale = 20; # else serialConfig()->portConfigs[1].functionMask = FUNCTION_RX_SERIAL; # endif rxConfig()->serialrx_provider = SERIALRX_SPEKTRUM2048; rxConfig()->spektrum_sat_bind = 5; motorAndServoConfig()->minthrottle = 1000; motorAndServoConfig()->maxthrottle = 2000; motorAndServoConfig()->motor_pwm_rate = 32000; imuConfig()->looptime = 2000; pidProfile()->pidController = 3; pidProfile()->P8[PIDROLL] = 36; pidProfile()->P8[PIDPITCH] = 36; failsafeConfig()->failsafe_delay = 2; failsafeConfig()->failsafe_off_delay = 0; currentControlRateProfile->rcRate8 = 130; currentControlRateProfile->rates[ROLL] = 20; currentControlRateProfile->rates[PITCH] = 20; currentControlRateProfile->rates[YAW] = 100; parseRcChannels("TAER1234", rxConfig()); *customMotorMixer(0) = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R *customMotorMixer(1) = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R *customMotorMixer(2) = (motorMixer_t){ 1.0f, 0.414178f, 1.0f, 1.0f }; // REAR_L *customMotorMixer(3) = (motorMixer_t){ 1.0f, 0.414178f, -1.0f, -1.0f }; // FRONT_L *customMotorMixer(4) = (motorMixer_t){ 1.0f, -1.0f, -0.414178f, -1.0f }; // MIDFRONT_R *customMotorMixer(5) = (motorMixer_t){ 1.0f, 1.0f, -0.414178f, 1.0f }; // MIDFRONT_L *customMotorMixer(6) = (motorMixer_t){ 1.0f, -1.0f, 0.414178f, 1.0f }; // MIDREAR_R *customMotorMixer(7) = (motorMixer_t){ 1.0f, 1.0f, 0.414178f, -1.0f }; // MIDREAR_L #endif // copy first profile into remaining profile PG_FOREACH_PROFILE(reg) { for (int i = 1; i < MAX_PROFILE_COUNT; i++) { memcpy(reg->address + i * pgSize(reg), reg->address, pgSize(reg)); } } for (int i = 1; i < MAX_PROFILE_COUNT; i++) { configureRateProfileSelection(i, i % MAX_CONTROL_RATE_PROFILE_COUNT); } }
// Default settings static void resetConf(void) { uint8_t i; const int8_t default_align[3][3] = { /* GYRO */ { 0, 0, 0 }, /* ACC */ { 0, 0, 0 }, /* MAG */ { -2, -3, 1 } }; memset(&cfg, 0, sizeof(config_t)); cfg.version = EEPROM_CONF_VERSION; cfg.mixerConfiguration = MULTITYPE_QUADX; featureClearAll(); // featureSet(FEATURE_VBAT); featureSet(FEATURE_PPM); // featureSet(FEATURE_FAILSAFE); // featureSet(FEATURE_LCD); // featureSet(FEATURE_GPS); // featureSet(FEATURE_PASS); // Just pass Throttlechannel // featureSet(FEATURE_SONAR); cfg.P8[ROLL] = 35; // 40 cfg.I8[ROLL] = 20; cfg.D8[ROLL] = 30; cfg.P8[PITCH] = 35; // 40 cfg.I8[PITCH] = 20; cfg.D8[PITCH] = 30; cfg.P8[YAW] = 60; // 70 cfg.I8[YAW] = 45; cfg.P8[PIDALT] = 100; cfg.I8[PIDALT] = 30; cfg.D8[PIDALT] = 80; cfg.P8[PIDPOS] = 10; // FIND YOUR VALUE cfg.I8[PIDPOS] = 0; // NOT USED cfg.D8[PIDPOS] = 0; // NOT USED cfg.P8[PIDPOSR] = 50; // FIND YOUR VALUE // Controls the speed part with my PH logic cfg.I8[PIDPOSR] = 0; // 25; // DANGER "I" may lead to circeling // Controls the speed part with my PH logic cfg.D8[PIDPOSR] = 40; // FIND YOUR VALUE // Controls the speed part with my PH logic cfg.P8[PIDNAVR] = 15; // 14 More ? cfg.I8[PIDNAVR] = 0; // NAV_I * 100; // Scaling/Purpose unchanged cfg.D8[PIDNAVR] = 0; // NAV_D * 1000; // Scaling/Purpose unchanged // cfg.P8[PIDPOS] = 11; // APM PH Stock values // cfg.I8[PIDPOS] = 0; // cfg.D8[PIDPOS] = 0; // cfg.P8[PIDPOSR] = 20; // POSHOLD_RATE_P * 10; // cfg.I8[PIDPOSR] = 8; // POSHOLD_RATE_I * 100; // cfg.D8[PIDPOSR] = 45; // POSHOLD_RATE_D * 1000; // cfg.P8[PIDNAVR] = 14; // NAV_P * 10; // cfg.I8[PIDNAVR] = 20; // NAV_I * 100; // cfg.D8[PIDNAVR] = 80; // NAV_D * 1000; cfg.P8[PIDLEVEL] = 60; // 70 cfg.I8[PIDLEVEL] = 10; cfg.D8[PIDLEVEL] = 50; cfg.P8[PIDMAG] = 80; // cfg.P8[PIDVEL] = 0;// cfg.I8[PIDVEL] = 0;// cfg.D8[PIDVEL] = 0; cfg.rcRate8 = 100; cfg.rcExpo8 = 80; // cfg.rollPitchRate = 0;// cfg.yawRate = 0;// cfg.dynThrPID = 0; cfg.thrMid8 = 50; // cfg.thrExpo8 = 0;//for (i = 0; i < CHECKBOXITEMS; i++)//cfg.activate[i] = 0; // cfg.angleTrim[0] = 0;// cfg.angleTrim[1] = 0;// cfg.accZero[0] = 0;// cfg.accZero[1] = 0; // cfg.accZero[2] = 0;// cfg.mag_declination = 0; // For example, -6deg 37min, = -637 Japan, format is [sign]dddmm (degreesminutes) default is zero. memcpy(&cfg.align, default_align, sizeof(cfg.align)); // cfg.mag_declination = 0; // For example, -6deg 37min, = -637 Japan, format is [sign]dddmm (degreesminutes) default is zero. cfg.mag_declination = 107; // Crashpilot //cfg.acc_hardware = ACC_DEFAULT;// default/autodetect cfg.mag_oldcalib = 0; // 1 = old hard iron calibration // 0 = extended calibration (better) cfg.mag_oldctime = 1; // 1 - 5 Time in MINUTES for old calibration. Use this together with mag_oldcalib = 1 if you have a monster of a copter cfg.acc_hardware = 2; // Crashpilot MPU6050 cfg.acc_lpf_factor = 100; // changed 27.11.2012 cfg.acc_ins_lpf = 10; // General LPF for all INS stuff cfg.looptime = 3000; // changed 27.11.2012 // cfg.acc_lpf_factor = 4; cfg.mainpidctrl = 1; // 1 = OriginalMwiiPid pimped by me, 2 = New mwii controller (experimental, float pimped + pt1) cfg.mainpt1cut = 15; // (0-50Hz) 0 Disables pt1element. Cuf Off Frequency for pt1 element D term in Hz of main Pid controller cfg.newpidimax = 256; // [10-65000) 256 Default. Imax of new Pidcontroller cfg.gpspt1cut = 10; // (1-50Hz) Cuf Off Frequency for D term in Hz of GPS Pid controller cfg.gyro_cmpf_factor = 1000; // (10-1000) 400 default. Now 1000. The higher, the more weight gets the gyro and the lower is the correction with Acc data. cfg.gyro_cmpfm_factor = 1000; // (10-2000) 200 default for 10Hz. Now 1000 for 70Hz seems ok. Gyro/Magnetometer Complement. Greater Value means more filter on mag/delay cfg.gyro_lpf = 42; // Possible values 256 188 98 42 20 10 (HZ) // Baro cfg.accz_vel_cf = 0.985f; // Crashpilot: Value for complementary filter accz and barovelocity cfg.accz_alt_cf = 0.940f; // Crashpilot: Value for complementary filter accz and altitude cfg.baro_lag = 0.3f; // Lag of Baro/Althold stuff in general, makes stop in hightchange snappier cfg.barodownscale = 0.7f; // Scale downmovement down (because copter drops faster than rising) // Autoland cfg.al_barolr = 75; // Temporary value "64" increase to increase Landingspeed cfg.al_snrlr = 75; // You can specify different landingfactor here on sonar contact, because sonar land maybe too fast when snr_cf is high cfg.al_lndthr = 0; // This is the absolute throttle that kicks off the "has landed timer" if it is too low cfg.minthrottle is taken. cfg.al_debounce = 5; // (0-20%) 0 Disables. Defines a Throttlelimiter on Autoland. Percentage defines the maximum deviation of assumed hoverthrottle during Autoland cfg.al_tobaro = 2000; // Timeout in ms (100 - 5000) before shutoff on autoland. "al_lndthr" must be undershot for that timeperiod cfg.al_tosnr = 1000; // Timeout in ms (100 - 5000) If sonar aided land is wanted (snr_land = 1) you can choose a different timeout here cfg.baro_debug = 0; // Crashpilot: 1 = Debug Barovalues //cfg.baro_noise_lpf = 0.6f;// Crashpilot: Not used anymore//cfg.baro_cf = 0.985f;// Crashpilot: Not used anymore cfg.moron_threshold = 32; cfg.gyro_smoothing_factor = 0x00141403; // default factors of 20, 20, 3 for R/P/Y cfg.vbatscale = 110; cfg.vbatmaxcellvoltage = 43; cfg.vbatmincellvoltage = 33; cfg.power_adc_channel = 0; // Radio parseRcChannels("AETR1234"); cfg.deadband = 15; // Crashpilot: A little deadband will not harm our crappy RC cfg.yawdeadband = 15; // Crashpilot: A little deadband will not harm our crappy RC cfg.alt_hold_throttle_neutral = 50; // Crashpilot: A little deadband will not harm our crappy RC cfg.gps_adddb = 5; // Additional Deadband for all GPS functions; // cfg.spektrum_hires = 0; cfg.midrc = 1500; cfg.mincheck = 1100; cfg.maxcheck = 1900; cfg.retarded_arm = 0; // disable arm/disarm on roll left/right cfg.auxChannels = 4; // [4 - 10] cGiesen: Default = 4, then like the standard! cfg.killswitchtime = 0; // Time in ms when your arm switch becomes a Killswitch, 0 disables the Killswitch, can not be used together with FEATURE_INFLIGHT_ACC_CAL // Motor/ESC/Servo cfg.minthrottle = 1150; // ORIG // cfg.minthrottle = 1100; cfg.maxthrottle = 1950; cfg.passmotor = 0; // Crashpilot: Only used with feature pass. If 0 = all Motors, otherwise specific Motor cfg.mincommand = 1000; cfg.motor_pwm_rate = 400; cfg.servo_pwm_rate = 50; // servos cfg.yaw_direction = 1; cfg.tri_yaw_middle = 1500; cfg.tri_yaw_min = 1020; cfg.tri_yaw_max = 2000; // flying wing cfg.wing_left_min = 1020; cfg.wing_left_mid = 1500; cfg.wing_left_max = 2000; cfg.wing_right_min = 1020; cfg.wing_right_mid = 1500; cfg.wing_right_max = 2000; cfg.pitch_direction_l = 1; cfg.pitch_direction_r = -1; cfg.roll_direction_l = 1; cfg.roll_direction_r = 1; // gimbal cfg.gimbal_pitch_gain = 10; cfg.gimbal_roll_gain = 10; cfg.gimbal_flags = GIMBAL_NORMAL; cfg.gimbal_pitch_min = 1020; cfg.gimbal_pitch_max = 2000; cfg.gimbal_pitch_mid = 1500; cfg.gimbal_roll_min = 1020; cfg.gimbal_roll_max = 2000; cfg.gimbal_roll_mid = 1500; // gps/nav cfg.gps_type = 1; // GPS_NMEA = 0, GPS_UBLOX = 1, GPS_MTK16 = 2, GPS_MTK19 = 3, GPS_UBLOX_DUMB = 4 cfg.gps_baudrate = 115200; //38400; // Changed 8/6/13 to 115200; // cfg.gps_baudrate = 38400; //38400; // Changed 8/6/13 to 115200; // cfg.gps_ins_vel = 0.72f; // Crashpilot GPS INS The LOWER the value the closer to gps speed // Dont go to high here cfg.gps_ins_vel = 0.6f; // Crashpilot GPS INS The LOWER the value the closer to gps speed // Dont go to high here cfg.gps_ins_mdl = 1; // NOTE: KEEP THIS TO "1" FOR NOW because other models work like shit currently. GPS ins model. 1 = Based on lat/lon, 2 = based on Groundcourse & speed,(3 = based on ublx velned deleted) cfg.gps_lag = 2000; // GPS Lag in ms cfg.gps_phase = 0; // +- 30 Degree Make a phaseshift of GPS output for whatever reason you might want that (frametype etc) cfg.gps_ph_minsat = 6; // Minimal Satcount for PH, PH on RTL is still done with 5Sats or more cfg.gps_ph_settlespeed = 10; // 1 - 200 cm/s PH settlespeed in cm/s cfg.gps_ph_brakemaxangle = 10; // 1 - 45 Degree Maximal 5 Degree Overspeedbrake cfg.gps_ph_minbrakepercent = 50; // 1 - 99% minimal percent of "brakemaxangle" left over for braking. Example brakemaxangle = 6 so 50 Percent is 3.. cfg.gps_ph_brkacc = 40; // [1 - 500] Is the assumed negative braking acceleration in cm/(s*s) of copter. Value is positive though. It will be a timeout. The lower the Value the longe the Timeout cfg.gps_ph_abstub = 100; // 0 - 1000cm (300 Dfault, 0 disables) Defines the "bath tub" around current absolute PH Position, where PosP is diminished, reaction gets harder on tubs edge and then goes on linear cfg.gps_maxangle = 25; // 10 - 45 Degree Maximal over all GPS bank angle cfg.gps_wp_radius = 150; // cfg.gps_rtl_minhight = 20; // (0 - 200) Minimal RTL hight in m, 0 disables feature cfg.gps_rtl_minhight = 0; // (0 - 200) Minimal RTL hight in m, 0 disables feature cfg.gps_rtl_mindist = 0; // 0 Disables. Minimal distance for RTL in m, otherwise it will just autoland, prevent Failsafe jump in your face, when arming copter and turning off TX cfg.gps_rtl_flyaway = 0; // 0 Disables. If during RTL the distance increases beyond this value (in meters relative to RTL activation point), something is wrong, autoland cfg.gps_yaw = 30; // Thats the MAG P during GPS functions, substitute for "cfg.P8[PIDMAG]" cfg.nav_rtl_lastturn = 1; // 1 = when copter gets to home position it rotates it's head to takeoff direction independend of nav_controls_heading // cfg.nav_slew_rate = 30; // was 30 and 50 before cfg.nav_slew_rate = 20; // was 30 and 50 before cfg.nav_tail_first = 0; // 1 = Copter comes back with ass first (only works with nav_controls_heading = 1) cfg.nav_controls_heading = 0; // 1 = Nav controls YAW during WP ONLY // cfg.nav_controls_heading = 1; // 1 = Nav controls YAW during WP ONLY cfg.nav_speed_min = 100; // 10 - 200 cm/s don't set higher than nav_speed_max! That dumbness is not covered. cfg.nav_speed_max = 350; // 50 - 2000 cm/s don't set lower than nav_speed_min! That dumbness is not covered. cfg.nav_approachdiv = 3; // 2 - 10 This is the divisor for approach speed for wp_distance. Example: 400cm / 3 = 133cm/s if below nav_speed_min it will be adjusted cfg.nav_tiltcomp = 20; // 0 - 100 (20 TestDefault) Only arducopter really knows. Dfault was 54. This is some kind of a hack of them to reach actual nav_speed_max. 54 was Dfault, 0 disables cfg.nav_ctrkgain = 0.5f; // 0 - 10.0 (0.5 TestDefault) (Floatvariable) That is the "Crosstrackgain" APM Dfault is "1". "0" disables // Failsafe Variables cfg.failsafe_delay = 10; // in 0.1s (10 = 1sec) cfg.failsafe_off_delay = 200; // in 0.1s (200 = 20sec) cfg.failsafe_throttle = 1200; // decent Dfault which should always be below hover throttle for people. cfg.failsafe_deadpilot = 0; // DONT USE, EXPERIMENTAL Time in sec when FS is engaged after idle on THR/YAW/ROLL/PITCH, 0 disables max 250 cfg.failsafe_justph = 0; // Does just PH&Autoland an not RTL, use this in difficult areas with many obstacles to avoid RTL crash into something cfg.failsafe_ignoreSNR = 1; // When snr_land is set to 1, it is possible to ignore that on Failsafe, because FS over a tree could turn off copter // serial (USART1) baudrate cfg.serial_baudrate = 115200; cfg.tele_prot = 0; // Protocol ONLY used when Armed including Baudchange if necessary. 0 (Dfault)=Keep Multiwii @CurrentUSB Baud, 1=Frsky @9600Baud, 2=Mavlink @CurrentUSB Baud, 3=Mavlink @57KBaud (like stock minimOSD wants it) // LED Stuff cfg.LED_invert = 0; // Crashpilot: Inversion of LED 0&1 Partly implemented because Bootup is not affected cfg.LED_Type = 1; // 1=MWCRGB / 2=MONO_LED / 3=LEDRing cfg.LED_Pinout = 1; // rc6 cfg.LED_ControlChannel = 8; // AUX4 (Channel 8) cfg.LED_Armed = 0; // 0 = Show LED only if armed, 1 = always show LED cfg.LED_Pattern1 = 1300; // 32bit bit pattern to have flickering led patterns / the pattern for MWCRGB 1000-2000 cfg.LED_Pattern2 = 1800; // 32bit bit pattern to have flickering led patterns / the pattern for MWCRGB 1000-2000 cfg.LED_Pattern3 = 1900; // 32bit bit pattern to have flickering led patterns / the pattern for MWCRGB 1000-2000 cfg.LED_Toggle_Delay1 = 0x08; // slow down LED_Pattern cfg.LED_Toggle_Delay2 = 0x08; // slow down LED_Pattern cfg.LED_Toggle_Delay3 = 0x08; // slow down LED_Pattern // SONAR // SOME INFO ON SONAR: // PWM56 are 5V resistant, RC78 only tolerate 3.3V(!!) so add a 1K Ohms resistor!!! // Note: You will never see the maximum possible sonar range in a copter, so go for the half of it (or less?) // // Connection possibilities depending on Receivertype: // PPSUM: RC78 possible, PWM56 possible (on max. quadcopters, see below) // Normal RX: Just Connection on Motorchannel 5&6 (PWM56) is possible. // The PWM56 sonar connection option is only available in setups with max motors 4, otherwise sonar is not initialized. // // HC-SR04: // Operation Voltage: 5V (!! Use PWM56 or 1K resistor !!) // Range: 2cm - 400cm // Angle: 15 Degrees (Test out for yourself: cfg.snr_tilt = X) // // Maxbotics in general // Operation Voltage: (some 2.5V)3.3V - 5V ((!! Use PWM56 or resistor with 5V !!) // Only wire the Maxbotics for PWM output (more precise anyway), not the analog etc. modes, just wire echopin (normally pin 2) // Range: 20cm(!) - 765cm (some >1000cm), MaxTiltAngle is not specified, depending on Model // Tested on MB1200 XL-MaxSonar-EZ0 // // GENERAL WARNING: DON'T SET snr_min TOO LOW, OTHERWISE THE WRONG SONARVALUE WILL BE TAKEN AS REAL MEASUREMENT!! // I implemented some checks to prevent that user error, but still keep that in mind. // Min/Max are checked and changed if they are too stupid for your sonar. So if you suddenly see other values, thats not an eeprom error or so. // MAXBOTICS: SET snr_min to at least 25! I check this in sensors and change the value, if needed. // NOTE: I limited Maxbotics to 7 meters in the code, knowing that some types will do >10m, if you have one of them 7m is still the limit for you. // HC-SR04: SET snr_min to at least 5 ! I check this in sensors and change the value, if needed. // DaddyWalross Sonar: I DON'T KNOW! But it uses HC-SR04 so i apply the same limits (5cm-400cm) to its output // NOTE: Sonar is def. not a must - have. But nice to have. cfg.snr_type = 3; // 0 = PWM56 HC-SR04, 1 = RC78 HC-SR04, 2 = I2C (DaddyWalross), 3 = MBPWM56, 4 = MBRC78 cfg.snr_min = 25; // Valid Sonar minimal range in cm (5-200) see warning above cfg.snr_max = 200; // Valid Sonar maximal range in cm (50-700) cfg.snr_debug = 0; // 1 Sends Sonardata (within defined range and tilt) to debug[0] and tiltvalue to debug[1], debug[0] will be -1 if out of range/tilt. debug[2] contains raw sonaralt, like before cfg.snr_tilt = 18; // Somehow copter tiltrange in degrees (Not exactly but good enough. Value * 0.9 = realtilt) in wich Sonar is possible cfg.snr_cf = 0.7f; // The bigger, the more Sonarinfluence, makes switch between Baro/Sonar smoother and defines baroinfluence when sonarcontact. 1.0f just takes Sonar, if contact (otherwise baro) cfg.snr_diff = 0; // 0 disables that check. Range (0-200) Maximal allowed difference in cm between sonar readouts (100ms rate and snr_diff = 50 means max 5m/s) cfg.snr_land = 1; // Aided Sonar - landing, by setting upper throttle limit to current throttle. - Beware of Trees!! Can be disabled for Failsafe with failsafe_ignoreSNR = 1 // LOGGING cfg.floppy_mode = FD_MODE_GPSLOGGER; // Usagemode of free Space. 1 = GPS Logger cfg.FDUsedDatasets = 0; // Default no Datasets stored cfg.stat_clear = 1; // This will clear the stats between flights, or you can set to 0 and treasue overallstats, but you have to write manually eeprom or have logging enabled cfg.sens_1G = 1; // Just feed a dummy "1" to avoid div by zero ClearStats(); // custom mixer. clear by Dfaults. for (i = 0; i < MAX_MOTORS; i++) cfg.customMixer[i].throttle = 0.0f; writeParams(0); }
// Default settings static void resetConf(void) { int i; // Clear all configuration memset(&masterConfig, 0, sizeof(master_t)); setProfile(0); setControlRateProfile(0); masterConfig.version = EEPROM_CONF_VERSION; masterConfig.mixerMode = MIXER_QUADX; featureClearAll(); persistentFlagClearAll(); featureSet(DEFAULT_RX_FEATURE | FEATURE_FAILSAFE); #ifdef DEFAULT_FEATURES featureSet(DEFAULT_FEATURES); #endif #ifdef BOARD_HAS_VOLTAGE_DIVIDER // only enable the VBAT feature by default if the board has a voltage divider otherwise // the user may see incorrect readings and unexpected issues with pin mappings may occur. featureSet(FEATURE_VBAT); #endif // global settings masterConfig.current_profile_index = 0; // default profile masterConfig.dcm_kp_acc = 2500; // 0.25 * 10000 masterConfig.dcm_ki_acc = 50; // 0.005 * 10000 masterConfig.dcm_kp_mag = 10000; // 1.00 * 10000 masterConfig.dcm_ki_mag = 0; // 0.00 * 10000 masterConfig.gyro_lpf = 3; // INV_FILTER_42HZ, In case of ST gyro, will default to 32Hz instead resetAccelerometerTrims(&masterConfig.accZero, &masterConfig.accGain); resetSensorAlignment(&masterConfig.sensorAlignmentConfig); masterConfig.boardAlignment.rollDeciDegrees = 0; masterConfig.boardAlignment.pitchDeciDegrees = 0; masterConfig.boardAlignment.yawDeciDegrees = 0; masterConfig.acc_hardware = ACC_DEFAULT; // default/autodetect masterConfig.gyroConfig.gyroMovementCalibrationThreshold = 32; masterConfig.mag_hardware = MAG_DEFAULT; // default/autodetect masterConfig.baro_hardware = BARO_DEFAULT; // default/autodetect resetBatteryConfig(&masterConfig.batteryConfig); resetTelemetryConfig(&masterConfig.telemetryConfig); masterConfig.rxConfig.serialrx_provider = 0; masterConfig.rxConfig.spektrum_sat_bind = 0; masterConfig.rxConfig.midrc = 1500; masterConfig.rxConfig.mincheck = 1100; masterConfig.rxConfig.maxcheck = 1900; masterConfig.rxConfig.rx_min_usec = 885; // any of first 4 channels below this value will trigger rx loss detection masterConfig.rxConfig.rx_max_usec = 2115; // any of first 4 channels above this value will trigger rx loss detection for (i = 0; i < MAX_SUPPORTED_RC_CHANNEL_COUNT; i++) { rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration = &masterConfig.rxConfig.failsafe_channel_configurations[i]; channelFailsafeConfiguration->mode = (i < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_MODE_AUTO : RX_FAILSAFE_MODE_HOLD; channelFailsafeConfiguration->step = (i == THROTTLE) ? CHANNEL_VALUE_TO_RXFAIL_STEP(masterConfig.rxConfig.rx_min_usec) : CHANNEL_VALUE_TO_RXFAIL_STEP(masterConfig.rxConfig.midrc); } masterConfig.rxConfig.rssi_channel = 0; masterConfig.rxConfig.rssi_scale = RSSI_SCALE_DEFAULT; masterConfig.rxConfig.rssi_ppm_invert = 0; masterConfig.rxConfig.rcSmoothing = 1; resetAllRxChannelRangeConfigurations(masterConfig.rxConfig.channelRanges); masterConfig.inputFilteringMode = INPUT_FILTERING_DISABLED; masterConfig.disarm_kill_switch = 1; masterConfig.auto_disarm_delay = 5; masterConfig.small_angle = 25; resetMixerConfig(&masterConfig.mixerConfig); // Motor/ESC/Servo resetEscAndServoConfig(&masterConfig.escAndServoConfig); resetFlight3DConfig(&masterConfig.flight3DConfig); #ifdef BRUSHED_MOTORS masterConfig.motor_pwm_rate = BRUSHED_MOTORS_PWM_RATE; #else masterConfig.motor_pwm_rate = BRUSHLESS_MOTORS_PWM_RATE; #endif masterConfig.servo_pwm_rate = 50; #ifdef GPS // gps/nav stuff masterConfig.gpsConfig.provider = GPS_UBLOX; masterConfig.gpsConfig.sbasMode = SBAS_AUTO; masterConfig.gpsConfig.autoConfig = GPS_AUTOCONFIG_ON; masterConfig.gpsConfig.autoBaud = GPS_AUTOBAUD_ON; masterConfig.gpsConfig.dynModel = GPS_DYNMODEL_AIR_1G; #endif #ifdef NAV resetNavConfig(&masterConfig.navConfig); #endif resetSerialConfig(&masterConfig.serialConfig); masterConfig.looptime = 2000; masterConfig.emf_avoidance = 0; masterConfig.i2c_overclock = 0; masterConfig.gyroSync = 0; masterConfig.gyroSyncDenominator = 2; resetPidProfile(¤tProfile->pidProfile); resetControlRateConfig(&masterConfig.controlRateProfiles[0]); // for (i = 0; i < CHECKBOXITEMS; i++) // cfg.activate[i] = 0; currentProfile->mag_declination = 0; resetBarometerConfig(&masterConfig.barometerConfig); // Radio parseRcChannels("AETR1234", &masterConfig.rxConfig); resetRcControlsConfig(¤tProfile->rcControlsConfig); currentProfile->throttle_tilt_compensation_strength = 0; // 0-100, 0 - disabled // Failsafe Variables masterConfig.failsafeConfig.failsafe_delay = 10; // 1sec masterConfig.failsafeConfig.failsafe_off_delay = 200; // 20sec masterConfig.failsafeConfig.failsafe_throttle = 1000; // default throttle off. masterConfig.failsafeConfig.failsafe_kill_switch = 0; // default failsafe switch action is identical to rc link loss masterConfig.failsafeConfig.failsafe_throttle_low_delay = 100; // default throttle low delay for "just disarm" on failsafe condition masterConfig.failsafeConfig.failsafe_procedure = 0; // default full failsafe procedure is 0: auto-landing #ifdef USE_SERVOS // servos for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) { currentProfile->servoConf[i].min = DEFAULT_SERVO_MIN; currentProfile->servoConf[i].max = DEFAULT_SERVO_MAX; currentProfile->servoConf[i].middle = DEFAULT_SERVO_MIDDLE; currentProfile->servoConf[i].rate = 100; currentProfile->servoConf[i].angleAtMin = DEFAULT_SERVO_MIN_ANGLE; currentProfile->servoConf[i].angleAtMax = DEFAULT_SERVO_MAX_ANGLE; currentProfile->servoConf[i].forwardFromChannel = CHANNEL_FORWARDING_DISABLED; } // gimbal currentProfile->gimbalConfig.mode = GIMBAL_MODE_NORMAL; #endif // custom mixer. clear by defaults. for (i = 0; i < MAX_SUPPORTED_MOTORS; i++) masterConfig.customMotorMixer[i].throttle = 0.0f; #ifdef LED_STRIP applyDefaultColors(masterConfig.colors, CONFIGURABLE_COLOR_COUNT); applyDefaultLedStripConfig(masterConfig.ledConfigs); #endif #ifdef BLACKBOX #ifdef ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT featureSet(FEATURE_BLACKBOX); masterConfig.blackbox_device = BLACKBOX_DEVICE_FLASH; #else masterConfig.blackbox_device = BLACKBOX_DEVICE_SERIAL; #endif masterConfig.blackbox_rate_num = 1; masterConfig.blackbox_rate_denom = 1; #endif // alternative defaults settings for COLIBRI RACE targets #if defined(COLIBRI_RACE) masterConfig.looptime = 1000; masterConfig.rxConfig.rcmap[0] = 1; masterConfig.rxConfig.rcmap[1] = 2; masterConfig.rxConfig.rcmap[2] = 3; masterConfig.rxConfig.rcmap[3] = 0; masterConfig.rxConfig.rcmap[4] = 4; masterConfig.rxConfig.rcmap[5] = 5; masterConfig.rxConfig.rcmap[6] = 6; masterConfig.rxConfig.rcmap[7] = 7; featureSet(FEATURE_ONESHOT125); featureSet(FEATURE_VBAT); featureSet(FEATURE_LED_STRIP); featureSet(FEATURE_FAILSAFE); #endif // alternative defaults settings for ALIENWIIF1 and ALIENWIIF3 targets #ifdef ALIENWII32 #ifdef ALIENWIIF3 masterConfig.serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL; masterConfig.batteryConfig.vbatscale = 20; #else masterConfig.serialConfig.portConfigs[1].functionMask = FUNCTION_RX_SERIAL; #endif masterConfig.rxConfig.serialrx_provider = 1; masterConfig.rxConfig.spektrum_sat_bind = 5; masterConfig.escAndServoConfig.minthrottle = 1000; masterConfig.escAndServoConfig.maxthrottle = 2000; masterConfig.motor_pwm_rate = 32000; masterConfig.looptime = 2000; currentProfile->pidProfile.P8[ROLL] = 36; currentProfile->pidProfile.P8[PITCH] = 36; masterConfig.failsafeConfig.failsafe_delay = 2; masterConfig.failsafeConfig.failsafe_off_delay = 0; currentControlRateProfile->rcRate8 = 130; currentControlRateProfile->rates[FD_PITCH] = 20; currentControlRateProfile->rates[FD_ROLL] = 20; currentControlRateProfile->rates[FD_YAW] = 100; parseRcChannels("TAER1234", &masterConfig.rxConfig); // { 1.0f, -0.414178f, 1.0f, -1.0f }, // REAR_R masterConfig.customMotorMixer[0].throttle = 1.0f; masterConfig.customMotorMixer[0].roll = -0.414178f; masterConfig.customMotorMixer[0].pitch = 1.0f; masterConfig.customMotorMixer[0].yaw = -1.0f; // { 1.0f, -0.414178f, -1.0f, 1.0f }, // FRONT_R masterConfig.customMotorMixer[1].throttle = 1.0f; masterConfig.customMotorMixer[1].roll = -0.414178f; masterConfig.customMotorMixer[1].pitch = -1.0f; masterConfig.customMotorMixer[1].yaw = 1.0f; // { 1.0f, 0.414178f, 1.0f, 1.0f }, // REAR_L masterConfig.customMotorMixer[2].throttle = 1.0f; masterConfig.customMotorMixer[2].roll = 0.414178f; masterConfig.customMotorMixer[2].pitch = 1.0f; masterConfig.customMotorMixer[2].yaw = 1.0f; // { 1.0f, 0.414178f, -1.0f, -1.0f }, // FRONT_L masterConfig.customMotorMixer[3].throttle = 1.0f; masterConfig.customMotorMixer[3].roll = 0.414178f; masterConfig.customMotorMixer[3].pitch = -1.0f; masterConfig.customMotorMixer[3].yaw = -1.0f; // { 1.0f, -1.0f, -0.414178f, -1.0f }, // MIDFRONT_R masterConfig.customMotorMixer[4].throttle = 1.0f; masterConfig.customMotorMixer[4].roll = -1.0f; masterConfig.customMotorMixer[4].pitch = -0.414178f; masterConfig.customMotorMixer[4].yaw = -1.0f; // { 1.0f, 1.0f, -0.414178f, 1.0f }, // MIDFRONT_L masterConfig.customMotorMixer[5].throttle = 1.0f; masterConfig.customMotorMixer[5].roll = 1.0f; masterConfig.customMotorMixer[5].pitch = -0.414178f; masterConfig.customMotorMixer[5].yaw = 1.0f; // { 1.0f, -1.0f, 0.414178f, 1.0f }, // MIDREAR_R masterConfig.customMotorMixer[6].throttle = 1.0f; masterConfig.customMotorMixer[6].roll = -1.0f; masterConfig.customMotorMixer[6].pitch = 0.414178f; masterConfig.customMotorMixer[6].yaw = 1.0f; // { 1.0f, 1.0f, 0.414178f, -1.0f }, // MIDREAR_L masterConfig.customMotorMixer[7].throttle = 1.0f; masterConfig.customMotorMixer[7].roll = 1.0f; masterConfig.customMotorMixer[7].pitch = 0.414178f; masterConfig.customMotorMixer[7].yaw = -1.0f; #endif // copy first profile into remaining profile for (i = 1; i < MAX_PROFILE_COUNT; i++) { memcpy(&masterConfig.profile[i], currentProfile, sizeof(profile_t)); } // copy first control rate config into remaining profile for (i = 1; i < MAX_CONTROL_RATE_PROFILE_COUNT; i++) { memcpy(&masterConfig.controlRateProfiles[i], currentControlRateProfile, sizeof(controlRateConfig_t)); } for (i = 1; i < MAX_PROFILE_COUNT; i++) { masterConfig.profile[i].defaultRateProfileIndex = i % MAX_CONTROL_RATE_PROFILE_COUNT; } }
void receiverCLI() { char rcOrderString[9]; float tempFloat; uint8_t index; uint8_t receiverQuery; uint8_t validQuery = false; cliBusy = true; cliPrint("\nEntering Receiver CLI....\n\n"); while(true) { cliPrint("Receiver CLI -> "); while ((cliAvailable() == false) && (validQuery == false)); if (validQuery == false) receiverQuery = cliRead(); cliPrint("\n"); switch(receiverQuery) { /////////////////////////// case 'a': // Receiver Configuration cliPrint("\nReceiver Type: "); switch(eepromConfig.receiverType) { case PARALLEL_PWM: cliPrint("Parallel\n"); break; case SERIAL_PWM: cliPrint("Serial\n"); break; case SPEKTRUM: cliPrint("Spektrum\n"); break; } cliPrint("Current RC Channel Assignment: "); for (index = 0; index < 8; index++) rcOrderString[eepromConfig.rcMap[index]] = rcChannelLetters[index]; rcOrderString[index] = '\0'; cliPrint(rcOrderString); cliPrint("\n"); cliPrintF("Spektrum Resolution: %s\n", eepromConfig.spektrumHires ? "11 Bit Mode" : "10 Bit Mode"); cliPrintF("Number of Spektrum Channels: %2d\n", eepromConfig.spektrumChannels); cliPrintF("Mid Command: %4ld\n", (uint16_t)eepromConfig.midCommand); cliPrintF("Min Check: %4ld\n", (uint16_t)eepromConfig.minCheck); cliPrintF("Max Check: %4ld\n", (uint16_t)eepromConfig.maxCheck); cliPrintF("Min Throttle: %4ld\n", (uint16_t)eepromConfig.minThrottle); cliPrintF("Max Thottle: %4ld\n\n", (uint16_t)eepromConfig.maxThrottle); tempFloat = eepromConfig.rateScaling * 180000.0 / PI; cliPrintF("Max Rate Command: %6.2f DPS\n", tempFloat); tempFloat = eepromConfig.attitudeScaling * 180000.0 / PI; cliPrintF("Max Attitude Command: %6.2f Degrees\n\n", tempFloat); cliPrintF("Arm Delay Count: %3d Frames\n", eepromConfig.armCount); cliPrintF("Disarm Delay Count: %3d Frames\n\n", eepromConfig.disarmCount); validQuery = false; break; /////////////////////////// case 'b': // Read Max Rate Value eepromConfig.rateScaling = readFloatCLI() / 180000 * PI; receiverQuery = 'a'; validQuery = true; break; /////////////////////////// case 'c': // Read Max Attitude Value eepromConfig.attitudeScaling = readFloatCLI() / 180000 * PI; receiverQuery = 'a'; validQuery = true; break; /////////////////////////// case 'x': cliPrint("\nExiting Receiver CLI....\n\n"); cliBusy = false; return; break; /////////////////////////// case 'A': // Read RX Input Type eepromConfig.receiverType = (uint8_t)readFloatCLI(); cliPrint( "\nReceiver Type Changed....\n"); cliPrint("\nSystem Resetting....\n"); delay(100); writeEEPROM(); systemReset(false); break; /////////////////////////// case 'B': // Read RC Control Order readStringCLI( rcOrderString, 8 ); parseRcChannels( rcOrderString ); receiverQuery = 'a'; validQuery = true; break; /////////////////////////// case 'C': // Read Spektrum Resolution eepromConfig.spektrumHires = (uint8_t)readFloatCLI(); receiverQuery = 'a'; validQuery = true; break; /////////////////////////// case 'D': // Read Number of Spektrum Channels eepromConfig.spektrumChannels = (uint8_t)readFloatCLI(); receiverQuery = 'a'; validQuery = true; break; /////////////////////////// case 'E': // Read RC Control Points eepromConfig.midCommand = readFloatCLI(); eepromConfig.minCheck = readFloatCLI(); eepromConfig.maxCheck = readFloatCLI(); eepromConfig.minThrottle = readFloatCLI(); eepromConfig.maxThrottle = readFloatCLI(); receiverQuery = 'a'; validQuery = true; break; /////////////////////////// case 'F': // Read Arm/Disarm Counts eepromConfig.armCount = (uint8_t)readFloatCLI(); eepromConfig.disarmCount = (uint8_t)readFloatCLI(); receiverQuery = 'a'; validQuery = true; break; /////////////////////////// case 'W': // Write EEPROM Parameters cliPrint("\nWriting EEPROM Parameters....\n\n"); writeEEPROM(); break; /////////////////////////// case '?': cliPrint("\n"); cliPrint("'a' Receiver Configuration Data 'A' Set RX Input Type AX, 1=Parallel, 2=Serial, 3=Spektrum\n"); cliPrint("'b' Set Maximum Rate Command 'B' Set RC Control Order BTAER1234\n"); cliPrint("'c' Set Maximum Attitude Command 'C' Set Spektrum Resolution C0 or C1\n"); cliPrint(" 'D' Set Number of Spektrum Channels D6 thru D12\n"); cliPrint(" 'E' Set RC Control Points EmidCmd;minChk;maxChk;minThrot;maxThrot\n"); cliPrint(" 'F' Set Arm/Disarm Counts FarmCount;disarmCount\n"); cliPrint(" 'W' Write EEPROM Parameters\n"); cliPrint("'x' Exit Receiver CLI '?' Command Summary\n"); cliPrint("\n"); break; /////////////////////////// } } }
// Default settings static void resetConf(void) { int i; const int8_t default_align[3][3] = { /* GYRO */ { 0, 0, 0 }, /* ACC */ { 0, 0, 0 }, /* MAG */ { -2, -3, 1 } }; memset(&cfg, 0, sizeof(config_t)); cfg.version = EEPROM_CONF_VERSION; //cfg.mixerConfiguration = MULTITYPE_QUADX; cfg.mixerConfiguration = MULTITYPE_AIRPLANE; featureClearAll(); //featureSet(FEATURE_VBAT); // Enable Vbat monitoring //featureSet(FEATURE_PPM); // Enable CPPM input cfg.looptime = 0; cfg.P8[ROLL] = 20; //cfg.I8[ROLL] = 30; //cfg.D8[ROLL] = 23; cfg.I8[ROLL] = 0; cfg.D8[ROLL] = 0; cfg.P8[PITCH] = 20; //cfg.I8[PITCH] = 30; //cfg.D8[PITCH] = 23; cfg.I8[PITCH] = 0; cfg.D8[PITCH] = 0; cfg.P8[YAW] = 85; cfg.I8[YAW] = 0; //cfg.I8[YAW] = 45; cfg.D8[YAW] = 0; cfg.P8[PIDALT] = 0; cfg.I8[PIDALT] = 0; cfg.D8[PIDALT] = 0; cfg.P8[PIDPOS] = 0; // POSHOLD_P * 100; cfg.I8[PIDPOS] = 0; // POSHOLD_I * 100; cfg.D8[PIDPOS] = 0; cfg.P8[PIDPOSR] = 0; // POSHOLD_RATE_P * 10; cfg.I8[PIDPOSR] = 0; // POSHOLD_RATE_I * 100; cfg.D8[PIDPOSR] = 0; // POSHOLD_RATE_D * 1000; cfg.P8[PIDNAVR] = 0; // NAV_P * 10; cfg.I8[PIDNAVR] = 0; // NAV_I * 100; cfg.D8[PIDNAVR] = 0; // NAV_D * 1000; cfg.P8[PIDLEVEL] = 20; cfg.I8[PIDLEVEL] = 0; cfg.D8[PIDLEVEL] = 100; //cfg.P8[PIDLEVEL] = 70; //cfg.I8[PIDLEVEL] = 10; //cfg.D8[PIDLEVEL] = 20; cfg.P8[PIDMAG] = 40; cfg.P8[PIDVEL] = 0; cfg.I8[PIDVEL] = 0; cfg.D8[PIDVEL] = 0; cfg.rcRate8 = 100; cfg.rcExpo8 = 0; cfg.rollPitchRate = 0; cfg.yawRate = 0; cfg.dynThrPID = 0; cfg.thrMid8 = 50; cfg.thrExpo8 = 0; for (i = 0; i < CHECKBOXITEMS; i++) cfg.activate[i] = 0; cfg.angleTrim[0] = 0; cfg.angleTrim[1] = 0; cfg.accZero[0] = 0; cfg.accZero[1] = 0; cfg.accZero[2] = 0; // Magnetic declination: format is [sign]dddmm (degreesminutes) default is zero. // +12deg 31min = 1231 Sydney, Australia // -6deg 37min = -637 Southern Japan // cfg.mag_declination = 0; cfg.mag_declination = 1231; memcpy(&cfg.align, default_align, sizeof(cfg.align)); cfg.acc_hardware = ACC_DEFAULT; // default/autodetect cfg.acc_lpf_factor = 4; cfg.acc_lpf_for_velocity = 10; cfg.accz_deadband = 50; cfg.gyro_cmpf_factor = 400; // default MWC cfg.gyro_lpf = 42; cfg.mpu6050_scale = 1; // f**k invensense cfg.baro_tab_size = 21; cfg.baro_noise_lpf = 0.6f; cfg.baro_cf = 0.985f; cfg.moron_threshold = 32; cfg.gyro_smoothing_factor = 0x00141403; // default factors of 20, 20, 3 for R/P/Y cfg.vbatscale = 110; cfg.vbatmaxcellvoltage = 43; cfg.vbatmincellvoltage = 33; // cfg.power_adc_channel = 0; // Radio parseRcChannels("AETR1234"); //parseRcChannels("TAER1234"); // Debug - JR cfg.deadband = 0; cfg.yawdeadband = 0; cfg.alt_hold_throttle_neutral = 20; cfg.spektrum_hires = 0; for (i = 0; i < 8; i++) // RC stick centers { cfg.midrc[i] = 1500; } cfg.defaultrc = 1500; cfg.mincheck = 1100; cfg.maxcheck = 1900; cfg.retarded_arm = 0; // disable arm/disarm on roll left/right // Failsafe Variables cfg.failsafe_delay = 10; // 1sec cfg.failsafe_off_delay = 200; // 20sec cfg.failsafe_throttle = 1200; // decent default which should always be below hover throttle for people. // Motor/ESC/Servo cfg.minthrottle = 1150; cfg.maxthrottle = 1850; cfg.mincommand = 1000; cfg.motor_pwm_rate = 400; cfg.servo_pwm_rate = 50; // servos cfg.yaw_direction = 1; cfg.tri_yaw_middle = 1500; cfg.tri_yaw_min = 1020; cfg.tri_yaw_max = 2000; // gimbal cfg.gimbal_pitch_gain = 10; cfg.gimbal_roll_gain = 10; cfg.gimbal_flags = GIMBAL_NORMAL; cfg.gimbal_pitch_min = 1020; cfg.gimbal_pitch_max = 2000; cfg.gimbal_pitch_mid = 1500; cfg.gimbal_roll_min = 1020; cfg.gimbal_roll_max = 2000; cfg.gimbal_roll_mid = 1500; // gps/nav stuff cfg.gps_type = GPS_NMEA; cfg.gps_baudrate = 115200; cfg.gps_wp_radius = 200; cfg.gps_lpf = 20; cfg.nav_slew_rate = 30; cfg.nav_controls_heading = 1; cfg.nav_speed_min = 100; cfg.nav_speed_max = 300; // serial (USART1) baudrate cfg.serial_baudrate = 115200; // Aeroplane stuff cfg.flapmode = ADV_FLAP; // Switch for flaperon mode? cfg.flapchan = AUX2; // RC channel number for simple flaps) cfg.aileron2 = AUX1; // RC channel number for second aileron cfg.flapspeed = 10; // Desired rate of change of flaps cfg.flapstep = 3; // Steps for each flap movement cfg.DynPIDchan = THROTTLE; // Dynamic PID source channel cfg.DynPIDbreakpoint = 1500; // Dynamic PID breakpoint cfg.rollPIDpol = 1; cfg.pitchPIDpol = 1; cfg.yawPIDpol = 1; for (i = 0; i < 8; i++) // Servo limits { cfg.servoendpoint_low[i] = 1000; cfg.servoendpoint_high[i] = 2000; cfg.servoreverse[i] = 1; cfg.servotrim[i] = 1500; // Set servo trim to default } // custom mixer. clear by defaults. for (i = 0; i < MAX_MOTORS; i++) cfg.customMixer[i].throttle = 0.0f; writeParams(0); }
// Default settings static void resetConf(void) { uint8_t i; const int8_t default_align[3][3] = { /* GYRO */ { 0, 0, 0 }, /* ACC */ { 0, 0, 0 }, /* MAG */ { 0, 0, 0 } }; memset(&cfg, 0, sizeof(config_t)); cfg.version = EEPROM_CONF_VERSION; cfg.mixerConfiguration = MULTITYPE_QUADX; featureClearAll(); // featureSet(FEATURE_VBAT); featureSet(FEATURE_PPM); // featureSet(FEATURE_FAILSAFE); // featureSet(FEATURE_LCD); // featureSet(FEATURE_GPS); // featureSet(FEATURE_PASS); // Just pass Throttlechannel // featureSet(FEATURE_SONAR); cfg.P8[ROLL] = 35; // 40 cfg.I8[ROLL] = 30; cfg.D8[ROLL] = 30; cfg.P8[PITCH] = 35; // 40 cfg.I8[PITCH] = 30; cfg.D8[PITCH] = 30; cfg.P8[YAW] = 60; // 70 cfg.I8[YAW] = 45; cfg.P8[PIDALT] = 100; cfg.I8[PIDALT] = 30; cfg.D8[PIDALT] = 80; cfg.P8[PIDPOS] = 10; // FIND YOUR VALUE cfg.I8[PIDPOS] = 40; // USED cfg.P8[PIDPOSR] = 70; // FIND YOUR VALUE // Controls the speed part with my PH logic cfg.D8[PIDPOSR] = 100; // FIND YOUR VALUE // Controls the speed part with my PH logic cfg.P8[PIDNAVR] = 15; // 14 More ? cfg.I8[PIDNAVR] = 0; // NAV_I * 100; // Scaling/Purpose unchanged cfg.D8[PIDNAVR] = 0; // NAV_D * 1000; // Scaling/Purpose unchanged // cfg.P8[PIDPOS] = 11; // APM PH Stock values // cfg.I8[PIDPOS] = 0; // cfg.D8[PIDPOS] = 0; // cfg.P8[PIDPOSR] = 20; // POSHOLD_RATE_P * 10; // cfg.I8[PIDPOSR] = 8; // POSHOLD_RATE_I * 100; // cfg.D8[PIDPOSR] = 45; // POSHOLD_RATE_D * 1000; // cfg.P8[PIDNAVR] = 14; // NAV_P * 10; // cfg.I8[PIDNAVR] = 20; // NAV_I * 100; // cfg.D8[PIDNAVR] = 80; // NAV_D * 1000; cfg.P8[PIDLEVEL] = 70; // 70 cfg.I8[PIDLEVEL] = 10; cfg.D8[PIDLEVEL] = 50; cfg.P8[PIDMAG] = 80; // cfg.P8[PIDVEL] = 0;// cfg.I8[PIDVEL] = 0;// cfg.D8[PIDVEL] = 0; cfg.rcRate8 = 100; cfg.rcExpo8 = 80; // cfg.rollPitchRate = 0;// cfg.yawRate = 0;// cfg.dynThrPID = 0; cfg.thrMid8 = 50; memcpy(&cfg.align, default_align, sizeof(cfg.align)); cfg.mag_dec = 113; // Crashpilot //cfg.acc_hdw = ACC_DEFAULT;// default/autodetect cfg.mag_time = 1; // (1-6) Calibration time in minutes cfg.mag_gain = 0; // 0(default) = 1.9 GAUSS ; 1 = 2.5 GAUSS (problematic copters, will reduce 20% resolution) cfg.acc_hdw = 2; // Crashpilot MPU6050 cfg.acc_lpfhz = 10.0f; // [0.x-100Hz] LPF for angle/horizon 0.536f resembles somehow the orig mwii factor cfg.acc_altlpfhz = 15; // [1-100Hz] LPF for althold cfg.acc_gpslpfhz = 30; // [1-100Hz] LPF for GPS ins stuff cfg.looptime = 3000; cfg.mainpidctrl = 0; // 0 = OriginalMwiiPid pimped by me, 1 = New mwii controller (experimental, float pimped + pt1) cfg.maincuthz = 12; // [1-100Hz] Cuf Off Frequency for D term of main Pid controller cfg.gpscuthz = 45; // [1-100Hz] Cuf Off Frequency for D term of GPS Pid controller cfg.gy_gcmpf = 700; // (10-1000) 400 default. Now 1000. The higher, the more weight gets the gyro and the lower is the correction with Acc data. cfg.gy_mcmpf = 200; // (10-2000) 200 default for 10Hz. Now higher. Gyro/Magnetometer Complement. cfg.gy_smrll = 0; cfg.gy_smptc = 0; cfg.gy_smyw = 0; // In Tricopter mode a "1" will enable a moving average filter, anything higher will also enable a lowpassfilter cfg.gy_lpf = 42; // Values for MPU 6050/3050: 256, 188, 98, 42, 20, 10, (HZ) For L3G4200D: 93, 78, 54, 32 cfg.gy_stdev = 5; // Baro cfg.accz_vcf = 0.985f; // Crashpilot: Value for complementary filter accz and barovelocity cfg.accz_acf = 0.960f; // Crashpilot: Value for complementary filter accz and altitude cfg.bar_lag = 0.3f; // Lag of Baro/Althold stuff in general, makes stop in hightchange snappier cfg.bar_dscl = 0.7f; // Scale downmovement down (because copter drops faster than rising) cfg.bar_dbg = 0; // Crashpilot: 1 = Debug Barovalues //cfg.baro_noise_lpf = 0.6f;// Crashpilot: Not used anymore//cfg.baro_cf = 0.985f;// Crashpilot: Not used anymore // Autoland cfg.al_barolr = 50; // [10 - 200cm/s] Baro Landingrate cfg.al_snrlr = 50; // [10 - 200cm/s] Sonar Landingrate - You can specify different landingfactor here on sonar contact, because sonar land maybe too fast when snr_cf is high cfg.al_debounce = 5; // (0-20%) 0 Disables. Defines a Throttlelimiter on Autoland. Percentage defines the maximum deviation of assumed hoverthrottle during Autoland cfg.al_tobaro = 2000; // Timeout in ms (100 - 5000) before shutoff on autoland. "esc_nfly" must be undershot for that timeperiod cfg.al_tosnr = 1000; // Timeout in ms (100 - 5000) If sonar aided land is wanted (snr_land = 1) you can choose a different timeout here // Autostart cfg.as_lnchr = 200; // [50 - 250 no dimension DEFAULT:200] Autostart initial launchrate to get off the ground. When as_stdev is exceeded, as_clmbr takes over cfg.as_clmbr = 100; // [50 - 250cm/s DEFAULT:100] Autostart climbrate in cm/s after liftoff! Autostart Rate in cm/s will be lowered when approaching targethight. cfg.as_trgt = 0; // [0 - 255m DEFAULT:0 (0 = Disable)] Autostart Targethight in m Note: use 2m or more cfg.as_stdev = 10; // [5 - 20 no dimension DEFAULT:10] This is the std. deviation of the variometer when a liftoff is assumed. The higher the more unsensitive. cfg.vbatscale = 110; cfg.vbatmaxcellvoltage = 43; cfg.vbatmincellvoltage = 33; cfg.power_adc_channel = 0; // Radio parseRcChannels("AETR1234"); cfg.rc_db = 20; // Crashpilot: A little deadband will not harm our crappy RC cfg.rc_dbyw = 20; // Crashpilot: A little deadband will not harm our crappy RC cfg.rc_dbah = 50; // Crashpilot: A little deadband will not harm our crappy RC cfg.rc_dbgps = 5; // Additional Deadband for all GPS functions; cfg.devorssi = 0; // Will take the last channel for RSSI value, so add one to rc_auxch, don't use that auxchannel unless you want it to trigger something // Note Spektrum or Graupner will override that setting to 0. cfg.rssicut = 0; // [0-80%][0 Disables] Below that percentage rssi will show zero. // cfg.spektrum_hires = 0; cfg.rc_minchk = 1100; cfg.rc_mid = 1500; cfg.rc_maxchk = 1900; cfg.rc_lowlat = 1; // [0 - 1] Default 1. 1 = lower latency, 0 = normal latency/more filtering. cfg.rc_rllrm = 0; // disable arm/disarm on roll left/right cfg.rc_auxch = 4; // [4 - 6] cGiesen: Default = 4, then like the standard! Crashpilot: Limited to 6 aux for safety cfg.rc_killt = 0; // Time in ms when your arm switch becomes a Killswitch, 0 disables the Killswitch, can not be used together with FEATURE_INFLIGHT_ACC_CAL cfg.rc_flpsp = 0; // [0-3] When enabled(1) and upside down in acro or horizon mode throttle is reduced (see readme) cfg.rc_motor = 0; // [0-2] Behaviour when thr < rc_minchk: 0= minthrottle no regulation, 1= minthrottle®ulation, 2= Motorstop // Motor/ESC/Servo cfg.esc_gain = 0; // [0Disables - 32] Gain for esc to reduce delay 16 = Gain of 1 that would double the initial response(limited to +500) Only helps unflashed ESC. // cfg.esc_min = 1150; // ORIG cfg.esc_min = 1100; cfg.esc_max = 1950; cfg.esc_moff = 1000; cfg.esc_nfly = 1300; // This is the absolute throttle that kicks off the "has landed timer" if it is too low cfg.rc_minchk + 5% is taken. Also baselinethr for Autostart, also plausibility check for initial Failsafethrottle // cfg.esc_nfly = 0; // This is the absolute throttle that kicks off the "has landed timer" if it is too low cfg.rc_minchk + 5% is taken. cfg.esc_pwm = 400; cfg.srv_pwm = 50; cfg.pass_mot = 0; // Crashpilot: Only used with feature pass. If 0 = all Motors, otherwise specific Motor // servos cfg.tri_ydir = 1; cfg.tri_ymid = 1500; cfg.tri_ymin = 1020; cfg.tri_ymax = 2000; cfg.tri_ydel = 0; // [0-1000ms] Tri Yaw Arm delay: Time in ms after wich the yaw servo after arming will engage (useful with "yaw arm"). 0 disables Yawservo always active. // flying wing cfg.wing_left_min = 1020; cfg.wing_left_mid = 1500; cfg.wing_left_max = 2000; cfg.wing_right_min = 1020; cfg.wing_right_mid = 1500; cfg.wing_right_max = 2000; cfg.pitch_direction_l = 1; cfg.pitch_direction_r = -1; cfg.roll_direction_l = 1; cfg.roll_direction_r = 1; // gimbal cfg.gbl_pgn = 10; cfg.gbl_rgn = 10; cfg.gbl_flg = GIMBAL_NORMAL; cfg.gbl_pmn = 1020; cfg.gbl_pmx = 2000; cfg.gbl_pmd = 1500; cfg.gbl_rmn = 1020; cfg.gbl_rmx = 2000; cfg.gbl_rmd = 1500; // gps/nav cfg.gps_type = 1; // GPS_NMEA = 0, GPS_UBLOX = 1, GPS_MTK16 = 2, GPS_MTK19 = 3, GPS_UBLOX_DUMB = 4 cfg.gps_baudrate = 115200; //38400; // Changed 8/6/13 to 115200; cfg.gps_ins_vel = 0.6f; // Crashpilot GPS INS The LOWER the value the closer to gps speed // Dont go to high here cfg.gps_lag = 2000; // GPS Lag in ms cfg.gps_ph_minsat = 6; // Minimal Satcount for PH, PH on RTL is still done with 5Sats or more cfg.gps_expo = 20; // 1 - 99 % defines the actual Expo applied for GPS cfg.gps_ph_settlespeed = 10; // 1 - 200 cm/s PH settlespeed in cm/s cfg.gps_ph_brakemaxangle = 15; // 1 - 45 Degree Maximal Overspeedbrake cfg.gps_ph_minbrakepercent = 50; // 1 - 99% minimal percent of "brakemaxangle" left over for braking. Example brakemaxangle = 6 so 50 Percent is 3.. cfg.gps_ph_brkacc = 40; // [1 - 500] Is the assumed negative braking acceleration in cm/(s*s) of copter. Value is positive though. It will be a timeout. The lower the Value the longe the Timeout cfg.gps_maxangle = 35; // 10 - 45 Degree Maximal over all GPS bank angle cfg.gps_wp_radius = 200; // cfg.rtl_mnh = 20; // (0 - 200m) Minimal RTL hight in m, 0 disables feature cfg.rtl_mnh = 0; // (0 - 200m) Minimal RTL hight in m, 0 disables feature cfg.rtl_cr = 80; // [10 - 200cm/s] When rtl_mnh is defined this is the climbrate in cm/s cfg.rtl_mnd = 0; // 0 Disables. Minimal distance for RTL in m, otherwise it will just autoland, prevent Failsafe jump in your face, when arming copter and turning off TX cfg.gps_rtl_flyaway = 0; // [0 - 100m] 0 Disables. If during RTL the distance increases beyond this value (in meters relative to RTL activation point), something is wrong, autoland cfg.gps_yaw = 30; // Thats the MAG P during GPS functions, substitute for "cfg.P8[PIDMAG]" cfg.nav_rtl_lastturn = 1; // 1 = when copter gets to home position it rotates it's head to takeoff direction independend of nav_controls_heading cfg.nav_tail_first = 0; // 1 = Copter comes back with ass first (only works with nav_controls_heading = 1) cfg.nav_controls_heading = 0; // 1 = Nav controls YAW during WP ONLY // cfg.nav_controls_heading = 1; // 1 = Nav controls YAW during WP ONLY cfg.nav_speed_min = 100; // 10 - 200 cm/s don't set higher than nav_speed_max! That dumbness is not covered. cfg.nav_speed_max = 350; // 50 - 2000 cm/s don't set lower than nav_speed_min! That dumbness is not covered. cfg.nav_approachdiv = 3; // 2 - 10 This is the divisor for approach speed for wp_distance. Example: 400cm / 3 = 133cm/s if below nav_speed_min it will be adjusted cfg.nav_tiltcomp = 30; // 0 - 100 (20 TestDefault) Only arducopter really knows. Dfault was 54. This is some kind of a hack of them to reach actual nav_speed_max. 54 was Dfault, 0 disables cfg.nav_ctrkgain = 0.5f; // 0 - 10.0 (0.5 TestDefault) (Floatvariable) That is the "Crosstrackgain" APM Dfault is "1". "0" disables // Failsafe Variables cfg.fs_delay = 10; // in 0.1s (10 = 1sec) cfg.fs_ofdel = 200; // in 0.1s (200 = 20sec) cfg.fs_rcthr = 1200; // decent Dfault which should always be below hover throttle for people. cfg.fs_ddplt = 0; // EXPERIMENTAL Time in sec when FS is engaged after idle on THR/YAW/ROLL/PITCH, 0 disables max 250 cfg.fs_jstph = 0; // Does just PH&Autoland an not RTL, use this in difficult areas with many obstacles to avoid RTL crash into something cfg.fs_nosnr = 1; // When snr_land is set to 1, it is possible to ignore that on Failsafe, because FS over a tree could turn off copter // serial (USART1) baudrate cfg.serial_baudrate = 115200; cfg.tele_prot = 0; // Protocol ONLY used when Armed including Baudchange if necessary. 0 (Dfault)=Keep Multiwii @CurrentUSB Baud, 1=Frsky @9600Baud, 2=Mavlink @CurrentUSB Baud, 3=Mavlink @57KBaud (like stock minimOSD wants it) // LED Stuff cfg.LED_invert = 0; // Crashpilot: Inversion of LED 0&1 Partly implemented because Bootup is not affected cfg.LED_Type = 1; // 1=MWCRGB / 2=MONO_LED / 3=LEDRing cfg.LED_Pinout = 1; // rc6 cfg.LED_ControlChannel = 8; // AUX4 (Channel 8) cfg.LED_Armed = 0; // 0 = Show LED only if armed, 1 = always show LED cfg.LED_Pattern1 = 1300; // 32bit bit pattern to have flickering led patterns / the pattern for MWCRGB 1000-2000 cfg.LED_Pattern2 = 1800; // 32bit bit pattern to have flickering led patterns / the pattern for MWCRGB 1000-2000 cfg.LED_Pattern3 = 1900; // 32bit bit pattern to have flickering led patterns / the pattern for MWCRGB 1000-2000 cfg.LED_Toggle_Delay1 = 0x08; // slow down LED_Pattern cfg.LED_Toggle_Delay2 = 0x08; // slow down LED_Pattern cfg.LED_Toggle_Delay3 = 0x08; // slow down LED_Pattern // SONAR // SOME INFO ON SONAR: // PWM56 are 5V resistant, RC78 only tolerate 3.3V(!!) so add a 1K Ohms resistor!!! // Note: You will never see the maximum possible sonar range in a copter, so go for the half of it (or less?) // // Connection possibilities depending on Receivertype: // PPSUM: RC78 possible, PWM56 possible (on max. quadcopters, see below) // Normal RX: Just Connection on Motorchannel 5&6 (PWM56) is possible. // The PWM56 sonar connection option is only available in setups with max motors 4, otherwise sonar is not initialized. // // HC-SR04: // Operation Voltage: 5V (!! Use PWM56 or 1K resistor !!) // Range: 2cm - 400cm // Angle: 15 Degrees (Test out for yourself: cfg.snr_tilt = X) // // Maxbotix in general // Operation Voltage: (some 2.5V)3.3V - 5V ((!! Use PWM56 or resistor with 5V !!) // Only wire the Maxbotics for PWM output (more precise anyway), not the analog etc. modes, just wire echopin (normally pin 2) // Range: 20cm(!) - 765cm (some >1000cm), MaxTiltAngle is not specified, depending on Model // Tested on MB1200 XL-MaxSonar-EZ0 // // I2C sonar in general (by mj666) // If operation voltage of the sonar sensor is 5 Volt (NAZE I2C is 3.3 Volt), take care they do not have pull up resistors connected to 5 Volt. // Outputs are always open drain so there is no risk kill something only signals may be critical so keep wires short as possible. // Maxbotix I2CXL series operates with 3.3 and 5 Volt but 5Volt are preferred for best performance and stability. // // Devantech Ltd. (SRF02, SRF235, SRF08, SRF10): // Type; Range; Cycletime; Angle; Comment // SRF02; 16 to 600cm; 65ms; 55 degree; automatic calibration, minimum rage can be read from sensor (not implemented) // SRF235; 10 - 1200cm; 10ms; 15 degree; angle is may be to small for the use case // SRF08; 3 - 600cm; 65ms; 55 degree; range, gain an cycletime can be adjusted, multiple echos are measured (both not implemented) // SRF10; 6 - 600cm; 65ms; 72 degree; range, gain an cycletime can be adjusted (not implemented) // be sure to adjust settings accordingly, no additional test are done. // more details at: http://www.robot-electronics.co.uk/index.html // // Maxbotix I2CXL (MB1202, MB1212, MB1222, MB1232, MB1242) // I"CXL Series of sensors only differentiated by the beam pattern and sensibility. Maxbotix is recommending the MX1242 for quadcopter applications. The interface is always the same // NOTE: Maxbotix Sonars only operate with lower I2C speed, so the speed is changed on the fly during Maxbotix readout. // Thanks must go to mj666 for implementing that! // GENERAL WARNING: DON'T SET snr_min TOO LOW, OTHERWISE THE WRONG SONARVALUE WILL BE TAKEN AS REAL MEASUREMENT!! // I implemented some checks to prevent that user error, but still keep that in mind. // Min/Max are checked and changed if they are too stupid for your sonar. So if you suddenly see other values, thats not an eeprom error or so. // MAXBOTICS: SET snr_min to at least 30! I check this in sensors and change the value, if needed. // NOTE: I limited Maxbotics to 7 meters in the code, knowing that some types will do >10m, if you have one of them 7m is still the limit for you. // HC-SR04: SET snr_min to at least 10 ! I check this in sensors and change the value, if needed. // DaddyWalross Sonar: I DON'T KNOW! But it uses HC-SR04 so i apply the same limits (10cm-400cm) to its output // Sonar minimal hight must be higher (including temperature difference) than the physical lower limit of the sensor to do a proximity alert // NOTE: Sonar is def. not a must - have. But nice to have. cfg.snr_type = 3; // 0=PWM56 HC-SR04, 1=RC78 HC-SR04, 2=I2C(DaddyWalross), 3=MBPWM56, 4=MBRC78, 5=I2C(SRFxx), 6=I2C (MX12x2) cfg.snr_min = 30; // Valid Sonar minimal range in cm (10 - 200) see warning above cfg.snr_max = 200; // Valid Sonar maximal range in cm (50 - 700) cfg.snr_dbg = 0; // 1 Sends Sonardata (within defined range and tilt) to debug[0] and tiltvalue to debug[1], debug[0] will be -1 if out of range/tilt. debug[2] contains raw sonaralt, like before cfg.snr_tilt = 18; // Somehow copter tiltrange in degrees (Not exactly but good enough. Value * 0.9 = realtilt) in wich Sonar is possible cfg.snr_cf = 0.5f; // The bigger, the more Sonarinfluence, makes switch between Baro/Sonar smoother and defines baroinfluence when sonarcontact. 1.0f just takes Sonar, if contact (otherwise baro) cfg.snr_diff = 0; // 0 disables that check. Range (0-200) Maximal allowed difference in cm between sonar readouts (100ms rate and snr_diff = 50 means max 5m/s) cfg.snr_land = 1; // Aided Sonar - landing, by setting upper throttle limit to current throttle. - Beware of Trees!! Can be disabled for Failsafe with fs_nosnr = 1 cfg.FDUsedDatasets = 0; // Default no Datasets stored cfg.stat_clear = 1; // This will clear the stats between flights, or you can set to 0 and treasue overallstats, but you have to write manually eeprom or have logging enabled cfg.sens_1G = 1; // Just feed a dummy "1" to avoid div by zero ClearStats(); for (i = 0; i < MAX_MOTORS; i++) cfg.customMixer[i].throttle = 0.0f;// custom mixer. clear by Dfaults. writeParams(0); }
void checkFirstTime(bool eepromReset) { uint8_t test_val; test_val = *(uint8_t *)FLASH_WRITE_EEPROM_ADDR; if (eepromReset || test_val != checkNewEEPROMConf) { // Default settings eepromConfig.version = checkNewEEPROMConf; /////////////////////////////// eepromConfig.accelTCBiasSlope[XAXIS] = 0.0f; eepromConfig.accelTCBiasSlope[YAXIS] = 0.0f; eepromConfig.accelTCBiasSlope[ZAXIS] = 0.0f; /////////////////////////////// eepromConfig.accelTCBiasIntercept[XAXIS] = 0.0f; eepromConfig.accelTCBiasIntercept[YAXIS] = 0.0f; eepromConfig.accelTCBiasIntercept[ZAXIS] = 0.0f; /////////////////////////////// eepromConfig.gyroTCBiasSlope[ROLL ] = 0.0f; eepromConfig.gyroTCBiasSlope[PITCH] = 0.0f; eepromConfig.gyroTCBiasSlope[YAW ] = 0.0f; /////////////////////////////// eepromConfig.gyroTCBiasIntercept[ROLL ] = 0.0f; eepromConfig.gyroTCBiasIntercept[PITCH] = 0.0f; eepromConfig.gyroTCBiasIntercept[YAW ] = 0.0f; /////////////////////////////// eepromConfig.magBias[XAXIS] = 0.0f; eepromConfig.magBias[YAXIS] = 0.0f; eepromConfig.magBias[ZAXIS] = 0.0f; /////////////////////////////// eepromConfig.accelCutoff = 1.0f; /////////////////////////////// eepromConfig.KpAcc = 5.0f; // proportional gain governs rate of convergence to accelerometer eepromConfig.KiAcc = 0.0f; // integral gain governs rate of convergence of gyroscope biases eepromConfig.KpMag = 5.0f; // proportional gain governs rate of convergence to magnetometer eepromConfig.KiMag = 0.0f; // integral gain governs rate of convergence of gyroscope biases /////////////////////////////// eepromConfig.compFilterA = 2.000f; eepromConfig.compFilterB = 1.000f; /////////////////////////////////// eepromConfig.dlpfSetting = BITS_DLPF_CFG_98HZ; /////////////////////////////////// eepromConfig.rateScaling = 300.0 / 180000.0 * PI; // Stick to rate scaling for 300 DPS eepromConfig.attitudeScaling = 60.0 / 180000.0 * PI; // Stick to att scaling for 60 degrees eepromConfig.nDotEdotScaling = 0.009f; // Stick to nDot/eDot scaling (9 mps)/(1000 RX PWM Steps) = 0.009 eepromConfig.hDotScaling = 0.003f; // Stick to hDot scaling (3 mps)/(1000 RX PWM Steps) = 0.003 /////////////////////////////// eepromConfig.receiverType = SPEKTRUM; eepromConfig.slaveSpektrum = false; parseRcChannels("TAER2134"); eepromConfig.escPwmRate = 450; eepromConfig.servoPwmRate = 50; eepromConfig.mixerConfiguration = MIXERTYPE_QUADX; eepromConfig.yawDirection = 1.0f; eepromConfig.midCommand = 3000.0f; eepromConfig.minCheck = (float)(MINCOMMAND + 200); eepromConfig.maxCheck = (float)(MAXCOMMAND - 200); eepromConfig.minThrottle = (float)(MINCOMMAND + 200); eepromConfig.maxThrottle = (float)(MAXCOMMAND); eepromConfig.PID[ROLL_RATE_PID].B = 1.0f; eepromConfig.PID[ROLL_RATE_PID].P = 250.0f; eepromConfig.PID[ROLL_RATE_PID].I = 100.0f; eepromConfig.PID[ROLL_RATE_PID].D = 0.0f; eepromConfig.PID[ROLL_RATE_PID].iTerm = 0.0f; eepromConfig.PID[ROLL_RATE_PID].windupGuard = 100.0f; // PWMs eepromConfig.PID[ROLL_RATE_PID].lastDcalcValue = 0.0f; eepromConfig.PID[ROLL_RATE_PID].lastDterm = 0.0f; eepromConfig.PID[ROLL_RATE_PID].lastLastDterm = 0.0f; eepromConfig.PID[ROLL_RATE_PID].dErrorCalc = D_ERROR; eepromConfig.PID[ROLL_RATE_PID].type = OTHER; eepromConfig.PID[PITCH_RATE_PID].B = 1.0f; eepromConfig.PID[PITCH_RATE_PID].P = 250.0f; eepromConfig.PID[PITCH_RATE_PID].I = 100.0f; eepromConfig.PID[PITCH_RATE_PID].D = 0.0f; eepromConfig.PID[PITCH_RATE_PID].iTerm = 0.0f; eepromConfig.PID[PITCH_RATE_PID].windupGuard = 100.0f; // PWMs eepromConfig.PID[PITCH_RATE_PID].lastDcalcValue = 0.0f; eepromConfig.PID[PITCH_RATE_PID].lastDterm = 0.0f; eepromConfig.PID[PITCH_RATE_PID].lastLastDterm = 0.0f; eepromConfig.PID[PITCH_RATE_PID].dErrorCalc = D_ERROR; eepromConfig.PID[PITCH_RATE_PID].type = OTHER; eepromConfig.PID[YAW_RATE_PID].B = 1.0f; eepromConfig.PID[YAW_RATE_PID].P = 350.0f; eepromConfig.PID[YAW_RATE_PID].I = 100.0f; eepromConfig.PID[YAW_RATE_PID].D = 0.0f; eepromConfig.PID[YAW_RATE_PID].iTerm = 0.0f; eepromConfig.PID[YAW_RATE_PID].windupGuard = 100.0f; // PWMs eepromConfig.PID[YAW_RATE_PID].lastDcalcValue = 0.0f; eepromConfig.PID[YAW_RATE_PID].lastDterm = 0.0f; eepromConfig.PID[YAW_RATE_PID].lastLastDterm = 0.0f; eepromConfig.PID[YAW_RATE_PID].dErrorCalc = D_ERROR; eepromConfig.PID[YAW_RATE_PID].type = OTHER; eepromConfig.PID[ROLL_ATT_PID].B = 1.0f; eepromConfig.PID[ROLL_ATT_PID].P = 2.0f; eepromConfig.PID[ROLL_ATT_PID].I = 0.0f; eepromConfig.PID[ROLL_ATT_PID].D = 0.0f; eepromConfig.PID[ROLL_ATT_PID].iTerm = 0.0f; eepromConfig.PID[ROLL_ATT_PID].windupGuard = 0.5f; // radians/sec eepromConfig.PID[ROLL_ATT_PID].lastDcalcValue = 0.0f; eepromConfig.PID[ROLL_ATT_PID].lastDterm = 0.0f; eepromConfig.PID[ROLL_ATT_PID].lastLastDterm = 0.0f; eepromConfig.PID[ROLL_ATT_PID].dErrorCalc = D_ERROR; eepromConfig.PID[ROLL_ATT_PID].type = ANGULAR; eepromConfig.PID[PITCH_ATT_PID].B = 1.0f; eepromConfig.PID[PITCH_ATT_PID].P = 2.0f; eepromConfig.PID[PITCH_ATT_PID].I = 0.0f; eepromConfig.PID[PITCH_ATT_PID].D = 0.0f; eepromConfig.PID[PITCH_ATT_PID].iTerm = 0.0f; eepromConfig.PID[PITCH_ATT_PID].windupGuard = 0.5f; // radians/sec eepromConfig.PID[PITCH_ATT_PID].lastDcalcValue = 0.0f; eepromConfig.PID[PITCH_ATT_PID].lastDterm = 0.0f; eepromConfig.PID[PITCH_ATT_PID].lastLastDterm = 0.0f; eepromConfig.PID[PITCH_ATT_PID].dErrorCalc = D_ERROR; eepromConfig.PID[PITCH_ATT_PID].type = ANGULAR; eepromConfig.PID[HEADING_PID].B = 1.0f; eepromConfig.PID[HEADING_PID].P = 3.0f; eepromConfig.PID[HEADING_PID].I = 0.0f; eepromConfig.PID[HEADING_PID].D = 0.0f; eepromConfig.PID[HEADING_PID].iTerm = 0.0f; eepromConfig.PID[HEADING_PID].windupGuard = 0.5f; // radians/sec eepromConfig.PID[HEADING_PID].lastDcalcValue = 0.0f; eepromConfig.PID[HEADING_PID].lastDterm = 0.0f; eepromConfig.PID[HEADING_PID].lastLastDterm = 0.0f; eepromConfig.PID[HEADING_PID].dErrorCalc = D_ERROR; eepromConfig.PID[HEADING_PID].type = ANGULAR; eepromConfig.PID[NDOT_PID].B = 1.0f; eepromConfig.PID[NDOT_PID].P = 3.0f; eepromConfig.PID[NDOT_PID].I = 0.0f; eepromConfig.PID[NDOT_PID].D = 0.0f; eepromConfig.PID[NDOT_PID].iTerm = 0.0f; eepromConfig.PID[NDOT_PID].windupGuard = 0.5f; eepromConfig.PID[NDOT_PID].lastDcalcValue = 0.0f; eepromConfig.PID[NDOT_PID].lastDterm = 0.0f; eepromConfig.PID[NDOT_PID].lastLastDterm = 0.0f; eepromConfig.PID[NDOT_PID].dErrorCalc = D_ERROR; eepromConfig.PID[NDOT_PID].type = OTHER; eepromConfig.PID[EDOT_PID].B = 1.0f; eepromConfig.PID[EDOT_PID].P = 3.0f; eepromConfig.PID[EDOT_PID].I = 0.0f; eepromConfig.PID[EDOT_PID].D = 0.0f; eepromConfig.PID[EDOT_PID].iTerm = 0.0f; eepromConfig.PID[EDOT_PID].windupGuard = 0.5f; eepromConfig.PID[EDOT_PID].lastDcalcValue = 0.0f; eepromConfig.PID[EDOT_PID].lastDterm = 0.0f; eepromConfig.PID[EDOT_PID].lastLastDterm = 0.0f; eepromConfig.PID[EDOT_PID].dErrorCalc = D_ERROR; eepromConfig.PID[EDOT_PID].type = OTHER; eepromConfig.PID[HDOT_PID].B = 1.0f; eepromConfig.PID[HDOT_PID].P = 2.0f; eepromConfig.PID[HDOT_PID].I = 0.0f; eepromConfig.PID[HDOT_PID].D = 0.0f; eepromConfig.PID[HDOT_PID].iTerm = 0.0f; eepromConfig.PID[HDOT_PID].windupGuard = 5.0f; eepromConfig.PID[HDOT_PID].lastDcalcValue = 0.0f; eepromConfig.PID[HDOT_PID].lastDterm = 0.0f; eepromConfig.PID[HDOT_PID].lastLastDterm = 0.0f; eepromConfig.PID[HDOT_PID].dErrorCalc = D_ERROR; eepromConfig.PID[HDOT_PID].type = OTHER; eepromConfig.PID[N_PID].B = 1.0f; eepromConfig.PID[N_PID].P = 3.0f; eepromConfig.PID[N_PID].I = 0.0f; eepromConfig.PID[N_PID].D = 0.0f; eepromConfig.PID[N_PID].iTerm = 0.0f; eepromConfig.PID[N_PID].windupGuard = 0.5f; eepromConfig.PID[N_PID].lastDcalcValue = 0.0f; eepromConfig.PID[N_PID].lastDterm = 0.0f; eepromConfig.PID[N_PID].lastLastDterm = 0.0f; eepromConfig.PID[N_PID].dErrorCalc = D_ERROR; eepromConfig.PID[N_PID].type = OTHER; eepromConfig.PID[E_PID].B = 1.0f; eepromConfig.PID[E_PID].P = 3.0f; eepromConfig.PID[E_PID].I = 0.0f; eepromConfig.PID[E_PID].D = 0.0f; eepromConfig.PID[E_PID].iTerm = 0.0f; eepromConfig.PID[E_PID].windupGuard = 0.5f; eepromConfig.PID[E_PID].lastDcalcValue = 0.0f; eepromConfig.PID[E_PID].lastDterm = 0.0f; eepromConfig.PID[E_PID].lastLastDterm = 0.0f; eepromConfig.PID[E_PID].dErrorCalc = D_ERROR; eepromConfig.PID[E_PID].type = OTHER; eepromConfig.PID[H_PID].B = 1.0f; eepromConfig.PID[H_PID].P = 2.0f; eepromConfig.PID[H_PID].I = 0.0f; eepromConfig.PID[H_PID].D = 0.0f; eepromConfig.PID[H_PID].iTerm = 0.0f; eepromConfig.PID[H_PID].windupGuard = 5.0f; eepromConfig.PID[H_PID].lastDcalcValue = 0.0f; eepromConfig.PID[H_PID].lastDterm = 0.0f; eepromConfig.PID[H_PID].lastLastDterm = 0.0f; eepromConfig.PID[H_PID].dErrorCalc = D_ERROR; eepromConfig.PID[H_PID].type = OTHER; eepromConfig.magVar = 9.033333f * D2R; // Albuquerque, NM Mag Var 9 degrees 2 minutes (+ East, - West) eepromConfig.batteryCells = 3; eepromConfig.voltageMonitorScale = 11.0f / 1.0f; eepromConfig.voltageMonitorBias = 0.0f; eepromConfig.armCount = 50; eepromConfig.disarmCount = 0; eepromConfig.activeTelemetry = 0; eepromConfig.verticalVelocityHoldOnly = true; writeEEPROM(); } }
void checkFirstTime(bool eepromReset) { uint8_t test_val; test_val = *(uint8_t *)FLASH_WRITE_EEPROM_ADDR; if (eepromReset || test_val != checkNewEEPROMConf) { // Default settings eepromConfig.version = checkNewEEPROMConf; /////////////////////////////// eepromConfig.accelBiasMPU[XAXIS] = 0.0f; eepromConfig.accelBiasMPU[YAXIS] = 0.0f; eepromConfig.accelBiasMPU[ZAXIS] = 0.0f; /////////////////////////////// eepromConfig.accelScaleFactorMPU[XAXIS] = 0.00119708f; // (1/8192) * 9.8065 (8192 LSB = 1 G) eepromConfig.accelScaleFactorMPU[YAXIS] = 0.00119708f; // (1/8192) * 9.8065 (8192 LSB = 1 G) eepromConfig.accelScaleFactorMPU[ZAXIS] = 0.00119708f; // (1/8192) * 9.8065 (8192 LSB = 1 G) /////////////////////////////// eepromConfig.accelTCBiasSlope[XAXIS] = 0.0f; eepromConfig.accelTCBiasSlope[YAXIS] = 0.0f; eepromConfig.accelTCBiasSlope[ZAXIS] = 0.0f; /////////////////////////////// eepromConfig.accelTCBiasIntercept[XAXIS] = 0.0f; eepromConfig.accelTCBiasIntercept[YAXIS] = 0.0f; eepromConfig.accelTCBiasIntercept[ZAXIS] = 0.0f; /////////////////////////////// eepromConfig.gyroTCBiasSlope[ROLL ] = 0.0f; eepromConfig.gyroTCBiasSlope[PITCH] = 0.0f; eepromConfig.gyroTCBiasSlope[YAW ] = 0.0f; /////////////////////////////// eepromConfig.gyroTCBiasIntercept[ROLL ] = 0.0f; eepromConfig.gyroTCBiasIntercept[PITCH] = 0.0f; eepromConfig.gyroTCBiasIntercept[YAW ] = 0.0f; /////////////////////////////// eepromConfig.magBias[XAXIS] = 0.0f; // Internal Mag Bias eepromConfig.magBias[YAXIS] = 0.0f; // Internal Mag Bias eepromConfig.magBias[ZAXIS] = 0.0f; // Internal Mag Bias eepromConfig.magBias[XAXIS + 3] = 0.0f; // External Mag Bias eepromConfig.magBias[YAXIS + 3] = 0.0f; // External Mag Bias eepromConfig.magBias[ZAXIS + 3] = 0.0f; // External Mag Bias /////////////////////////////// eepromConfig.accelCutoff = 0.25f; /////////////////////////////// eepromConfig.KpAcc = 1.0f; // proportional gain governs rate of convergence to accelerometer eepromConfig.KiAcc = 0.0f; // integral gain governs rate of convergence of gyroscope biases eepromConfig.KpMag = 5.0f; // proportional gain governs rate of convergence to magnetometer eepromConfig.KiMag = 0.0f; // integral gain governs rate of convergence of gyroscope biases /////////////////////////////// eepromConfig.compFilterA = 2.0f; eepromConfig.compFilterB = 1.0f; /////////////////////////////// eepromConfig.dlpfSetting = BITS_DLPF_CFG_98HZ; /////////////////////////////////// eepromConfig.sensorOrientation = 1; // No rotation /////////////////////////////////// eepromConfig.rollAndPitchRateScaling = 200.0 / 180000.0 * PI; // Stick to rate scaling for 100 DPS eepromConfig.yawRateScaling = 200.0 / 180000.0 * PI; // Stick to rate scaling for 100 DPS eepromConfig.attitudeScaling = 60.0 / 180000.0 * PI; // Stick to att scaling for 60 degrees eepromConfig.nDotEdotScaling = 0.009f; // Stick to nDot/eDot scaling (9 mps)/(1000 RX PWM Steps) = 0.009 eepromConfig.hDotScaling = 0.003f; // Stick to hDot scaling (3 mps)/(1000 RX PWM Steps) = 0.003 /////////////////////////////// eepromConfig.receiverType = PPM;//PWM; eepromConfig.ppmChannels = 9; eepromConfig.slaveSpektrum = false; parseRcChannels("TAER12345678"); eepromConfig.escPwmRate = 450; eepromConfig.servoPwmRate = 50; eepromConfig.mixerConfiguration = MIXERTYPE_QUADX47;//MIXERTYPE_TRI; eepromConfig.yawDirection = 1.0f; eepromConfig.triYawServoPwmRate = 50; eepromConfig.triYawServoMin = 2000.0f; eepromConfig.triYawServoMid = 3000.0f; eepromConfig.triYawServoMax = 4000.0f; eepromConfig.triCopterYawCmd500HzLowPassTau = 0.05f; // Free Mix Defaults to Quad X eepromConfig.freeMixMotors = 4; eepromConfig.freeMix[0][ROLL ] = 1.0f; eepromConfig.freeMix[0][PITCH] = -1.0f; eepromConfig.freeMix[0][YAW ] = -1.0f; eepromConfig.freeMix[0][THROTTLE] = 1.0f; eepromConfig.freeMix[1][ROLL ] = -1.0f; eepromConfig.freeMix[1][PITCH] = -1.0f; eepromConfig.freeMix[1][YAW ] = 1.0f; eepromConfig.freeMix[1][THROTTLE] = 1.0f; eepromConfig.freeMix[2][ROLL ] = -1.0f; eepromConfig.freeMix[2][PITCH] = 1.0f; eepromConfig.freeMix[2][YAW ] = -1.0f; eepromConfig.freeMix[2][THROTTLE] = 1.0f; eepromConfig.freeMix[3][ROLL ] = 1.0f; eepromConfig.freeMix[3][PITCH] = 1.0f; eepromConfig.freeMix[3][YAW ] = 1.0f; eepromConfig.freeMix[3][THROTTLE] = 1.0f; eepromConfig.freeMix[4][ROLL ] = 0.0f; eepromConfig.freeMix[4][PITCH] = 0.0f; eepromConfig.freeMix[4][YAW ] = 0.0f; eepromConfig.freeMix[4][THROTTLE] = 0.0f; eepromConfig.freeMix[5][ROLL ] = 0.0f; eepromConfig.freeMix[5][PITCH] = 0.0f; eepromConfig.freeMix[5][YAW ] = 0.0f; eepromConfig.freeMix[5][THROTTLE] = 0.0f; eepromConfig.freeMix[6][ROLL ] = 0.0f; eepromConfig.freeMix[6][PITCH] = 0.0f; eepromConfig.freeMix[6][YAW ] = 0.0f; eepromConfig.freeMix[6][THROTTLE] = 0.0f; eepromConfig.freeMix[7][ROLL ] = 0.0f; eepromConfig.freeMix[7][PITCH] = 0.0f; eepromConfig.freeMix[7][YAW ] = 0.0f; eepromConfig.freeMix[7][THROTTLE] = 0.0f; eepromConfig.rollAttAltCompensationGain = 1.0f; eepromConfig.rollAttAltCompensationLimit = 0.0f * D2R; eepromConfig.pitchAttAltCompensationGain = 1.0f; eepromConfig.pitchAttAltCompensationLimit = 0.0f * D2R; eepromConfig.midCommand = 3043.0f;//3000.0f; eepromConfig.minCheck = (float)(MINCOMMAND + 200); eepromConfig.maxCheck = (float)(MAXCOMMAND - 200); eepromConfig.minThrottle = (float)(MINCOMMAND + 200); eepromConfig.maxThrottle = (float)(MAXCOMMAND); /////////////////////////////// eepromConfig.PID[ROLL_RATE_PID].P = 250.0f; eepromConfig.PID[ROLL_RATE_PID].I = 100.0f; eepromConfig.PID[ROLL_RATE_PID].D = 0.0f; eepromConfig.PID[ROLL_RATE_PID].Limit = 1000.0f * eepromConfig.rollAndPitchRateScaling * eepromConfig.PID[ROLL_RATE_PID].P ; eepromConfig.PID[ROLL_RATE_PID].integratorState = 0.0f; eepromConfig.PID[ROLL_RATE_PID].filterState = 0.0f; eepromConfig.PID[ROLL_RATE_PID].prevResetState = false; eepromConfig.PID[PITCH_RATE_PID].P = 250.0f; eepromConfig.PID[PITCH_RATE_PID].I = 100.0f; eepromConfig.PID[PITCH_RATE_PID].D = 0.0f; eepromConfig.PID[PITCH_RATE_PID].Limit = 1000.0f * eepromConfig.rollAndPitchRateScaling * eepromConfig.PID[PITCH_RATE_PID].P; eepromConfig.PID[PITCH_RATE_PID].integratorState = 0.0f; eepromConfig.PID[PITCH_RATE_PID].filterState = 0.0f; eepromConfig.PID[PITCH_RATE_PID].prevResetState = false; eepromConfig.PID[YAW_RATE_PID].P = 350.0f; eepromConfig.PID[YAW_RATE_PID].I = 100.0f; eepromConfig.PID[YAW_RATE_PID].D = 0.0f; eepromConfig.PID[YAW_RATE_PID].Limit = 1000.0f * eepromConfig.yawRateScaling * eepromConfig.PID[YAW_RATE_PID].P; eepromConfig.PID[YAW_RATE_PID].integratorState = 0.0f; eepromConfig.PID[YAW_RATE_PID].filterState = 0.0f; eepromConfig.PID[YAW_RATE_PID].prevResetState = false; eepromConfig.PID[ROLL_ATT_PID].P = 2.0f; eepromConfig.PID[ROLL_ATT_PID].I = 0.0f; eepromConfig.PID[ROLL_ATT_PID].D = 0.0f; eepromConfig.PID[ROLL_ATT_PID].Limit = 1000.0f * eepromConfig.attitudeScaling * eepromConfig.PID[ROLL_ATT_PID].P; eepromConfig.PID[ROLL_ATT_PID].integratorState = 0.0f; eepromConfig.PID[ROLL_ATT_PID].filterState = 0.0f; eepromConfig.PID[ROLL_ATT_PID].prevResetState = false; eepromConfig.PID[PITCH_ATT_PID].P = 2.0f; eepromConfig.PID[PITCH_ATT_PID].I = 0.0f; eepromConfig.PID[PITCH_ATT_PID].D = 0.0f; eepromConfig.PID[PITCH_ATT_PID].Limit = 1000.0f * eepromConfig.attitudeScaling * eepromConfig.PID[PITCH_ATT_PID].P; eepromConfig.PID[PITCH_ATT_PID].integratorState = 0.0f; eepromConfig.PID[PITCH_ATT_PID].filterState = 0.0f; eepromConfig.PID[PITCH_ATT_PID].prevResetState = false; eepromConfig.PID[HEADING_PID].P = 3.0f; eepromConfig.PID[HEADING_PID].I = 0.0f; eepromConfig.PID[HEADING_PID].D = 0.0f; eepromConfig.PID[HEADING_PID].Limit = 90.0f * D2R; eepromConfig.PID[HEADING_PID].integratorState = 0.0f; eepromConfig.PID[HEADING_PID].filterState = 0.0f; eepromConfig.PID[HEADING_PID].prevResetState = false; eepromConfig.PID[NDOT_PID].P = 3.0f; eepromConfig.PID[NDOT_PID].I = 0.0f; eepromConfig.PID[NDOT_PID].D = 0.0f; eepromConfig.PID[NDOT_PID].Limit = 1000.0f * eepromConfig.nDotEdotScaling * eepromConfig.PID[NDOT_PID].P; eepromConfig.PID[NDOT_PID].integratorState = 0.0f; eepromConfig.PID[NDOT_PID].filterState = 0.0f; eepromConfig.PID[NDOT_PID].prevResetState = false; eepromConfig.PID[EDOT_PID].P = 3.0f; eepromConfig.PID[EDOT_PID].I = 0.0f; eepromConfig.PID[EDOT_PID].D = 0.0f; eepromConfig.PID[EDOT_PID].Limit = 1000.0f * eepromConfig.nDotEdotScaling * eepromConfig.PID[EDOT_PID].P; eepromConfig.PID[EDOT_PID].integratorState = 0.0f; eepromConfig.PID[EDOT_PID].filterState = 0.0f; eepromConfig.PID[EDOT_PID].prevResetState = false; eepromConfig.PID[HDOT_PID].P = 2.0f; eepromConfig.PID[HDOT_PID].I = 0.0f; eepromConfig.PID[HDOT_PID].D = 0.0f; eepromConfig.PID[HDOT_PID].Limit = 1000.0f * eepromConfig.hDotScaling * eepromConfig.PID[HDOT_PID].P; eepromConfig.PID[HDOT_PID].integratorState = 0.0f; eepromConfig.PID[HDOT_PID].filterState = 0.0f; eepromConfig.PID[HDOT_PID].prevResetState = false; eepromConfig.PID[N_PID].P = 3.0f; eepromConfig.PID[N_PID].I = 0.0f; eepromConfig.PID[N_PID].D = 0.0f; eepromConfig.PID[N_PID].Limit = 10.0f; eepromConfig.PID[N_PID].integratorState = 0.0f; eepromConfig.PID[N_PID].filterState = 0.0f; eepromConfig.PID[N_PID].prevResetState = false; eepromConfig.PID[E_PID].P = 3.0f; eepromConfig.PID[E_PID].I = 0.0f; eepromConfig.PID[E_PID].D = 0.0f; eepromConfig.PID[E_PID].Limit = 10.0f; eepromConfig.PID[E_PID].integratorState = 0.0f; eepromConfig.PID[E_PID].filterState = 0.0f; eepromConfig.PID[E_PID].prevResetState = false; eepromConfig.PID[H_PID].P = 2.0f; eepromConfig.PID[H_PID].I = 0.0f; eepromConfig.PID[H_PID].D = 0.0f; eepromConfig.PID[H_PID].Limit = 10.0f; eepromConfig.PID[H_PID].integratorState = 0.0f; eepromConfig.PID[H_PID].filterState = 0.0f; eepromConfig.PID[H_PID].prevResetState = false; /////////////////////////////// eepromConfig.osdEnabled = false;//true; eepromConfig.defaultVideoStandard = PAL; eepromConfig.metricUnits = true; eepromConfig.osdDisplayAlt = true; eepromConfig.osdDisplayAltRow = 15; eepromConfig.osdDisplayAltCol = 1; eepromConfig.osdDisplayAltHoldState = false; eepromConfig.osdDisplayAH = false; // DO NOT SET BOTH TO TRUE eepromConfig.osdDisplayAtt = true; eepromConfig.osdDisplayHdg = false; eepromConfig.osdDisplayHdgRow = 1; eepromConfig.osdDisplayHdgCol = 13; eepromConfig.osdDisplayHdgBar = true; eepromConfig.osdDisplayHdgBarRow = 14; eepromConfig.osdDisplayHdgBarCol = 10; eepromConfig.osdDisplayVoltage = true; eepromConfig.osdDisplayVoltageRow = 1; eepromConfig.osdDisplayVoltageCol = 1; eepromConfig.osdDisplayCurrent = true; eepromConfig.osdDisplayCurrentRow = 1; eepromConfig.osdDisplayCurrentCol = 8; eepromConfig.osdDisplayThrot = true; eepromConfig.osdDisplayThrotRow = 15; eepromConfig.osdDisplayThrotCol = 25; eepromConfig.osdDisplayTimer = true; eepromConfig.osdDisplayTimerRow = 0; eepromConfig.osdDisplayTimerCol = 23; eepromConfig.osdDisplayRSSI = true; eepromConfig.osdDisplayRSSIRow = 1; eepromConfig.osdDisplayRSSICol = 24; /////////////////////////////// // The default agl pin and scale factor are // for the MB1200 ultrasonic ranger. The // MB1200 is connected to the RNG input (ADC1) // on the AQ32 V2 hardware and is supplied // with 3.3 volts. If supplied with 5 volts, // the analog output of the MB1200 can exceed // 3.3 volts by 0.1 volts. It is not known if // this will damage the analog input or not. eepromConfig.aglPin = 1; eepromConfig.aglScale = 3.125f; // mV to meters, 3.2 mV = 1 cm eepromConfig.aglBias = 0.0f; // Current monitoring defaults to off. // The default scale factor of 27.322404 // is for the 90 amp AttoPilot sensor. It // is a nominal value and slight adjustment // may be required. eepromConfig.currentMonitoring = true;//false; eepromConfig.currentMonitorPin = 5;//6; eepromConfig.currentMonitorScale = 27.322404f; // For 90 amp AttoPilot Sensor eepromConfig.currentMonitorBias = 0.0f; eepromConfig.rssiPPM = true;//false; eepromConfig.rssiPin = 9;//5; eepromConfig.rssiMax = eepromConfig.minCheck;//3450; eepromConfig.rssiMin = eepromConfig.maxCheck;//10; eepromConfig.rssiWarning = 25; // The default voltage monitor pin and scale factor // are for the AQ32 onboard resistor divider. To use // an external voltage monitor, the ADC pin and scale // factor must be changed. The onboard resistor // divider requires a 7.666667 scale factor, the 90 // amp AttoPilot sensor requires a 15.701052 scale // factor. These are nominal values, and slight // adjustment may be required. eepromConfig.voltageMonitorPin = 9;//7; eepromConfig.voltageMonitorScale = 15.696969f;//7.666667f; eepromConfig.voltageMonitorBias = 0.0f; eepromConfig.batteryCells = 4;//3; eepromConfig.batteryLow = 3.30f; eepromConfig.batteryVeryLow = 3.20f; eepromConfig.batteryMaxLow = 3.10f; /////////////////////////////// eepromConfig.armCount = 35;//50; eepromConfig.disarmCount = 5;//0; /////////////////////////////// eepromConfig.activeTelemetry = 0; eepromConfig.mavlinkEnabled = false; eepromConfig.verticalVelocityHoldOnly = true; eepromConfig.externalHMC5883 = 0; eepromConfig.externalMS5611 = false; /////////////////////////////// writeEEPROM(); } }
void receiverCLI() { char rcOrderString[13]; float tempFloat; uint8_t tempChannels = 0; uint16_t tempMax = 0; uint16_t tempMin = 0; uint8_t tempPin = 0; uint8_t tempWarn = 0; uint8_t index; uint8_t receiverQuery = 'x'; uint8_t validQuery = false; cliBusy = true; cliPortPrint("\nEntering Receiver CLI....\n\n"); while(true) { cliPortPrint("Receiver CLI -> "); while ((cliPortAvailable() == false) && (validQuery == false)); if (validQuery == false) receiverQuery = cliPortRead(); cliPortPrint("\n"); switch(receiverQuery) { /////////////////////////// case 'a': // Receiver Configuration cliPortPrint("\nReceiver Type: "); if (eepromConfig.receiverType == PPM) cliPortPrint(" PPM\n"); else if (eepromConfig.receiverType == PWM) cliPortPrint(" PWM\n"); else if (eepromConfig.receiverType == SPEKTRUM) cliPortPrint("Spektrum\n"); else cliPortPrint("Error...\n"); if (eepromConfig.receiverType == PPM) tempChannels = eepromConfig.ppmChannels; else tempChannels = 8; for (index = 0; index < tempChannels; index++) rcOrderString[eepromConfig.rcMap[index]] = rcChannelLetters[index]; rcOrderString[index] = '\0'; cliPortPrintF("Current RC Channel Assignment: %12s\n", rcOrderString); if (eepromConfig.receiverType == PPM) cliPortPrintF("Number of serial PWM channels %2d\n", eepromConfig.ppmChannels); cliPortPrintF("Mid Command: %4ld\n", (uint16_t)eepromConfig.midCommand); cliPortPrintF("Min Check: %4ld\n", (uint16_t)eepromConfig.minCheck); cliPortPrintF("Max Check: %4ld\n", (uint16_t)eepromConfig.maxCheck); cliPortPrintF("Min Throttle: %4ld\n", (uint16_t)eepromConfig.minThrottle); cliPortPrintF("Max Thottle: %4ld\n\n", (uint16_t)eepromConfig.maxThrottle); tempFloat = eepromConfig.rollAndPitchRateScaling * 180000.0 / PI; cliPortPrintF("Max Roll and Pitch Rate Cmd: %6.2f DPS\n", tempFloat); tempFloat = eepromConfig.yawRateScaling * 180000.0 / PI; cliPortPrintF("Max Yaw Rate Cmd: %6.2f DPS\n", tempFloat); tempFloat = eepromConfig.attitudeScaling * 180000.0 / PI; cliPortPrintF("Max Attitude Cmd: %6.2f Degrees\n\n", tempFloat); cliPortPrintF("Arm Delay Count: %3d Frames\n", eepromConfig.armCount); cliPortPrintF("Disarm Delay Count: %3d Frames\n\n", eepromConfig.disarmCount); cliPortPrintF("RSSI via PPM or ADC: %s", eepromConfig.rssiPPM ? "PPM\n" : "ADC\n"); if (eepromConfig.rssiPPM == true) cliPortPrintF("RSSI PPM Channel: %1d\n", eepromConfig.rssiPin); else cliPortPrintF("RSSI ADC Pin: %1d\n", eepromConfig.rssiPin); cliPortPrintF("RSSI Min: %4d\n", eepromConfig.rssiMin); cliPortPrintF("RSSI Max: %4d\n", eepromConfig.rssiMax); cliPortPrintF("RSSI Warning %%: %2d\n\n", eepromConfig.rssiWarning); validQuery = false; break; /////////////////////////// case 'b': // Read Max Rate Values eepromConfig.rollAndPitchRateScaling = readFloatCLI() / 180000.0f * PI; eepromConfig.yawRateScaling = readFloatCLI() / 180000.0f * PI; receiverQuery = 'a'; validQuery = true; break; /////////////////////////// case 'c': // Read Max Attitude Value eepromConfig.attitudeScaling = readFloatCLI() / 180000 * PI; receiverQuery = 'a'; validQuery = true; break; case 'r': // Toggle RSSI between ADC and PPM eepromConfig.rssiPPM = !eepromConfig.rssiPPM; if (eepromConfig.rssiPPM) { // automatically adjust the settings eepromConfig.rssiPin = 9; eepromConfig.rssiMin = eepromConfig.minCheck; eepromConfig.rssiMax = eepromConfig.maxCheck; } else { eepromConfig.rssiPin = 5; // default from config.c eepromConfig.rssiMin = 10; eepromConfig.rssiMax = 3450; } eepromConfig.rssiWarning = 25; receiverQuery = 'a'; validQuery = true; break; /////////////////////////// case 'x': cliPortPrint("\nExiting Receiver CLI....\n\n"); cliBusy = false; return; break; /////////////////////////// case 'A': // Read RX Input Type eepromConfig.receiverType = (uint8_t)readFloatCLI(); cliPortPrint( "\nReceiver Type Changed....\n"); cliPortPrint("\nSystem Resetting....\n"); delay(100); writeEEPROM(); systemReset(false); break; /////////////////////////// case 'B': // Read RC Control Order readStringCLI( rcOrderString, 12 ); parseRcChannels( rcOrderString ); receiverQuery = 'a'; validQuery = true; break; /////////////////////////// case 'E': // Read RC Control Points eepromConfig.midCommand = readFloatCLI(); eepromConfig.minCheck = readFloatCLI(); eepromConfig.maxCheck = readFloatCLI(); eepromConfig.minThrottle = readFloatCLI(); eepromConfig.maxThrottle = readFloatCLI(); receiverQuery = 'a'; validQuery = true; break; /////////////////////////// case 'F': // Read Arm/Disarm Counts eepromConfig.armCount = (uint8_t)readFloatCLI(); eepromConfig.disarmCount = (uint8_t)readFloatCLI(); receiverQuery = 'a'; validQuery = true; break; /////////////////////////// case 'G': // Read number of PPM Channels tempChannels = (uint8_t)readFloatCLI(); if ((tempChannels < 8) || (tempChannels > 12)) { cliPortPrintF("\nValid number of channels are 8 to 12\n"); cliPortPrintF("You entered %2d\n\n", tempChannels); } else eepromConfig.ppmChannels = tempChannels; receiverQuery = 'a'; validQuery = true; break; /////////////////////////// case 'R': // RSSI pin/min/max/warning tempPin = readFloatCLI(); tempMin = readFloatCLI(); tempMax = readFloatCLI(); tempWarn = readFloatCLI(); if (eepromConfig.rssiPPM) { if ((tempPin < 0) || (tempPin > eepromConfig.ppmChannels)) { cliPortPrintF("Invalid RSSI PPM channel number, valid numbers are 0-%2d\n", eepromConfig.ppmChannels); cliPortPrintF("You entered %2d, please try again\n", tempPin); receiverQuery = '?'; validQuery = false; break; } } else { if ((tempPin < 1) || (tempPin > 6)) { cliPortPrintF("Invalid RSSI Pin number, valid numbers are 1-6\n"); cliPortPrintF("You entered %2d, please try again\n", tempPin); receiverQuery = '?'; validQuery = false; break; } } eepromConfig.rssiPin = tempPin; eepromConfig.rssiMin = tempMin; eepromConfig.rssiMax = tempMax; eepromConfig.rssiWarning = tempWarn; receiverQuery = 'a'; validQuery = true; break; /////////////////////////// case 'W': // Write EEPROM Parameters cliPortPrint("\nWriting EEPROM Parameters....\n\n"); writeEEPROM(); validQuery = false; break; /////////////////////////// case '?': cliPortPrint("\n"); cliPortPrint("'a' Receiver Configuration Data 'A' Set RX Input Type AX, 0=PPM, 1=PWM, 2=Spektrum\n"); cliPortPrint("'b' Set Maximum Rate Commands 'B' Set RC Control Order BTAER12345678\n"); cliPortPrint("'c' Set Maximum Attitude Command\n"); cliPortPrint(" 'E' Set RC Control Points EmidCmd;minChk;maxChk;minThrot;maxThrot\n"); cliPortPrint(" 'F' Set Arm/Disarm Counts FarmCount;disarmCount\n"); cliPortPrint(" 'G' Set number of serial PWM channels GnumChannels\n"); cliPortPrint("'r' Toggle RSSI between PPM/ADC 'R' Set RSSI Config RPin;Min;Max;Warning\n"); cliPortPrint(" 'W' Write EEPROM Parameters\n"); cliPortPrint("'x' Exit Receiver CLI '?' Command Summary\n\n"); break; /////////////////////////// } } }
// Default settings static void resetConf(void) { int i; int8_t servoRates[8] = { 30, 30, 100, 100, 100, 100, 100, 100 }; // Clear all configuration memset(&mcfg, 0, sizeof(master_t)); memset(&cfg, 0, sizeof(config_t)); mcfg.version = EEPROM_CONF_VERSION; mcfg.mixerConfiguration = MULTITYPE_QUADX; featureClearAll(); #ifdef CJMCU featureSet(FEATURE_PPM); #else featureSet(FEATURE_VBAT); #endif // global settings mcfg.current_profile = 0; // default profile mcfg.gyro_cmpf_factor = 600; // default MWC mcfg.gyro_cmpfm_factor = 250; // default MWC mcfg.gyro_lpf = 42; // supported by all gyro drivers now. In case of ST gyro, will default to 32Hz instead mcfg.accZero[0] = 0; mcfg.accZero[1] = 0; mcfg.accZero[2] = 0; mcfg.gyro_align = ALIGN_DEFAULT; mcfg.acc_align = ALIGN_DEFAULT; mcfg.mag_align = ALIGN_DEFAULT; mcfg.board_align_roll = 0; mcfg.board_align_pitch = 0; mcfg.board_align_yaw = 0; mcfg.acc_hardware = ACC_DEFAULT; // default/autodetect mcfg.mag_hardware = MAG_DEFAULT; mcfg.max_angle_inclination = 500; // 50 degrees mcfg.yaw_control_direction = 1; mcfg.moron_threshold = 32; mcfg.currentscale = 400; // for Allegro ACS758LCB-100U (40mV/A) mcfg.vbatscale = 110; mcfg.vbatmaxcellvoltage = 43; mcfg.vbatmincellvoltage = 33; mcfg.vbatwarningcellvoltage = 35; mcfg.power_adc_channel = 0; mcfg.serialrx_type = 0; mcfg.spektrum_sat_bind = 0; mcfg.telemetry_provider = TELEMETRY_PROVIDER_FRSKY; mcfg.telemetry_port = TELEMETRY_PORT_UART; mcfg.telemetry_switch = 0; mcfg.midrc = 1500; mcfg.mincheck = 1100; mcfg.maxcheck = 1900; mcfg.retarded_arm = 0; // disable arm/disarm on roll left/right mcfg.disarm_kill_switch = 1; // AUX disarm independently of throttle value mcfg.fw_althold_dir = 1; // Motor/ESC/Servo mcfg.minthrottle = 1150; mcfg.maxthrottle = 1850; mcfg.mincommand = 1000; mcfg.deadband3d_low = 1406; mcfg.deadband3d_high = 1514; mcfg.neutral3d = 1460; mcfg.deadband3d_throttle = 50; mcfg.motor_pwm_rate = MOTOR_PWM_RATE; mcfg.servo_pwm_rate = 50; // safety features mcfg.auto_disarm_board = 5; // auto disarm after 5 sec if motors not started or disarmed // gps/nav stuff mcfg.gps_type = GPS_NMEA; mcfg.gps_baudrate = GPS_BAUD_115200; // serial (USART1) baudrate mcfg.serial_baudrate = 115200; mcfg.softserial_baudrate = 9600; mcfg.softserial_1_inverted = 0; mcfg.softserial_2_inverted = 0; mcfg.looptime = 3500; mcfg.emf_avoidance = 0; mcfg.rssi_aux_channel = 0; mcfg.rssi_adc_max = 4095; cfg.pidController = 0; cfg.P8[ROLL] = 40; cfg.I8[ROLL] = 30; cfg.D8[ROLL] = 23; cfg.P8[PITCH] = 40; cfg.I8[PITCH] = 30; cfg.D8[PITCH] = 23; cfg.P8[YAW] = 85; cfg.I8[YAW] = 45; cfg.D8[YAW] = 0; cfg.P8[PIDALT] = 50; cfg.I8[PIDALT] = 0; cfg.D8[PIDALT] = 0; cfg.P8[PIDPOS] = 11; // POSHOLD_P * 100; cfg.I8[PIDPOS] = 0; // POSHOLD_I * 100; cfg.D8[PIDPOS] = 0; cfg.P8[PIDPOSR] = 20; // POSHOLD_RATE_P * 10; cfg.I8[PIDPOSR] = 8; // POSHOLD_RATE_I * 100; cfg.D8[PIDPOSR] = 45; // POSHOLD_RATE_D * 1000; cfg.P8[PIDNAVR] = 14; // NAV_P * 10; cfg.I8[PIDNAVR] = 20; // NAV_I * 100; cfg.D8[PIDNAVR] = 80; // NAV_D * 1000; cfg.P8[PIDLEVEL] = 90; cfg.I8[PIDLEVEL] = 10; cfg.D8[PIDLEVEL] = 100; cfg.P8[PIDMAG] = 40; cfg.P8[PIDVEL] = 120; cfg.I8[PIDVEL] = 45; cfg.D8[PIDVEL] = 1; cfg.rcRate8 = 90; cfg.rcExpo8 = 65; cfg.yawRate = 0; cfg.dynThrPID = 0; cfg.tpa_breakpoint = 1500; cfg.thrMid8 = 50; cfg.thrExpo8 = 0; // for (i = 0; i < CHECKBOXITEMS; i++) // cfg.activate[i] = 0; cfg.angleTrim[0] = 0; cfg.angleTrim[1] = 0; cfg.locked_in = 0; cfg.mag_declination = 0; // For example, -6deg 37min, = -637 Japan, format is [sign]dddmm (degreesminutes) default is zero. cfg.acc_lpf_factor = 4; cfg.accz_deadband = 40; cfg.accxy_deadband = 40; cfg.baro_tab_size = 21; cfg.baro_noise_lpf = 0.6f; cfg.baro_cf_vel = 0.985f; cfg.baro_cf_alt = 0.965f; cfg.accz_lpf_cutoff = 5.0f; cfg.acc_unarmedcal = 1; cfg.small_angle = 25; // Radio parseRcChannels("AETR1234"); cfg.deadband = 0; cfg.yawdeadband = 0; cfg.alt_hold_throttle_neutral = 40; cfg.alt_hold_fast_change = 1; cfg.throttle_correction_value = 0; // could 10 with althold or 40 for fpv cfg.throttle_correction_angle = 800; // could be 80.0 deg with atlhold or 45.0 for fpv // Failsafe Variables cfg.failsafe_delay = 10; // 1sec cfg.failsafe_off_delay = 200; // 20sec cfg.failsafe_throttle = 1200; // decent default which should always be below hover throttle for people. cfg.failsafe_detect_threshold = 985; // any of first 4 channels below this value will trigger failsafe // servos for (i = 0; i < 8; i++) { cfg.servoConf[i].min = 1020; cfg.servoConf[i].max = 2000; cfg.servoConf[i].middle = 1500; cfg.servoConf[i].rate = servoRates[i]; } cfg.yaw_direction = 1; cfg.tri_unarmed_servo = 1; // gimbal cfg.gimbal_flags = GIMBAL_NORMAL; // gps/nav stuff cfg.gps_wp_radius = 200; cfg.gps_lpf = 20; cfg.nav_slew_rate = 30; cfg.nav_controls_heading = 1; cfg.nav_speed_min = 100; cfg.nav_speed_max = 300; cfg.ap_mode = 40; // fw stuff cfg.fw_roll_throw = 0.5f; cfg.fw_pitch_throw = 0.5f; cfg.fw_gps_maxcorr = 20; cfg.fw_gps_rudder = 15; cfg.fw_gps_maxclimb = 15; cfg.fw_gps_maxdive = 15; cfg.fw_climb_throttle = 1900; cfg.fw_cruise_throttle = 1500; cfg.fw_idle_throttle = 1300; cfg.fw_scaler_throttle = 8; cfg.fw_roll_comp = 1; // control stuff mcfg.reboot_character = 'R'; // custom mixer. clear by defaults. for (i = 0; i < MAX_MOTORS; i++) mcfg.customMixer[i].throttle = 0.0f; // copy default config into all 3 profiles for (i = 0; i < 3; i++) memcpy(&mcfg.profile[i], &cfg, sizeof(config_t)); }
// Default settings static void resetConf(void) { int i; int8_t servoRates[8] = { 30, 30, 100, 100, 100, 100, 100, 100 }; // Clear all configuration memset(&mcfg, 0, sizeof(master_t)); memset(&cfg, 0, sizeof(config_t)); mcfg.version = EEPROM_CONF_VERSION; mcfg.mixerConfiguration = MULTITYPE_QUADX; featureClearAll(); featureSet(FEATURE_VBAT); // global settings mcfg.current_profile = 0; // default profile mcfg.gyro_cmpf_factor = 600; // default MWC mcfg.gyro_cmpfm_factor = 250; // default MWC mcfg.gyro_lpf = 42; // supported by all gyro drivers now. In case of ST gyro, will default to 32Hz instead mcfg.accZero[0] = 0; mcfg.accZero[1] = 0; mcfg.accZero[2] = 0; mcfg.gyro_align = ALIGN_DEFAULT; mcfg.acc_align = ALIGN_DEFAULT; mcfg.mag_align = ALIGN_DEFAULT; mcfg.board_align_roll = 0; mcfg.board_align_pitch = 0; mcfg.board_align_yaw = 0; mcfg.acc_hardware = ACC_DEFAULT; // default/autodetect mcfg.max_angle_inclination = 500; // 50 degrees mcfg.yaw_control_direction = 1; mcfg.moron_threshold = 32; mcfg.vbatscale = 110; mcfg.vbatmaxcellvoltage = 43; mcfg.vbatmincellvoltage = 33; mcfg.power_adc_channel = 0; mcfg.serialrx_type = 0; mcfg.telemetry_softserial = 0; mcfg.telemetry_switch = 0; mcfg.midrc = 1500; mcfg.mincheck = 1100; mcfg.maxcheck = 1900; mcfg.retarded_arm = 0; // disable arm/disarm on roll left/right mcfg.flaps_speed = 0; mcfg.fixedwing_althold_dir = 1; // Motor/ESC/Servo mcfg.minthrottle = 1150; mcfg.maxthrottle = 1850; mcfg.mincommand = 1000; mcfg.deadband3d_low = 1406; mcfg.deadband3d_high = 1514; mcfg.neutral3d = 1460; mcfg.deadband3d_throttle = 50; mcfg.motor_pwm_rate = 400; mcfg.servo_pwm_rate = 50; // gps/nav stuff mcfg.gps_type = GPS_NMEA; mcfg.gps_baudrate = 0; // serial (USART1) baudrate mcfg.serial_baudrate = 115200; mcfg.softserial_baudrate = 19200; mcfg.softserial_inverted = 0; mcfg.looptime = 3500; mcfg.rssi_aux_channel = 0; cfg.pidController = 0; cfg.P8[ROLL] = 40; cfg.I8[ROLL] = 30; cfg.D8[ROLL] = 23; cfg.P8[PITCH] = 40; cfg.I8[PITCH] = 30; cfg.D8[PITCH] = 23; cfg.P8[YAW] = 85; cfg.I8[YAW] = 45; cfg.D8[YAW] = 0; cfg.P8[PIDALT] = 50; cfg.I8[PIDALT] = 0; cfg.D8[PIDALT] = 0; cfg.P8[PIDPOS] = 11; // POSHOLD_P * 100; cfg.I8[PIDPOS] = 0; // POSHOLD_I * 100; cfg.D8[PIDPOS] = 0; cfg.P8[PIDPOSR] = 20; // POSHOLD_RATE_P * 10; cfg.I8[PIDPOSR] = 8; // POSHOLD_RATE_I * 100; cfg.D8[PIDPOSR] = 45; // POSHOLD_RATE_D * 1000; cfg.P8[PIDNAVR] = 14; // NAV_P * 10; cfg.I8[PIDNAVR] = 20; // NAV_I * 100; cfg.D8[PIDNAVR] = 80; // NAV_D * 1000; cfg.P8[PIDLEVEL] = 90; cfg.I8[PIDLEVEL] = 10; cfg.D8[PIDLEVEL] = 100; cfg.P8[PIDMAG] = 40; cfg.P8[PIDVEL] = 120; cfg.I8[PIDVEL] = 45; cfg.D8[PIDVEL] = 1; cfg.rcRate8 = 90; cfg.rcExpo8 = 65; cfg.rollPitchRate = 0; cfg.yawRate = 0; cfg.dynThrPID = 0; cfg.thrMid8 = 50; cfg.thrExpo8 = 0; // for (i = 0; i < CHECKBOXITEMS; i++) // cfg.activate[i] = 0; cfg.angleTrim[0] = 0; cfg.angleTrim[1] = 0; cfg.mag_declination = 0; // For example, -6deg 37min, = -637 Japan, format is [sign]dddmm (degreesminutes) default is zero. cfg.acc_lpf_factor = 4; cfg.accz_deadband = 40; cfg.accxy_deadband = 40; cfg.baro_tab_size = 21; cfg.baro_noise_lpf = 0.6f; cfg.baro_cf_vel = 0.985f; cfg.baro_cf_alt = 0.965f; cfg.acc_unarmedcal = 1; // Radio parseRcChannels("AETR1234"); cfg.deadband = 0; cfg.yawdeadband = 0; cfg.alt_hold_throttle_neutral = 40; cfg.alt_hold_fast_change = 1; cfg.throttle_angle_correction = 0; // could be 40 // Failsafe Variables cfg.failsafe_delay = 10; // 1sec cfg.failsafe_off_delay = 200; // 20sec cfg.failsafe_throttle = 1200; // decent default which should always be below hover throttle for people. cfg.failsafe_detect_threshold = 985; // any of first 4 channels below this value will trigger failsafe // servos for (i = 0; i < 8; i++) { cfg.servoConf[i].min = 1020; cfg.servoConf[i].max = 2000; cfg.servoConf[i].middle = 1500; cfg.servoConf[i].rate = servoRates[i]; } cfg.yaw_direction = 1; cfg.tri_unarmed_servo = 1; // gimbal cfg.gimbal_flags = GIMBAL_NORMAL; // gps/nav stuff cfg.gps_wp_radius = 200; cfg.gps_lpf = 20; cfg.nav_slew_rate = 30; cfg.nav_controls_heading = 1; cfg.nav_speed_min = 100; cfg.nav_speed_max = 300; cfg.ap_mode = 40; // custom mixer. clear by defaults. for (i = 0; i < MAX_MOTORS; i++) mcfg.customMixer[i].throttle = 0.0f; // copy default config into all 3 profiles for (i = 0; i < 3; i++) memcpy(&mcfg.profile[i], &cfg, sizeof(config_t)); }
// Default settings static void resetConf(void) { int i; #ifdef USE_SERVOS int8_t servoRates[MAX_SUPPORTED_SERVOS] = { 30, 30, 100, 100, 100, 100, 100, 100 }; ; #endif // Clear all configuration memset(&masterConfig, 0, sizeof(master_t)); setProfile(0); setControlRateProfile(0); masterConfig.version = EEPROM_CONF_VERSION; masterConfig.mixerMode = MIXER_QUADX; featureClearAll(); #if defined(CJMCU) || defined(SPARKY) featureSet(FEATURE_RX_PPM); #endif #ifdef BOARD_HAS_VOLTAGE_DIVIDER // only enable the VBAT feature by default if the board has a voltage divider otherwise // the user may see incorrect readings and unexpected issues with pin mappings may occur. featureSet(FEATURE_VBAT); #endif featureSet(FEATURE_FAILSAFE); // global settings masterConfig.current_profile_index = 0; // default profile masterConfig.gyro_cmpf_factor = 600; // default MWC masterConfig.gyro_cmpfm_factor = 250; // default MWC masterConfig.gyro_lpf = 42; // supported by all gyro drivers now. In case of ST gyro, will default to 32Hz instead resetAccelerometerTrims(&masterConfig.accZero); resetSensorAlignment(&masterConfig.sensorAlignmentConfig); masterConfig.boardAlignment.rollDegrees = 0; masterConfig.boardAlignment.pitchDegrees = 0; masterConfig.boardAlignment.yawDegrees = 0; masterConfig.acc_hardware = ACC_DEFAULT; // default/autodetect masterConfig.max_angle_inclination = 500; // 50 degrees masterConfig.yaw_control_direction = 1; masterConfig.gyroConfig.gyroMovementCalibrationThreshold = 32; masterConfig.mag_hardware = MAG_DEFAULT; // default/autodetect resetBatteryConfig(&masterConfig.batteryConfig); resetTelemetryConfig(&masterConfig.telemetryConfig); masterConfig.rxConfig.serialrx_provider = 0; masterConfig.rxConfig.spektrum_sat_bind = 0; masterConfig.rxConfig.midrc = 1500; masterConfig.rxConfig.mincheck = 1100; masterConfig.rxConfig.maxcheck = 1900; masterConfig.rxConfig.rx_min_usec = 985; // any of first 4 channels below this value will trigger rx loss detection masterConfig.rxConfig.rx_max_usec = 2115; // any of first 4 channels above this value will trigger rx loss detection masterConfig.rxConfig.rssi_channel = 0; masterConfig.rxConfig.rssi_scale = RSSI_SCALE_DEFAULT; masterConfig.inputFilteringMode = INPUT_FILTERING_DISABLED; masterConfig.retarded_arm = 0; masterConfig.disarm_kill_switch = 1; masterConfig.auto_disarm_delay = 5; masterConfig.small_angle = 25; resetMixerConfig(&masterConfig.mixerConfig); masterConfig.airplaneConfig.flaps_speed = 0; masterConfig.airplaneConfig.fixedwing_althold_dir = 1; // Motor/ESC/Servo resetEscAndServoConfig(&masterConfig.escAndServoConfig); resetFlight3DConfig(&masterConfig.flight3DConfig); #ifdef BRUSHED_MOTORS masterConfig.motor_pwm_rate = BRUSHED_MOTORS_PWM_RATE; #else masterConfig.motor_pwm_rate = BRUSHLESS_MOTORS_PWM_RATE; #endif masterConfig.servo_pwm_rate = 50; #ifdef GPS // gps/nav stuff masterConfig.gpsConfig.provider = GPS_NMEA; masterConfig.gpsConfig.sbasMode = SBAS_AUTO; masterConfig.gpsConfig.autoConfig = GPS_AUTOCONFIG_ON; masterConfig.gpsConfig.autoBaud = GPS_AUTOBAUD_OFF; #endif resetSerialConfig(&masterConfig.serialConfig); masterConfig.looptime = 3500; masterConfig.emf_avoidance = 0; resetPidProfile(¤tProfile->pidProfile); resetControlRateConfig(&masterConfig.controlRateProfiles[0]); // for (i = 0; i < CHECKBOXITEMS; i++) // cfg.activate[i] = 0; resetRollAndPitchTrims(¤tProfile->accelerometerTrims); currentProfile->mag_declination = 0; currentProfile->acc_lpf_factor = 4; currentProfile->accz_lpf_cutoff = 5.0f; currentProfile->accDeadband.xy = 40; currentProfile->accDeadband.z = 40; resetBarometerConfig(¤tProfile->barometerConfig); currentProfile->acc_unarmedcal = 1; // Radio parseRcChannels("AETR1234", &masterConfig.rxConfig); resetRcControlsConfig(¤tProfile->rcControlsConfig); currentProfile->throttle_correction_value = 0; // could 10 with althold or 40 for fpv currentProfile->throttle_correction_angle = 800; // could be 80.0 deg with atlhold or 45.0 for fpv // Failsafe Variables masterConfig.failsafeConfig.failsafe_delay = 10; // 1sec masterConfig.failsafeConfig.failsafe_off_delay = 200; // 20sec masterConfig.failsafeConfig.failsafe_throttle = 1000; // default throttle off. #ifdef USE_SERVOS // servos for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) { currentProfile->servoConf[i].min = DEFAULT_SERVO_MIN; currentProfile->servoConf[i].max = DEFAULT_SERVO_MAX; currentProfile->servoConf[i].middle = DEFAULT_SERVO_MIDDLE; currentProfile->servoConf[i].rate = servoRates[i]; currentProfile->servoConf[i].forwardFromChannel = CHANNEL_FORWARDING_DISABLED; } // gimbal currentProfile->gimbalConfig.gimbal_flags = GIMBAL_NORMAL; #endif #ifdef GPS resetGpsProfile(¤tProfile->gpsProfile); #endif // custom mixer. clear by defaults. for (i = 0; i < MAX_SUPPORTED_MOTORS; i++) masterConfig.customMixer[i].throttle = 0.0f; #ifdef LED_STRIP applyDefaultColors(masterConfig.colors, CONFIGURABLE_COLOR_COUNT); applyDefaultLedStripConfig(masterConfig.ledConfigs); #endif #ifdef BLACKBOX #ifdef SPRACINGF3 featureSet(FEATURE_BLACKBOX); masterConfig.blackbox_device = 1; #else masterConfig.blackbox_device = 0; #endif masterConfig.blackbox_rate_num = 1; masterConfig.blackbox_rate_denom = 1; #endif // alternative defaults settings for ALIENWIIF1 and ALIENWIIF3 targets #ifdef ALIENWII32 featureSet(FEATURE_RX_SERIAL); featureSet(FEATURE_MOTOR_STOP); featureSet(FEATURE_FAILSAFE); #ifdef ALIENWIIF3 masterConfig.serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL; masterConfig.batteryConfig.vbatscale = 20; #else masterConfig.serialConfig.portConfigs[1].functionMask = FUNCTION_RX_SERIAL; #endif masterConfig.rxConfig.serialrx_provider = 1; masterConfig.rxConfig.spektrum_sat_bind = 5; masterConfig.escAndServoConfig.minthrottle = 1000; masterConfig.escAndServoConfig.maxthrottle = 2000; masterConfig.motor_pwm_rate = 32000; masterConfig.looptime = 2000; currentProfile->pidProfile.pidController = 3; currentProfile->pidProfile.P8[ROLL] = 36; currentProfile->pidProfile.P8[PITCH] = 36; masterConfig.failsafeConfig.failsafe_delay = 2; masterConfig.failsafeConfig.failsafe_off_delay = 0; masterConfig.failsafeConfig.failsafe_throttle = 1000; currentControlRateProfile->rcRate8 = 130; currentControlRateProfile->rates[FD_PITCH] = 20; currentControlRateProfile->rates[FD_ROLL] = 20; currentControlRateProfile->rates[FD_YAW] = 100; parseRcChannels("TAER1234", &masterConfig.rxConfig); // { 1.0f, -0.5f, 1.0f, -1.0f }, // REAR_R masterConfig.customMixer[0].throttle = 1.0f; masterConfig.customMixer[0].roll = -0.5f; masterConfig.customMixer[0].pitch = 1.0f; masterConfig.customMixer[0].yaw = -1.0f; // { 1.0f, -0.5f, -1.0f, 1.0f }, // FRONT_R masterConfig.customMixer[1].throttle = 1.0f; masterConfig.customMixer[1].roll = -0.5f; masterConfig.customMixer[1].pitch = -1.0f; masterConfig.customMixer[1].yaw = 1.0f; // { 1.0f, 0.5f, 1.0f, 1.0f }, // REAR_L masterConfig.customMixer[2].throttle = 1.0f; masterConfig.customMixer[2].roll = 0.5f; masterConfig.customMixer[2].pitch = 1.0f; masterConfig.customMixer[2].yaw = 1.0f; // { 1.0f, 0.5f, -1.0f, -1.0f }, // FRONT_L masterConfig.customMixer[3].throttle = 1.0f; masterConfig.customMixer[3].roll = 0.5f; masterConfig.customMixer[3].pitch = -1.0f; masterConfig.customMixer[3].yaw = -1.0f; // { 1.0f, -1.0f, -0.5f, -1.0f }, // MIDFRONT_R masterConfig.customMixer[4].throttle = 1.0f; masterConfig.customMixer[4].roll = -1.0f; masterConfig.customMixer[4].pitch = -0.5f; masterConfig.customMixer[4].yaw = -1.0f; // { 1.0f, 1.0f, -0.5f, 1.0f }, // MIDFRONT_L masterConfig.customMixer[5].throttle = 1.0f; masterConfig.customMixer[5].roll = 1.0f; masterConfig.customMixer[5].pitch = -0.5f; masterConfig.customMixer[5].yaw = 1.0f; // { 1.0f, -1.0f, 0.5f, 1.0f }, // MIDREAR_R masterConfig.customMixer[6].throttle = 1.0f; masterConfig.customMixer[6].roll = -1.0f; masterConfig.customMixer[6].pitch = 0.5f; masterConfig.customMixer[6].yaw = 1.0f; // { 1.0f, 1.0f, 0.5f, -1.0f }, // MIDREAR_L masterConfig.customMixer[7].throttle = 1.0f; masterConfig.customMixer[7].roll = 1.0f; masterConfig.customMixer[7].pitch = 0.5f; masterConfig.customMixer[7].yaw = -1.0f; #endif // copy first profile into remaining profile for (i = 1; i < MAX_PROFILE_COUNT; i++) { memcpy(&masterConfig.profile[i], currentProfile, sizeof(profile_t)); } // copy first control rate config into remaining profile for (i = 1; i < MAX_CONTROL_RATE_PROFILE_COUNT; i++) { memcpy(&masterConfig.controlRateProfiles[i], currentControlRateProfile, sizeof(controlRateConfig_t)); } for (i = 1; i < MAX_PROFILE_COUNT; i++) { masterConfig.profile[i].defaultRateProfileIndex = i % MAX_CONTROL_RATE_PROFILE_COUNT; } }
// Default settings static void resetConf(void) { int i; int8_t servoRates[8] = { 30, 30, 100, 100, 100, 100, 100, 100 }; // Clear all configuration memset(&masterConfig, 0, sizeof(master_t)); memset(¤tProfile, 0, sizeof(profile_t)); masterConfig.version = EEPROM_CONF_VERSION; masterConfig.mixerConfiguration = MULTITYPE_QUADX; featureClearAll(); featureSet(FEATURE_VBAT); // global settings masterConfig.current_profile_index = 0; // default profile masterConfig.gyro_cmpf_factor = 600; // default MWC masterConfig.gyro_cmpfm_factor = 250; // default MWC masterConfig.gyro_lpf = 42; // supported by all gyro drivers now. In case of ST gyro, will default to 32Hz instead resetAccelerometerTrims(&masterConfig.accZero); resetSensorAlignment(&masterConfig.sensorAlignmentConfig); masterConfig.boardAlignment.rollDegrees = 0; masterConfig.boardAlignment.pitchDegrees = 0; masterConfig.boardAlignment.yawDegrees = 0; masterConfig.acc_hardware = ACC_DEFAULT; // default/autodetect masterConfig.max_angle_inclination = 500; // 50 degrees masterConfig.yaw_control_direction = 1; masterConfig.gyroConfig.gyroMovementCalibrationThreshold = 32; masterConfig.batteryConfig.vbatscale = 110; masterConfig.batteryConfig.vbatmaxcellvoltage = 43; masterConfig.batteryConfig.vbatmincellvoltage = 33; masterConfig.batteryConfig.currentMeterOffset = 0; masterConfig.batteryConfig.currentMeterScale = 400; // for Allegro ACS758LCB-100U (40mV/A) resetTelemetryConfig(&masterConfig.telemetryConfig); masterConfig.rxConfig.serialrx_provider = 0; masterConfig.rxConfig.midrc = 1500; masterConfig.rxConfig.mincheck = 1100; masterConfig.rxConfig.maxcheck = 1900; masterConfig.rxConfig.rssi_channel = 0; masterConfig.retarded_arm = 0; // disable arm/disarm on roll left/right masterConfig.airplaneConfig.flaps_speed = 0; masterConfig.fixedwing_althold_dir = 1; // Motor/ESC/Servo resetEscAndServoConfig(&masterConfig.escAndServoConfig); resetFlight3DConfig(&masterConfig.flight3DConfig); masterConfig.motor_pwm_rate = 400; masterConfig.servo_pwm_rate = 50; // gps/nav stuff masterConfig.gpsConfig.provider = GPS_NMEA; masterConfig.gpsConfig.sbasMode = SBAS_AUTO; resetSerialConfig(&masterConfig.serialConfig); masterConfig.looptime = 3500; masterConfig.emf_avoidance = 0; currentProfile.pidController = 0; resetPidProfile(¤tProfile.pidProfile); currentProfile.controlRateConfig.rcRate8 = 90; currentProfile.controlRateConfig.rcExpo8 = 65; currentProfile.controlRateConfig.rollPitchRate = 0; currentProfile.controlRateConfig.yawRate = 0; currentProfile.dynThrPID = 0; currentProfile.tpa_breakpoint = 1500; currentProfile.controlRateConfig.thrMid8 = 50; currentProfile.controlRateConfig.thrExpo8 = 0; // for (i = 0; i < CHECKBOXITEMS; i++) // cfg.activate[i] = 0; resetRollAndPitchTrims(¤tProfile.accelerometerTrims); currentProfile.mag_declination = 0; currentProfile.acc_lpf_factor = 4; currentProfile.accDeadband.xy = 40; currentProfile.accDeadband.z = 40; resetBarometerConfig(¤tProfile.barometerConfig); currentProfile.acc_unarmedcal = 1; // Radio parseRcChannels("AETR1234", &masterConfig.rxConfig); currentProfile.deadband = 0; currentProfile.yaw_deadband = 0; currentProfile.alt_hold_deadband = 40; currentProfile.alt_hold_fast_change = 1; currentProfile.throttle_correction_value = 0; // could 10 with althold or 40 for fpv currentProfile.throttle_correction_angle = 800; // could be 80.0 deg with atlhold or 45.0 for fpv // Failsafe Variables currentProfile.failsafeConfig.failsafe_delay = 10; // 1sec currentProfile.failsafeConfig.failsafe_off_delay = 200; // 20sec currentProfile.failsafeConfig.failsafe_throttle = 1200; // decent default which should always be below hover throttle for people. currentProfile.failsafeConfig.failsafe_min_usec = 985; // any of first 4 channels below this value will trigger failsafe currentProfile.failsafeConfig.failsafe_max_usec = 2115; // any of first 4 channels above this value will trigger failsafe // servos for (i = 0; i < 8; i++) { currentProfile.servoConf[i].min = DEFAULT_SERVO_MIN; currentProfile.servoConf[i].max = DEFAULT_SERVO_MAX; currentProfile.servoConf[i].middle = DEFAULT_SERVO_MIDDLE; currentProfile.servoConf[i].rate = servoRates[i]; currentProfile.servoConf[i].forwardFromChannel = CHANNEL_FORWARDING_DISABLED; } currentProfile.mixerConfig.yaw_direction = 1; currentProfile.mixerConfig.tri_unarmed_servo = 1; // gimbal currentProfile.gimbalConfig.gimbal_flags = GIMBAL_NORMAL; resetGpsProfile(¤tProfile.gpsProfile); // custom mixer. clear by defaults. for (i = 0; i < MAX_SUPPORTED_MOTORS; i++) masterConfig.customMixer[i].throttle = 0.0f; // copy default config into all 3 profiles for (i = 0; i < 3; i++) memcpy(&masterConfig.profile[i], ¤tProfile, sizeof(profile_t));
void receiverCLI() { char rcOrderString[9]; float tempFloat; uint8_t index; uint8_t receiverQuery = 'x'; uint8_t validQuery = false; NVIC_InitTypeDef NVIC_InitStructure; cliBusy = true; cliPortPrint("\nEntering Receiver CLI....\n\n"); while(true) { cliPortPrint("Receiver CLI -> "); while ((cliPortAvailable() == false) && (validQuery == false)); if (validQuery == false) receiverQuery = cliPortRead(); cliPortPrint("\n"); switch(receiverQuery) { /////////////////////////// case 'a': // Receiver Configuration cliPortPrint("\nReceiver Type: "); switch(systemConfig.receiverType) { case PPM: cliPortPrint("PPM\n"); break; case SPEKTRUM: cliPortPrint("Spektrum\n"); break; } cliPortPrint("Current RC Channel Assignment: "); for (index = 0; index < 8; index++) rcOrderString[systemConfig.rcMap[index]] = rcChannelLetters[index]; rcOrderString[index] = '\0'; cliPortPrint(rcOrderString); cliPortPrint("\n"); cliPortPrintF("Secondary Spektrum: "); if ((systemConfig.slaveSpektrum == true) && false) // HJI Inhibit Slave Spektrum on Naze32 Pro cliPortPrintF("Installed\n"); else cliPortPrintF("Uninstalled\n"); cliPortPrintF("Mid Command: %4ld\n", (uint16_t)systemConfig.midCommand); cliPortPrintF("Min Check: %4ld\n", (uint16_t)systemConfig.minCheck); cliPortPrintF("Max Check: %4ld\n", (uint16_t)systemConfig.maxCheck); cliPortPrintF("Min Throttle: %4ld\n", (uint16_t)systemConfig.minThrottle); cliPortPrintF("Max Thottle: %4ld\n\n", (uint16_t)systemConfig.maxThrottle); tempFloat = systemConfig.rollAndPitchRateScaling * 180000.0 / PI; cliPortPrintF("Max Roll and Pitch Rate Cmd: %6.2f DPS\n", tempFloat); tempFloat = systemConfig.yawRateScaling * 180000.0 / PI; cliPortPrintF("Max Yaw Rate Cmd: %6.2f DPS\n\n", tempFloat); cliPortPrintF("Roll Rate Cmd Tau: %6.2f\n", systemConfig.rollRateCmdLowPassTau); cliPortPrintF("Pitch Rate Cmd Tau: %6.2f\n\n", systemConfig.pitchRateCmdLowPassTau); tempFloat = systemConfig.attitudeScaling * 180000.0 / PI; cliPortPrintF("Max Attitude Cmd: %6.2f Degrees\n\n", tempFloat); cliPortPrintF("Roll Attitude Cmd Tau: %6.2f\n", systemConfig.rollAttCmdLowPassTau); cliPortPrintF("Pitch Attitude Cmd Tau: %6.2f\n\n", systemConfig.pitchAttCmdLowPassTau); cliPortPrintF("Arm Delay Count: %3d Frames\n", systemConfig.armCount); cliPortPrintF("Disarm Delay Count: %3d Frames\n\n", systemConfig.disarmCount); validQuery = false; break; /////////////////////////// case 'x': cliPortPrint("\nExiting Receiver CLI....\n\n"); cliBusy = false; return; break; /////////////////////////// case 'A': // Toggle PPM/Spektrum Satellite Receiver if (systemConfig.receiverType == PPM) { NVIC_InitStructure.NVIC_IRQChannel = TIM1_CC_IRQn; NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 2; NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0; NVIC_InitStructure.NVIC_IRQChannelCmd = DISABLE; NVIC_Init(&NVIC_InitStructure); TIM_ITConfig(TIM1, TIM_IT_CC1, DISABLE); systemConfig.receiverType = SPEKTRUM; spektrumInit(); } else { NVIC_InitStructure.NVIC_IRQChannel = TIM1_TRG_COM_TIM17_IRQn; NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 2; NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0; NVIC_InitStructure.NVIC_IRQChannelCmd = DISABLE; NVIC_Init(&NVIC_InitStructure); TIM_ITConfig(TIM17, TIM_IT_Update, DISABLE); systemConfig.receiverType = PPM; ppmRxInit(); } receiverQuery = 'a'; validQuery = true; break; /////////////////////////// case 'B': // Read RC Control Order readStringCLI( rcOrderString, 8 ); parseRcChannels( rcOrderString ); receiverQuery = 'a'; validQuery = true; break; /////////////////////////// case 'C': // Toggle Slave Spektrum State // HJI Inhibit Slave Spektrum on Naze32 Pro if (systemConfig.slaveSpektrum == true) systemConfig.slaveSpektrum = false; // HJI Inhibit Slave Spektrum on Naze32 Pro else // HJI Inhibit Slave Spektrum on Naze32 Pro systemConfig.slaveSpektrum = true; receiverQuery = 'a'; validQuery = true; break; /////////////////////////// case 'D': // Read RC Control Points systemConfig.midCommand = readFloatCLI(); systemConfig.minCheck = readFloatCLI(); systemConfig.maxCheck = readFloatCLI(); systemConfig.minThrottle = readFloatCLI(); systemConfig.maxThrottle = readFloatCLI(); receiverQuery = 'a'; validQuery = true; break; /////////////////////////// case 'E': // Read Arm/Disarm Counts systemConfig.armCount = (uint8_t)readFloatCLI(); systemConfig.disarmCount = (uint8_t)readFloatCLI(); receiverQuery = 'a'; validQuery = true; break; /////////////////////////// case 'F': // Read Max Rate Value systemConfig.rollAndPitchRateScaling = readFloatCLI() / 180000.0f * PI; systemConfig.yawRateScaling = readFloatCLI() / 180000.0f * PI; receiverQuery = 'a'; validQuery = true; break; /////////////////////////// case 'G': // Read Max Attitude Value systemConfig.attitudeScaling = readFloatCLI() / 180000.0f * PI; receiverQuery = 'a'; validQuery = true; break; /////////////////////////// case 'H': // Read Rate Cmd Tau Value systemConfig.rollRateCmdLowPassTau = readFloatCLI(); systemConfig.pitchRateCmdLowPassTau = readFloatCLI(); receiverQuery = 'a'; validQuery = true; break; /////////////////////////// case 'I': // Read Attitude Cmd Tau Value systemConfig.rollAttCmdLowPassTau = readFloatCLI(); systemConfig.pitchAttCmdLowPassTau = readFloatCLI(); receiverQuery = 'a'; validQuery = true; break; /////////////////////////// case 'W': // Write System EEPROM Parameters cliPortPrint("\nWriting System EEPROM Parameters....\n\n"); writeSystemEEPROM(); validQuery = false; break; /////////////////////////// case '?': cliPortPrint("\n"); cliPortPrint("'a' Receiver Configuration Data 'A' Toggle PPM/Spektrum Receiver\n"); cliPortPrint(" 'B' Set RC Control Order BTAER1234\n"); cliPortPrint(" 'C' Toggle Slave Spektrum State\n"); cliPortPrint(" 'D' Set RC Control Points DmidCmd;minChk;maxChk;minThrot;maxThrot\n"); cliPortPrint(" 'E' Set Arm/Disarm Counts EarmCount;disarmCount\n"); cliPortPrint(" 'F' Set Maximum Rate Commands FRP;Y RP = Roll/Pitch, Y = Yaw\n"); cliPortPrint(" 'G' Set Maximum Attitude Command\n"); cliPortPrint(" 'H' Set Roll/Pitch Rate Command Filters HROLL;PITCH\n"); cliPortPrint(" 'I' Set Roll/Pitch Att Command Filters IROLL;PITCH\n"); cliPortPrint(" 'W' Write System EEPROM Parameters\n"); cliPortPrint("'x' Exit Receiver CLI '?' Command Summary\n"); cliPortPrint("\n"); break; /////////////////////////// } } }
// Default settings static void resetConf(void) { int i; int8_t servoRates[8] = { 30, 30, 100, 100, 100, 100, 100, 100 }; // Clear all configuration memset(&masterConfig, 0, sizeof(master_t)); setProfile(0); setControlRateProfile(0); masterConfig.version = EEPROM_CONF_VERSION; masterConfig.mixerConfiguration = MULTITYPE_QUADX; featureClearAll(); #if defined(CJMCU) || defined(SPARKY) featureSet(FEATURE_RX_PPM); #endif featureSet(FEATURE_VBAT); // global settings masterConfig.current_profile_index = 0; // default profile masterConfig.gyro_cmpf_factor = 600; // default MWC masterConfig.gyro_cmpfm_factor = 250; // default MWC masterConfig.gyro_lpf = 42; // supported by all gyro drivers now. In case of ST gyro, will default to 32Hz instead resetAccelerometerTrims(&masterConfig.accZero); resetSensorAlignment(&masterConfig.sensorAlignmentConfig); masterConfig.boardAlignment.rollDegrees = 0; masterConfig.boardAlignment.pitchDegrees = 0; masterConfig.boardAlignment.yawDegrees = 0; masterConfig.acc_hardware = ACC_DEFAULT; // default/autodetect masterConfig.max_angle_inclination = 500; // 50 degrees masterConfig.yaw_control_direction = 1; masterConfig.gyroConfig.gyroMovementCalibrationThreshold = 32; resetBatteryConfig(&masterConfig.batteryConfig); resetTelemetryConfig(&masterConfig.telemetryConfig); masterConfig.rxConfig.serialrx_provider = 0; masterConfig.rxConfig.spektrum_sat_bind = 0; masterConfig.rxConfig.midrc = 1500; masterConfig.rxConfig.mincheck = 1100; masterConfig.rxConfig.maxcheck = 1900; masterConfig.rxConfig.rssi_channel = 0; masterConfig.rxConfig.rssi_scale = RSSI_SCALE_DEFAULT; masterConfig.inputFilteringMode = INPUT_FILTERING_DISABLED; masterConfig.retarded_arm = 0; masterConfig.disarm_kill_switch = 1; masterConfig.small_angle = 25; masterConfig.airplaneConfig.flaps_speed = 0; masterConfig.airplaneConfig.fixedwing_althold_dir = 1; // Motor/ESC/Servo resetEscAndServoConfig(&masterConfig.escAndServoConfig); resetFlight3DConfig(&masterConfig.flight3DConfig); #ifdef BRUSHED_MOTORS masterConfig.motor_pwm_rate = BRUSHED_MOTORS_PWM_RATE; #else masterConfig.motor_pwm_rate = BRUSHLESS_MOTORS_PWM_RATE; #endif masterConfig.servo_pwm_rate = 50; #ifdef GPS // gps/nav stuff masterConfig.gpsConfig.provider = GPS_NMEA; masterConfig.gpsConfig.sbasMode = SBAS_AUTO; masterConfig.gpsConfig.autoConfig = GPS_AUTOCONFIG_ON; masterConfig.gpsConfig.autoBaud = GPS_AUTOBAUD_OFF; #endif resetSerialConfig(&masterConfig.serialConfig); masterConfig.looptime = 3500; masterConfig.emf_avoidance = 0; currentProfile->pidController = 0; resetPidProfile(¤tProfile->pidProfile); resetControlRateConfig(&masterConfig.controlRateProfiles[0]); // for (i = 0; i < CHECKBOXITEMS; i++) // cfg.activate[i] = 0; resetRollAndPitchTrims(¤tProfile->accelerometerTrims); currentProfile->mag_declination = 0; currentProfile->acc_lpf_factor = 4; currentProfile->accz_lpf_cutoff = 5.0f; currentProfile->accDeadband.xy = 40; currentProfile->accDeadband.z = 40; resetBarometerConfig(¤tProfile->barometerConfig); currentProfile->acc_unarmedcal = 1; // Radio parseRcChannels("AETR1234", &masterConfig.rxConfig); resetRcControlsConfig(¤tProfile->rcControlsConfig); currentProfile->throttle_correction_value = 0; // could 10 with althold or 40 for fpv currentProfile->throttle_correction_angle = 800; // could be 80.0 deg with atlhold or 45.0 for fpv // Failsafe Variables currentProfile->failsafeConfig.failsafe_delay = 10; // 1sec currentProfile->failsafeConfig.failsafe_off_delay = 200; // 20sec currentProfile->failsafeConfig.failsafe_throttle = 1200; // decent default which should always be below hover throttle for people. currentProfile->failsafeConfig.failsafe_min_usec = 985; // any of first 4 channels below this value will trigger failsafe currentProfile->failsafeConfig.failsafe_max_usec = 2115; // any of first 4 channels above this value will trigger failsafe // servos for (i = 0; i < 8; i++) { currentProfile->servoConf[i].min = DEFAULT_SERVO_MIN; currentProfile->servoConf[i].max = DEFAULT_SERVO_MAX; currentProfile->servoConf[i].middle = DEFAULT_SERVO_MIDDLE; currentProfile->servoConf[i].rate = servoRates[i]; currentProfile->servoConf[i].forwardFromChannel = CHANNEL_FORWARDING_DISABLED; } currentProfile->mixerConfig.yaw_direction = 1; currentProfile->mixerConfig.tri_unarmed_servo = 1; // gimbal currentProfile->gimbalConfig.gimbal_flags = GIMBAL_NORMAL; #ifdef GPS resetGpsProfile(¤tProfile->gpsProfile); #endif // custom mixer. clear by defaults. for (i = 0; i < MAX_SUPPORTED_MOTORS; i++) masterConfig.customMixer[i].throttle = 0.0f; #ifdef LED_STRIP applyDefaultColors(masterConfig.colors, CONFIGURABLE_COLOR_COUNT); applyDefaultLedStripConfig(masterConfig.ledConfigs); #endif // copy first profile into remaining profile for (i = 1; i < MAX_PROFILE_COUNT; i++) { memcpy(&masterConfig.profile[i], currentProfile, sizeof(profile_t)); } // copy first control rate config into remaining profile for (i = 1; i < MAX_CONTROL_RATE_PROFILE_COUNT; i++) { memcpy(&masterConfig.controlRateProfiles[i], currentControlRateProfile, sizeof(controlRateConfig_t)); } for (i = 1; i < MAX_PROFILE_COUNT; i++) { masterConfig.profile[i].defaultRateProfileIndex = i % MAX_CONTROL_RATE_PROFILE_COUNT; } }