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)
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...
42 #ifdef USE_TARGET_CONFIG
44 #include "blackbox/blackbox.h"
45 #include "fc/rc_modes.h"
46 #include "common/axis.h"
47 #include "common/filter.h"
48 #include "config/feature.h"
49 #include "drivers/pwm_esc_detect.h"
50 #include "config/config.h"
51 #include "fc/controlrate_profile.h"
52 #include "fc/rc_controls.h"
53 #include "fc/rc_modes.h"
54 #include "flight/imu.h"
55 #include "flight/mixer.h"
56 #include "flight/pid.h"
57 #include "io/beeper.h"
58 #include "io/serial.h"
62 #include "sensors/barometer.h"
63 #include "sensors/boardalignment.h"
64 #include "sensors/compass.h"
65 #include "sensors/gyro.h"
67 #ifdef BRUSHED_MOTORS_PWM_RATE
68 #undef BRUSHED_MOTORS_PWM_RATE
71 #define BRUSHED_MOTORS_PWM_RATE 32000
74 void targetConfiguration(void)
76 if (getDetectedMotorType() == MOTOR_BRUSHED
) {
77 motorConfigMutable()->dev
.motorPwmRate
= BRUSHED_MOTORS_PWM_RATE
;
78 motorConfigMutable()->minthrottle
= 1050; // for 6mm and 7mm brushed
81 /* Default to Spektrum */
82 rxConfigMutable()->serialrx_provider
= SERIALRX_SPEKTRUM2048
; // all DSM* except DSM2 22ms
83 rxConfigMutable()->spektrum_sat_bind
= 5; // DSM2 11ms
84 rxConfigMutable()->spektrum_sat_bind_autoreset
= 1;
85 rxConfigMutable()->mincheck
= 1025;
86 parseRcChannels("TAER1234", rxConfigMutable());
88 mixerConfigMutable()->yaw_motors_reversed
= true;
89 imuConfigMutable()->small_angle
= 180;
91 blackboxConfigMutable()->sample_rate
= 1; // sample_rate is half of PID loop frequency
93 /* Breadboard-specific settings for development purposes only
95 #if defined(BREADBOARD)
96 boardAlignmentMutable()->pitchDegrees
= 90; // vertical breakout board
97 barometerConfigMutable()->baro_hardware
= BARO_DEFAULT
; // still testing not on V1 or V2 pcb
100 compassConfigMutable()->mag_hardware
= MAG_NONE
;
102 systemConfigMutable()->cpu_overclock
= 2; //216MHZ
104 pidConfigMutable()->runaway_takeoff_prevention
= false;
106 featureConfigSet((FEATURE_AIRMODE
| FEATURE_ANTI_GRAVITY
) ^ FEATURE_RX_PARALLEL_PWM
);
108 /* AlienWhoop PIDs tested with 6mm and 7mm motors on most frames */
109 for (uint8_t pidProfileIndex
= 0; pidProfileIndex
< PID_PROFILE_COUNT
; pidProfileIndex
++) {
110 pidProfile_t
*pidProfile
= pidProfilesMutable(pidProfileIndex
);
112 pidProfile
->pidSumLimit
= 1000;
113 pidProfile
->pidSumLimitYaw
= 1000;
115 /* AlienWhoop PIDs tested with 6mm and 7mm motors on most frames */
116 pidProfile
->pid
[PID_PITCH
].P
= 115;
117 pidProfile
->pid
[PID_PITCH
].I
= 75;
118 pidProfile
->pid
[PID_PITCH
].D
= 95;
119 pidProfile
->pid
[PID_ROLL
].P
= 110;
120 pidProfile
->pid
[PID_ROLL
].I
= 75;
121 pidProfile
->pid
[PID_ROLL
].D
= 85;
122 pidProfile
->pid
[PID_YAW
].P
= 220;
123 pidProfile
->pid
[PID_YAW
].I
= 75;
124 pidProfile
->pid
[PID_YAW
].D
= 20;
125 pidProfile
->pid
[PID_LEVEL
].P
= 65;
126 pidProfile
->pid
[PID_LEVEL
].I
= 65;
127 pidProfile
->pid
[PID_LEVEL
].D
= 55;
130 pidProfile
->dterm_lpf1_type
= FILTER_BIQUAD
;
131 pidProfile
->dterm_notch_hz
= 0;
132 pidProfile
->pid
[PID_PITCH
].F
= 100;
133 pidProfile
->pid
[PID_ROLL
].F
= 100;
134 pidProfile
->feedforward_transition
= 0;
137 pidProfile
->itermThrottleThreshold
= 500;
138 pidProfile
->itermAcceleratorGain
= 5000;
140 pidProfile
->levelAngleLimit
= 65;
143 for (uint8_t rateProfileIndex
= 0; rateProfileIndex
< CONTROL_RATE_PROFILE_COUNT
; rateProfileIndex
++) {
144 controlRateConfig_t
*controlRateConfig
= controlRateProfilesMutable(rateProfileIndex
);
147 controlRateConfig
->rcRates
[FD_ROLL
] = 218;
148 controlRateConfig
->rcRates
[FD_PITCH
] = 218;
149 controlRateConfig
->rcRates
[FD_YAW
] = 218;
152 controlRateConfig
->rcExpo
[FD_ROLL
] = 45;
153 controlRateConfig
->rcExpo
[FD_PITCH
] = 45;
154 controlRateConfig
->rcExpo
[FD_YAW
] = 45;
156 /* Super Expo Rates */
157 controlRateConfig
->rates
[FD_ROLL
] = 0;
158 controlRateConfig
->rates
[FD_PITCH
] = 0;
159 controlRateConfig
->rates
[FD_YAW
] = 0;
161 /* Throttle PID Attenuation (TPA) */
162 controlRateConfig
->dynThrPID
= 0; // tpa_rate off
163 controlRateConfig
->tpa_breakpoint
= 1600;
165 /* Force the clipping mixer at 100% seems better for brushed than default (off) and scaling)? */
166 controlRateConfig
->throttle_limit_type
= THROTTLE_LIMIT_TYPE_CLIP
;
167 //controlRateConfig->throttle_limit_percent = 100;
169 controlRateConfig
->thrExpo8
= 20; // 20% throttle expo