1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-19 14:25:20 +03:00

AlienFlight config fix

This commit is contained in:
Michael Jakob 2016-08-12 05:17:54 +02:00
parent 08776bc309
commit 2c9776861d
3 changed files with 18 additions and 18 deletions

View file

@ -77,12 +77,12 @@ void targetConfiguration(void)
masterConfig.motor_pwm_rate = 32000; masterConfig.motor_pwm_rate = 32000;
masterConfig.failsafeConfig.failsafe_delay = 2; masterConfig.failsafeConfig.failsafe_delay = 2;
masterConfig.failsafeConfig.failsafe_off_delay = 0; masterConfig.failsafeConfig.failsafe_off_delay = 0;
currentProfile->pidProfile.P8[ROLL] = 90; masterConfig.profile[0].pidProfile.P8[ROLL] = 90;
currentProfile->pidProfile.I8[ROLL] = 44; masterConfig.profile[0].pidProfile.I8[ROLL] = 44;
currentProfile->pidProfile.D8[ROLL] = 60; masterConfig.profile[0].pidProfile.D8[ROLL] = 60;
currentProfile->pidProfile.P8[PITCH] = 90; masterConfig.profile[0].pidProfile.P8[PITCH] = 90;
currentProfile->pidProfile.I8[PITCH] = 44; masterConfig.profile[0].pidProfile.I8[PITCH] = 44;
currentProfile->pidProfile.D8[PITCH] = 60; masterConfig.profile[0].pidProfile.D8[PITCH] = 60;
masterConfig.customMotorMixer[0] = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R 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[1] = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R

View file

@ -85,12 +85,12 @@ void targetConfiguration(void) {
masterConfig.failsafeConfig.failsafe_off_delay = 0; masterConfig.failsafeConfig.failsafe_off_delay = 0;
masterConfig.gyro_sync_denom = 2; masterConfig.gyro_sync_denom = 2;
masterConfig.pid_process_denom = 1; masterConfig.pid_process_denom = 1;
currentProfile->pidProfile.P8[ROLL] = 90; masterConfig.profile[0].pidProfile.P8[ROLL] = 90;
currentProfile->pidProfile.I8[ROLL] = 44; masterConfig.profile[0].pidProfile.I8[ROLL] = 44;
currentProfile->pidProfile.D8[ROLL] = 60; masterConfig.profile[0].pidProfile.D8[ROLL] = 60;
currentProfile->pidProfile.P8[PITCH] = 90; masterConfig.profile[0].pidProfile.P8[PITCH] = 90;
currentProfile->pidProfile.I8[PITCH] = 44; masterConfig.profile[0].pidProfile.I8[PITCH] = 44;
currentProfile->pidProfile.D8[PITCH] = 60; masterConfig.profile[0].pidProfile.D8[PITCH] = 60;
masterConfig.customMotorMixer[0] = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R 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[1] = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R

View file

@ -85,12 +85,12 @@ void targetConfiguration(void) {
masterConfig.failsafeConfig.failsafe_off_delay = 0; masterConfig.failsafeConfig.failsafe_off_delay = 0;
masterConfig.gyro_sync_denom = 1; masterConfig.gyro_sync_denom = 1;
masterConfig.pid_process_denom = 1; masterConfig.pid_process_denom = 1;
currentProfile->pidProfile.P8[ROLL] = 90; masterConfig.profile[0].pidProfile.P8[ROLL] = 90;
currentProfile->pidProfile.I8[ROLL] = 44; masterConfig.profile[0].pidProfile.I8[ROLL] = 44;
currentProfile->pidProfile.D8[ROLL] = 60; masterConfig.profile[0].pidProfile.D8[ROLL] = 60;
currentProfile->pidProfile.P8[PITCH] = 90; masterConfig.profile[0].pidProfile.P8[PITCH] = 90;
currentProfile->pidProfile.I8[PITCH] = 44; masterConfig.profile[0].pidProfile.I8[PITCH] = 44;
currentProfile->pidProfile.D8[PITCH] = 60; masterConfig.profile[0].pidProfile.D8[PITCH] = 60;
masterConfig.customMotorMixer[0] = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R 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[1] = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R