Removed excess trailing spaces before new lines on licenses.
[betaflight.git] / src / main / target / ALIENWHOOP / config.c
blob4f8e667db8d1c4d6da2e8afdcbf21af39251d163
1 /*
2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
8 * any later version.
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
26 \ | _ _| __| \ |\ \ /| | _ \ _ \ _ \
27 _ \ | | _| . | \ \ \ / __ | ( |( |__/
28 _/ _\____|___|___|_|\_| \_/\_/ _| _|\___/\___/_|
31 Take me to your leader-board...
37 #include <stdbool.h>
38 #include <stdint.h>
40 #include <platform.h>
42 #ifdef USE_TARGET_CONFIG
44 #include "fc/rc_modes.h"
45 #include "common/axis.h"
46 #include "config/feature.h"
47 #include "drivers/pwm_esc_detect.h"
48 #include "fc/config.h"
49 #include "fc/controlrate_profile.h"
50 #include "fc/rc_controls.h"
51 #include "flight/mixer.h"
52 #include "flight/pid.h"
53 #include "io/beeper.h"
54 #include "io/serial.h"
55 #include "rx/rx.h"
56 #include "sensors/barometer.h"
57 #include "sensors/boardalignment.h"
58 #include "sensors/compass.h"
59 #include "sensors/gyro.h"
61 #ifdef BRUSHED_MOTORS_PWM_RATE
62 #undef BRUSHED_MOTORS_PWM_RATE
63 #endif
65 #define BRUSHED_MOTORS_PWM_RATE 666 // 666Hz };-)>~ low PWM rate seems to give better power and cooler motors...
68 void targetConfiguration(void)
70 if (hardwareMotorType == MOTOR_BRUSHED) {
71 motorConfigMutable()->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
72 motorConfigMutable()->minthrottle = 1020;
73 motorConfigMutable()->maxthrottle = 2000;
76 /* Default to Spektrum */
77 rxConfigMutable()->serialrx_provider = SERIALRX_SPEKTRUM2048;
78 rxConfigMutable()->spektrum_sat_bind = 5;
79 rxConfigMutable()->spektrum_sat_bind_autoreset = 1;
80 parseRcChannels("TAER1234", rxConfigMutable());
81 #if defined(ALIENWHOOPF7)
82 rxConfigMutable()->serialrx_inverted = true;
83 #endif
85 beeperOffSet((BEEPER_BAT_CRIT_LOW | BEEPER_BAT_LOW | BEEPER_RX_SET) ^ BEEPER_GYRO_CALIBRATED);
87 /* Breadboard-specific settings for development purposes only
89 #if defined(BREADBOARD)
90 boardAlignmentMutable()->pitchDegrees = 90; // vertical breakout board
91 barometerConfigMutable()->baro_hardware = BARO_DEFAULT; // still testing not on V1 or V2 pcb
92 #else
93 barometerConfigMutable()->baro_hardware = BARO_NONE;
94 #endif
96 compassConfigMutable()->mag_hardware = MAG_NONE;
98 /* Default to 32kHz enabled at 16/16 */
99 gyroConfigMutable()->gyro_use_32khz = 1; // enable 32kHz sampling
100 gyroConfigMutable()->gyroMovementCalibrationThreshold = 200; // aka moron_threshold
101 gyroConfigMutable()->gyro_sync_denom = 2; // 16kHz gyro
102 pidConfigMutable()->pid_process_denom = 1; // 16kHz PID
104 featureSet((FEATURE_DYNAMIC_FILTER | FEATURE_AIRMODE | FEATURE_ANTI_GRAVITY) ^ FEATURE_RX_PARALLEL_PWM);
106 /* AlienWhoop PIDs based on Ole Gravy Leg (aka Matt Williamson's) PIDs
108 for (uint8_t pidProfileIndex = 0; pidProfileIndex < MAX_PROFILE_COUNT; pidProfileIndex++) {
109 pidProfile_t *pidProfile = pidProfilesMutable(pidProfileIndex);
111 /* AlienWhoop PIDs tested with 6mm and 7mm motors on most frames */
112 pidProfile->pid[PID_PITCH].P = 75;
113 pidProfile->pid[PID_PITCH].I = 36;
114 pidProfile->pid[PID_PITCH].D = 25;
115 pidProfile->pid[PID_ROLL].P = 75;
116 pidProfile->pid[PID_ROLL].I = 36;
117 pidProfile->pid[PID_ROLL].D = 25;
118 pidProfile->pid[PID_YAW].P = 70;
119 pidProfile->pid[PID_YAW].I = 36;
121 pidProfile->pid[PID_LEVEL].P = 30;
122 pidProfile->pid[PID_LEVEL].D = 30;
124 /* Setpoints */
125 pidProfile->dtermSetpointWeight = 100;
126 pidProfile->setpointRelaxRatio = 100;
128 /* Throttle PID Attenuation (TPA) */
129 pidProfile->itermThrottleThreshold = 400;
132 for (uint8_t rateProfileIndex = 0; rateProfileIndex < CONTROL_RATE_PROFILE_COUNT; rateProfileIndex++) {
133 controlRateConfig_t *controlRateConfig = controlRateProfilesMutable(rateProfileIndex);
135 /* RC Rates */
136 controlRateConfig->rcRates[FD_ROLL] = 100;
137 controlRateConfig->rcRates[FD_PITCH] = 100;
138 controlRateConfig->rcRates[FD_YAW] = 100;
139 controlRateConfig->rcExpo[FD_ROLL] = 0;
140 controlRateConfig->rcExpo[FD_PITCH] = 0;
142 /* Super Expo Rates */
143 controlRateConfig->rates[FD_ROLL] = 80;
144 controlRateConfig->rates[FD_PITCH] = 80;
145 controlRateConfig->rates[FD_YAW] = 85;
147 /* Throttle PID Attenuation (TPA) */
148 controlRateConfig->dynThrPID = 0; // tpa_rate off
149 controlRateConfig->tpa_breakpoint = 1650;
152 #endif