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/>.
27 #ifdef USE_TARGET_CONFIG
29 #include "common/axis.h"
30 #include "common/maths.h"
32 #include "config/feature.h"
34 #include "drivers/light_led.h"
35 #include "drivers/pwm_esc_detect.h"
37 #include "fc/config.h"
38 #include "fc/controlrate_profile.h"
39 #include "fc/rc_modes.h"
40 #include "fc/rc_controls.h"
42 #include "flight/mixer.h"
43 #include "flight/pid.h"
49 #include "io/serial.h"
52 #include "sensors/battery.h"
53 #include "sensors/gyro.h"
55 #include "telemetry/telemetry.h"
57 #if !defined(BEEBRAIN_V2D)
58 #define BBV2_FRSKY_RSSI_CH_IDX 9
61 #ifdef BRUSHED_MOTORS_PWM_RATE
62 #undef BRUSHED_MOTORS_PWM_RATE
65 #define BRUSHED_MOTORS_PWM_RATE 32000 // 32kHz
67 void targetConfiguration(void)
69 if (hardwareMotorType
== MOTOR_BRUSHED
) {
70 motorConfigMutable()->dev
.motorPwmRate
= BRUSHED_MOTORS_PWM_RATE
;
71 motorConfigMutable()->minthrottle
= 1030;
72 pidConfigMutable()->pid_process_denom
= 1;
75 for (uint8_t pidProfileIndex
= 0; pidProfileIndex
< MAX_PROFILE_COUNT
; pidProfileIndex
++) {
76 pidProfile_t
*pidProfile
= pidProfilesMutable(pidProfileIndex
);
78 pidProfile
->pid
[PID_ROLL
].P
= 86;
79 pidProfile
->pid
[PID_ROLL
].I
= 50;
80 pidProfile
->pid
[PID_ROLL
].D
= 60;
81 pidProfile
->pid
[PID_PITCH
].P
= 90;
82 pidProfile
->pid
[PID_PITCH
].I
= 55;
83 pidProfile
->pid
[PID_PITCH
].D
= 60;
84 pidProfile
->pid
[PID_YAW
].P
= 123;
85 pidProfile
->pid
[PID_YAW
].I
= 75;
88 for (uint8_t rateProfileIndex
= 0; rateProfileIndex
< CONTROL_RATE_PROFILE_COUNT
; rateProfileIndex
++) {
89 controlRateConfig_t
*controlRateConfig
= controlRateProfilesMutable(rateProfileIndex
);
91 controlRateConfig
->rcRates
[FD_YAW
] = 120;
92 controlRateConfig
->rcExpo
[FD_ROLL
] = 15;
93 controlRateConfig
->rcExpo
[FD_PITCH
] = 15;
94 controlRateConfig
->rcExpo
[FD_YAW
] = 15;
95 controlRateConfig
->rates
[FD_ROLL
] = 85;
96 controlRateConfig
->rates
[FD_PITCH
] = 85;
99 batteryConfigMutable()->batteryCapacity
= 250;
100 batteryConfigMutable()->vbatmincellvoltage
= 28;
101 batteryConfigMutable()->vbatwarningcellvoltage
= 33;
103 *customMotorMixerMutable(0) = (motorMixer_t
){ 1.0f
, -0.414178f
, 1.0f
, -1.0f
}; // REAR_R
104 *customMotorMixerMutable(1) = (motorMixer_t
){ 1.0f
, -0.414178f
, -1.0f
, 1.0f
}; // FRONT_R
105 *customMotorMixerMutable(2) = (motorMixer_t
){ 1.0f
, 0.414178f
, 1.0f
, 1.0f
}; // REAR_L
106 *customMotorMixerMutable(3) = (motorMixer_t
){ 1.0f
, 0.414178f
, -1.0f
, -1.0f
}; // FRONT_L
108 vcdProfileMutable()->video_system
= VIDEO_SYSTEM_NTSC
;
109 #if defined(BEESTORM)
110 strcpy(pilotConfigMutable()->name
, "BeeStorm");
112 strcpy(pilotConfigMutable()->name
, "BeeBrain V2");
114 osdConfigMutable()->cap_alarm
= 250;
115 osdConfigMutable()->item_pos
[OSD_CRAFT_NAME
] = OSD_POS(9, 11) | VISIBLE_FLAG
;
116 osdConfigMutable()->item_pos
[OSD_MAIN_BATT_VOLTAGE
] = OSD_POS(23, 10) | VISIBLE_FLAG
;
117 osdConfigMutable()->item_pos
[OSD_ITEM_TIMER_2
] = OSD_POS(2, 10) | VISIBLE_FLAG
;
118 osdConfigMutable()->item_pos
[OSD_FLYMODE
] = OSD_POS(17, 10) | VISIBLE_FLAG
;
119 osdConfigMutable()->item_pos
[OSD_VTX_CHANNEL
] = OSD_POS(10, 10) | VISIBLE_FLAG
;
120 osdConfigMutable()->item_pos
[OSD_RSSI_VALUE
] &= ~VISIBLE_FLAG
;
121 osdConfigMutable()->item_pos
[OSD_ITEM_TIMER_1
] &= ~VISIBLE_FLAG
;
122 osdConfigMutable()->item_pos
[OSD_THROTTLE_POS
] &= ~VISIBLE_FLAG
;
123 osdConfigMutable()->item_pos
[OSD_CROSSHAIRS
] &= ~VISIBLE_FLAG
;
124 osdConfigMutable()->item_pos
[OSD_HORIZON_SIDEBARS
] &= ~VISIBLE_FLAG
;
125 osdConfigMutable()->item_pos
[OSD_ARTIFICIAL_HORIZON
] &= ~VISIBLE_FLAG
;
126 osdConfigMutable()->item_pos
[OSD_CURRENT_DRAW
] &= ~VISIBLE_FLAG
;
127 osdConfigMutable()->item_pos
[OSD_MAH_DRAWN
] &= ~VISIBLE_FLAG
;
128 osdConfigMutable()->item_pos
[OSD_GPS_SPEED
] &= ~VISIBLE_FLAG
;
129 osdConfigMutable()->item_pos
[OSD_GPS_LON
] &= ~VISIBLE_FLAG
;
130 osdConfigMutable()->item_pos
[OSD_GPS_LAT
] &= ~VISIBLE_FLAG
;
131 osdConfigMutable()->item_pos
[OSD_GPS_SATS
] &= ~VISIBLE_FLAG
;
132 osdConfigMutable()->item_pos
[OSD_HOME_DIR
] &= ~VISIBLE_FLAG
;
133 osdConfigMutable()->item_pos
[OSD_HOME_DIST
] &= ~VISIBLE_FLAG
;
134 osdConfigMutable()->item_pos
[OSD_COMPASS_BAR
] &= ~VISIBLE_FLAG
;
135 osdConfigMutable()->item_pos
[OSD_ALTITUDE
] &= ~VISIBLE_FLAG
;
136 osdConfigMutable()->item_pos
[OSD_ROLL_PIDS
] &= ~VISIBLE_FLAG
;
137 osdConfigMutable()->item_pos
[OSD_PITCH_PIDS
] &= ~VISIBLE_FLAG
;
138 osdConfigMutable()->item_pos
[OSD_YAW_PIDS
] &= ~VISIBLE_FLAG
;
139 osdConfigMutable()->item_pos
[OSD_DEBUG
] &= ~VISIBLE_FLAG
;
140 osdConfigMutable()->item_pos
[OSD_POWER
] &= ~VISIBLE_FLAG
;
141 osdConfigMutable()->item_pos
[OSD_PIDRATE_PROFILE
] &= ~VISIBLE_FLAG
;
142 osdConfigMutable()->item_pos
[OSD_WARNINGS
] &= ~VISIBLE_FLAG
;
143 osdConfigMutable()->item_pos
[OSD_AVG_CELL_VOLTAGE
] &= ~VISIBLE_FLAG
;
144 osdConfigMutable()->item_pos
[OSD_PITCH_ANGLE
] &= ~VISIBLE_FLAG
;
145 osdConfigMutable()->item_pos
[OSD_ROLL_ANGLE
] &= ~VISIBLE_FLAG
;
146 osdConfigMutable()->item_pos
[OSD_MAIN_BATT_USAGE
] &= ~VISIBLE_FLAG
;
147 osdConfigMutable()->item_pos
[OSD_DISARMED
] &= ~VISIBLE_FLAG
;
148 osdConfigMutable()->item_pos
[OSD_NUMERICAL_HEADING
] &= ~VISIBLE_FLAG
;
149 osdConfigMutable()->item_pos
[OSD_NUMERICAL_VARIO
] &= ~VISIBLE_FLAG
;
150 osdConfigMutable()->item_pos
[OSD_ESC_TMP
] &= ~VISIBLE_FLAG
;
151 osdConfigMutable()->item_pos
[OSD_ESC_RPM
] &= ~VISIBLE_FLAG
;
153 modeActivationConditionsMutable(0)->modeId
= BOXANGLE
;
154 modeActivationConditionsMutable(0)->auxChannelIndex
= AUX2
- NON_AUX_CHANNEL_COUNT
;
155 modeActivationConditionsMutable(0)->range
.startStep
= CHANNEL_VALUE_TO_STEP(900);
156 modeActivationConditionsMutable(0)->range
.endStep
= CHANNEL_VALUE_TO_STEP(2100);
158 #if defined(BEEBRAIN_V2D)
160 for (uint8_t rxRangeIndex
= 0; rxRangeIndex
< NON_AUX_CHANNEL_COUNT
; rxRangeIndex
++) {
161 rxChannelRangeConfig_t
*channelRangeConfig
= rxChannelRangeConfigsMutable(rxRangeIndex
);
163 channelRangeConfig
->min
= 1160;
164 channelRangeConfig
->max
= 1840;
168 serialConfigMutable()->portConfigs
[findSerialPortIndexByIdentifier(SERIALRX_UART
)].functionMask
= FUNCTION_TELEMETRY_FRSKY_HUB
| FUNCTION_RX_SERIAL
;
169 rxConfigMutable()->rssi_channel
= BBV2_FRSKY_RSSI_CH_IDX
;
170 rxFailsafeChannelConfig_t
*channelFailsafeConfig
= rxFailsafeChannelConfigsMutable(BBV2_FRSKY_RSSI_CH_IDX
- 1);
171 channelFailsafeConfig
->mode
= RX_FAILSAFE_MODE_SET
;
172 channelFailsafeConfig
->step
= CHANNEL_VALUE_TO_RXFAIL_STEP(1000);
173 osdConfigMutable()->item_pos
[OSD_RSSI_VALUE
] = OSD_POS(2, 11) | VISIBLE_FLAG
;