add SPL06 in Matek targets
[inav/snaewe.git] / src / main / target / FALCORE / config.c
blob2deb50522657d86e6ddf5741e15f172cc5fe660e
1 /*
2 * This file is part of Cleanflight.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
18 #include <stdint.h>
19 #include "platform.h"
20 #include "config/feature.h"
21 #include "drivers/pwm_output.h"
22 #include "drivers/pwm_mapping.h"
23 #include "blackbox/blackbox.h"
24 #include "fc/config.h"
25 #include "fc/controlrate_profile.h"
26 #include "fc/rc_controls.h"
27 #include "fc/rc_modes.h"
28 #include "io/serial.h"
29 #include "rx/rx.h"
30 #include "sensors/sensors.h"
31 #include "sensors/gyro.h"
32 #include "sensors/acceleration.h"
33 #include "sensors/barometer.h"
34 #include "sensors/compass.h"
35 #include "sensors/boardalignment.h"
36 #include "flight/pid.h"
37 #include "flight/mixer.h"
38 #include "flight/servos.h"
39 #include "flight/imu.h"
40 #include "flight/failsafe.h"
41 #include "navigation/navigation.h"
44 void targetConfiguration(void)
46 mixerConfigMutable()->platformType = PLATFORM_MULTIROTOR;
48 featureSet(FEATURE_VBAT);
49 featureSet(FEATURE_GPS);
50 featureSet(FEATURE_TELEMETRY);
51 featureSet(FEATURE_LED_STRIP);
52 featureSet(FEATURE_BLACKBOX);
54 serialConfigMutable()->portConfigs[0].functionMask = FUNCTION_MSP; // VCP
55 serialConfigMutable()->portConfigs[1].functionMask = FUNCTION_GPS; // UART1
56 serialConfigMutable()->portConfigs[2].functionMask = FUNCTION_RX_SERIAL; // UART2
57 serialConfigMutable()->portConfigs[3].functionMask = FUNCTION_NONE; // UART4
58 serialConfigMutable()->portConfigs[4].functionMask = FUNCTION_TELEMETRY_MAVLINK; // UART5
61 gyroConfigMutable()->looptime = 1000;
62 gyroConfigMutable()->gyro_lpf = 0; // 256 Hz
63 gyroConfigMutable()->gyro_main_lpf_hz = 90;
65 accelerometerConfigMutable()->acc_hardware = ACC_MPU6500;
66 accelerometerConfigMutable()->acc_lpf_hz = 15;
68 compassConfigMutable()->mag_hardware = MAG_HMC5883;
69 compassConfigMutable()->mag_align = CW270_DEG_FLIP;
71 barometerConfigMutable()->baro_hardware = BARO_MS5607;
72 barometerConfigMutable()->use_median_filtering = 1;
74 rxConfigMutable()->receiverType = RX_TYPE_SERIAL;
75 rxConfigMutable()->serialrx_provider = SERIALRX_IBUS;
76 rxConfigMutable()->mincheck = 1100;
77 rxConfigMutable()->maxcheck = 1900;
79 blackboxConfigMutable()->rate_num = 1;
80 blackboxConfigMutable()->rate_denom = 4;
82 motorConfigMutable()->maxthrottle = 2000;
83 motorConfigMutable()->mincommand = 980;
84 motorConfigMutable()->motorPwmRate = 2000;
85 motorConfigMutable()->motorPwmProtocol = PWM_TYPE_ONESHOT125;
87 failsafeConfigMutable()->failsafe_delay = 5;
88 failsafeConfigMutable()->failsafe_recovery_delay = 5;
89 failsafeConfigMutable()->failsafe_off_delay = 200;
90 currentBatteryProfile->failsafe_throttle = 1200;
91 failsafeConfigMutable()->failsafe_procedure = FAILSAFE_PROCEDURE_RTH;
93 boardAlignmentMutable()->rollDeciDegrees = 0;
94 boardAlignmentMutable()->pitchDeciDegrees = 165;
95 boardAlignmentMutable()->yawDeciDegrees = 0;
97 imuConfigMutable()->small_angle = 30;
99 gpsConfigMutable()->provider = GPS_UBLOX;
100 gpsConfigMutable()->sbasMode = SBAS_NONE;
101 gpsConfigMutable()->dynModel = GPS_DYNMODEL_AIR_1G;
102 gpsConfigMutable()->autoConfig = 1;
103 gpsConfigMutable()->autoBaud = 1;
104 gpsConfigMutable()->gpsMinSats = 7;
106 rcControlsConfigMutable()->deadband = 10;
107 rcControlsConfigMutable()->yaw_deadband = 15;
109 navConfigMutable()->general.flags.disarm_on_landing = 1;
110 navConfigMutable()->general.flags.use_thr_mid_for_althold = 1;
111 navConfigMutable()->general.flags.extra_arming_safety = 1;
112 navConfigMutable()->general.flags.rth_allow_landing = NAV_RTH_ALLOW_LANDING_ALWAYS;
114 navConfigMutable()->general.max_auto_speed = 500;
115 navConfigMutable()->general.max_auto_climb_rate = 200;
116 navConfigMutable()->general.max_manual_speed = 500;
117 navConfigMutable()->general.max_manual_climb_rate = 200;
118 navConfigMutable()->general.rth_altitude = 1000;
120 navConfigMutable()->mc.max_bank_angle = 30;
121 currentBatteryProfile->nav.mc.hover_throttle = 1500;
122 navConfigMutable()->mc.auto_disarm_delay = 2000;
125 aux 0 0 0 1150 2100
126 aux 1 2 0 1300 1700
127 aux 2 20 0 1150 2100
128 aux 3 3 3 1300 1700
129 aux 4 9 3 1300 1700
130 aux 5 8 3 1700 2100
131 aux 6 19 1 1375 2100
134 for (int index = 0; index < MAX_MODE_ACTIVATION_CONDITION_COUNT; index++) {
135 modeActivationConditionsMutable(index)->modeId = 0;
136 modeActivationConditionsMutable(index)->auxChannelIndex = 0;
137 modeActivationConditionsMutable(index)->range.startStep = 0;
138 modeActivationConditionsMutable(index)->range.endStep = 0;
141 configureModeActivationCondition(0, BOXARM, 0, 1150, 2100);
142 configureModeActivationCondition(1, BOXANGLE, 0, 1300, 1700);
143 configureModeActivationCondition(2, BOXNAVALTHOLD, 3, 1300, 1700);
144 configureModeActivationCondition(3, BOXNAVPOSHOLD, 3, 1300, 1700);
145 configureModeActivationCondition(4, BOXNAVRTH, 3, 1700, 2100);
146 configureModeActivationCondition(5, BOXANGLE, 3, 1700, 2100);
148 // Rates and PIDs
149 setConfigProfile(0);
150 pidProfileMutable()->bank_mc.pid[PID_PITCH].P = 65;
151 pidProfileMutable()->bank_mc.pid[PID_PITCH].I = 50;
152 pidProfileMutable()->bank_mc.pid[PID_PITCH].D = 28;
153 pidProfileMutable()->bank_mc.pid[PID_ROLL].P = 45;
154 pidProfileMutable()->bank_mc.pid[PID_ROLL].I = 40;
155 pidProfileMutable()->bank_mc.pid[PID_ROLL].D = 25;
156 pidProfileMutable()->bank_mc.pid[PID_YAW].P = 90;
157 pidProfileMutable()->bank_mc.pid[PID_YAW].I = 45;
158 pidProfileMutable()->bank_mc.pid[PID_YAW].D = 0;
159 pidProfileMutable()->bank_mc.pid[PID_LEVEL].P = 20;
160 pidProfileMutable()->bank_mc.pid[PID_LEVEL].I = 10;
161 pidProfileMutable()->bank_mc.pid[PID_LEVEL].D = 75;
163 pidProfileMutable()->max_angle_inclination[FD_ROLL] = 300;
164 pidProfileMutable()->max_angle_inclination[FD_PITCH] = 300;
165 pidProfileMutable()->dterm_lpf_hz = 70;
166 pidProfileMutable()->yaw_lpf_hz = 35;
167 pidProfileMutable()->pidSumLimit = 500;
168 pidProfileMutable()->axisAccelerationLimitRollPitch = 0;
169 pidProfileMutable()->axisAccelerationLimitYaw = 10000;
171 pidProfileMutable()->bank_mc.pid[PID_POS_Z].P = 50;
172 pidProfileMutable()->bank_mc.pid[PID_POS_Z].I = 0;
173 pidProfileMutable()->bank_mc.pid[PID_POS_Z].D = 0;
174 pidProfileMutable()->bank_mc.pid[PID_VEL_Z].P = 100;
175 pidProfileMutable()->bank_mc.pid[PID_VEL_Z].I = 50;
176 pidProfileMutable()->bank_mc.pid[PID_VEL_Z].D = 10;
177 pidProfileMutable()->bank_mc.pid[PID_POS_XY].P = 50;
178 pidProfileMutable()->bank_mc.pid[PID_POS_XY].I = 100;
179 pidProfileMutable()->bank_mc.pid[PID_POS_XY].D = 10;
180 pidProfileMutable()->bank_mc.pid[PID_VEL_XY].P = 150;
181 pidProfileMutable()->bank_mc.pid[PID_VEL_XY].I = 20;
182 pidProfileMutable()->bank_mc.pid[PID_VEL_XY].D = 70;
184 ((controlRateConfig_t*)currentControlRateProfile)->stabilized.rcExpo8 = 60;
185 ((controlRateConfig_t*)currentControlRateProfile)->stabilized.rcYawExpo8 = 35;
186 ((controlRateConfig_t*)currentControlRateProfile)->stabilized.rates[FD_ROLL] = 54;
187 ((controlRateConfig_t*)currentControlRateProfile)->stabilized.rates[FD_PITCH] = 54;
188 ((controlRateConfig_t*)currentControlRateProfile)->stabilized.rates[FD_YAW] = 36;
189 ((controlRateConfig_t*)currentControlRateProfile)->throttle.rcMid8 = 50;
190 ((controlRateConfig_t*)currentControlRateProfile)->throttle.rcExpo8 = 0;
191 ((controlRateConfig_t*)currentControlRateProfile)->throttle.dynPID = 10;
192 ((controlRateConfig_t*)currentControlRateProfile)->throttle.pa_breakpoint = 1600;
194 beeperConfigMutable()->pwmMode = true;