Merge pull request #11513 from 4712/Serial-4way-if_v2006
[betaflight.git] / docs / Mixer.md
blob2fd63a10281111ea3f58056db1007818f4a03c29
1 # Mixer
3 Cleanflight supports a number of mixing configurations as well as custom mixing.  Mixer configurations determine how the servos and motors work together to control the aircraft.
5 ## Configuration
7 To use a built-in mixing configuration, you can use the Chrome configuration GUI.  It includes images of the various mixer types to assist in making the proper connections.  See the Configuration section of the documentation for more information on the GUI.
9 You can also use the Command Line Interface (CLI) to set the mixer type:
11 1. Use `mixer list` to see a list of supported mixes
12 2. Select a mixer.  For example, to select TRI, use `mixer TRI`
13 3. You must use `save` to preserve your changes
15 ## Supported Mixer Types
17 | Name             | Description               | Motors         | Servos           |
18 | ---------------- | ------------------------- | -------------- | ---------------- |
19 | TRI              | Tricopter                 | M1-M3          | S1               |
20 | QUADP            | Quadcopter-Plus           | M1-M4          | None             |
21 | QUADX            | Quadcopter-X              | M1-M4          | None             |
22 | BI               | Bicopter (left/right)     | M1-M2          | S1, S2           |
23 | GIMBAL           | Gimbal control            | N/A            | S1, S2           |
24 | Y6               | Y6-copter                 | M1-M6          | None             |
25 | HEX6             | Hexacopter-Plus           | M1-M6          | None             |
26 | FLYING\_WING      | Fixed wing; elevons       | M1             | S1, S2           |
27 | Y4               | Y4-copter                 | M1-M4          | None             |
28 | HEX6X            | Hexacopter-X              | M1-M6          | None             |
29 | OCTOX8           | Octocopter-X (over/under) | M1-M8          | None             |
30 | OCTOFLATP        | Octocopter-FlatPlus       | M1-M8          | None             |
31 | OCTOFLATX        | Octocopter-FlatX          | M1-M8          | None             |
32 | AIRPLANE         | Fixed wing; Ax2, R, E     | M1             | S1, S2, S3, S4   |
33 | HELI\_120\_CCPM    | 3D-capable Helicopter     | M1             | S1, S2, S3, S4   |
34 | HELI\_90\_DEG      |                           |                |                  |
35 | VTAIL4           | Quadcopter with V-Tail    | M1-M4          | N/A              |
36 | HEX6H            | Hexacopter-H              | M1-M6          | None             |
37 | PPM\_TO\_SERVO     |                           |                |                  |
38 | DUALCOPTER       | Dualcopter                | M1-M2          | S1, S2           |
39 | SINGLECOPTER     | Conventional helicopter   | M1             | S1               |
40 | ATAIL4           | Quadcopter with A-Tail    | M1-M4          | N/A              |
41 | CUSTOM           | User-defined              |                |                  |
42 | CUSTOM AIRPLANE  | User-defined airplane     | M1-M2          | S1-S8            |
43 | CUSTOM TRICOPTER | User-defined tricopter    |                |                  |
45 ## Servo configuration
47 The cli `servo` command defines the settings for the servo outputs.
48 The cli mixer `smix` command controls how the mixer maps internal FC data (RC input, PID stabilization output, channel forwarding, etc) to servo outputs.
50 ### Channel Forwarding
52 Channel Forwarding allows you to forward your AUX channels directly to servos over PWM pins 5-8. You can enable it under features in the GUI or using the cli 
53 with ``feature CHANNEL_FORWARDING``. This requires you to run PPM or another serial RC protocol, and is currently supported on NAZE and SPRACINGF3 targets.
54 Note that if you have the led feature enabled on the NAZE target,  AUX1-2 is mapped to PWM13-14 instead. So for instance if you enable this feature on a Naze
55 AUX1 from your receiver will automatically be forwarded to PWM5 as a servo signal.
57 ### cli `servo`
59 `servo <min> <max> <middle> <angleMin> <angleMax> <rate> <forwardFromChannel>`
61 - `<min>`, `<max>` - limit servo travel, in uS
63 - `<middle>` - mid value when not forwarding, value from servo mixer is added to this.
65 - `<angleMin>`,  `<angleMax>` - unused
67 - `<rate>` - scale for value from servo mixer or gimbal input, -100% .. 100%
69 - `<forwardFromChannel>` - use RC channel value as reference instead of `<middle>`. Servo will follow given RC channel, with possible correction from servo mixer. `<min>`, `<max>` are still honored.
72 ## Servo filtering
74 A low-pass filter can be enabled for the servos.  It may be useful for avoiding structural modes in the airframe, for example.
76 ### Configuration
78 Currently it can only be configured via the CLI:
80 1. Use `set servo_lowpass_freq = nnn` to select the cutoff frequency.  Valid values range from 10Hz to 400Hz, second order filter is used.
81 2. Use `set servo_lowpass_enable = ON` to enable filtering.
83 ### Tuning
85 One method for tuning the filter cutoff is as follows:
87 1. Ensure your vehicle can move at least somewhat freely in the troublesome axis.  For example, if you are having yaw oscillations on a tricopter, ensure that the copter is supported in a way that allows it to rotate left and right to at least some degree.  Suspension near the CG is ideal.  Alternatively, you can just fly the vehicle and trigger the problematic condition you are trying to eliminate, although tuning will be more tedious.
89 2. Tap the vehicle at its end in the axis under evaluation.  Directly commanding the servo in question to move may also be used.  In the tricopter example, tap the end of the tail boom from the side, or command a yaw using your transmitter.
91 3. If your vehicle oscillates for several seconds or even continues oscillating indefinitely, then the filter cutoff frequency should be reduced. Reduce the value of `servo_lowpass_freq` by half its current value and repeat the previous step.
93 4. If the oscillations are dampened within roughly a second or are no longer present, then you are done.  Be sure to run `save`.
95 ## Custom Motor Mixing
97 Custom motor mixing allows for completely customized motor configurations. Each motor must be defined with a custom mixing table for that motor. The mix must reflect how close each motor is with reference to the CG (Center of Gravity) of the flight controller. A motor closer to the CG of the flight controller will need to travel less distance than a motor further away.
99 Steps to configure custom mixer in the CLI:
101 1. Use `mixer custom` to enable the custom mixing.
102 2. Use `mmix reset` to erase the any existing custom mixing.
103 3. Optionally use `mmix load <name>` to start with one of available mixers.
104 4. Issue a `mmix` statement for each motor.
106 The `mmix` statement has the following syntax: `mmix n THROTTLE ROLL PITCH YAW`
108 | Mixing table parameter | Definition |
109 | ---------------------- | ---------- |
110 | n                      | Motor ordering number |
111 | THROTTLE               | Indicates how much throttle is mixed for this motor. All values used in current configurations are set to 1.0 (full throttle mixing), but other non-zero values may be used. Unused set to 0.0. |
112 | ROLL                   | Indicates how much roll authority this motor imparts to the roll of the flight controller. Accepts values nominally from -1.0 to 1.0. |
113 | PITCH                  | Indicates the pitch authority this motor has over the flight controller. Also accepts values nominally from -1.0 to 1.0. |
114 | YAW                    | Indicates the direction of the motor rotation in relationship with the flight controller. 1.0 = CCW -1.0 = CW. |
116 Note: the `mmix` command may show a motor mix that is not active, custom motor mixes are only active for models that use custom mixers.
118 Note: You have to configure every motor number starting at 0. Your command will be ignored if there was no `mmix` command for the previous motor number (mixer stops on first THROTTLE value that is zero). See example 5.
121 ## Custom Servo Mixing
123 Custom servo mixing rules can be applied to each servo.  Rules are applied in the order they are defined.
125 ##### `smix`
127 Prints current servo mixer
129 Note: the `smix` command may show a servo mix that is not active, custom servo mixes are only active for models that use custom mixers.
131 ##### `smix reset`
133 Erase custom mixer. Servo reversal in current profile ONLY is erased too.
135 ##### `smix load <name>`
137 Load servo part of given configuration (`<name>` is from `mixer list`)
139 ##### `smix <rule> <servo> <source> <rate> <speed> <min> <max> <box>`
141 - `<rule>` is index of rule, used mainly for bookkeeping. Rules are applied in this order, but ordering has no influence on result in current code.
143 - `<servo>`
145 | id |  Servo slot |
146 |----|--------------|
147 | 0  | GIMBAL PITCH |
148 | 1  | GIMBAL ROLL |
149 | 2  | ELEVATOR / SINGLECOPTER\_4 |
150 | 3  | FLAPPERON 1 (LEFT) / SINGLECOPTER\_1 |
151 | 4  | FLAPPERON 2 (RIGHT) / BICOPTER\_LEFT / DUALCOPTER\_LEFT / SINGLECOPTER\_2 |
152 | 5  | RUDDER / BICOPTER\_RIGHT / DUALCOPTER\_RIGHT / SINGLECOPTER\_3 |
153 | 6  | THROTTLE (Based ONLY on the first motor output) |
154 | 7  | FLAPS |
156 Only some `<servo>` channels are connected to output, based on mode. For custom modes:
157   - RUDDER for CUSTOM\_TRI
158   - ELEVATOR ... FLAPS for CUSTOM\_AIRPLANE
159   - no servos for CUSTOM
161 GIMBAL handling is hard-coded, mmix rule is ignored.
163 - `<source>`
165 | id |  Input sources |
166 |----|-----------------|
167 | 0  | Stabilized ROLL |
168 | 1  | Stabilized PITCH |
169 | 2  | Stabilized YAW |
170 | 3  | Stabilized THROTTLE (ONLY the first motor output) |
171 | 4  | RC ROLL |
172 | 5  | RC PITCH |
173 | 6  | RC YAW |
174 | 7  | RC THROTTLE |
175 | 8  | RC AUX 1 |
176 | 9  | RC AUX 2 |
177 | 10 | RC AUX 3 |
178 | 11 | RC AUX 4 |
179 | 12 | GIMBAL PITCH |
180 | 13 | GIMBAL ROLL |
182 Stabilized ROLL/PITCH/YAW is taken directly from RC command when in PASSTHRU mode.
184 - `<rate>` is used to scale `<source>`, -100% - 100% is allowed. Note that servo reversal may be applied, see below. Zero `<rate>` will terminate smix table.
186 - `<speed>` will limit <source> speed when non-zero. This speed is taken per-rule, so you may limit only some sources. Value is maximal change of value per loop (1ms with default configuration)
188 - `<min>` `<max>` - Value in percentage of full servo range. For symmetrical servo limits (equal distance between mid and min/max), 0% is servo min, 50% is servo center, 100% is max servo position. When mid position is asymmetrical, 0% and 100% limits will be shifted.
190 - `<box>` rule will be applied only when `<box>` is zero or corresponding SERVOx mode is enabled.
192 ##### `smix reverse`
194 Print current servo reversal configuration
196 ##### `smix reverse <servo> <source> r|n`
198 Each `<source>` may be `r`eversed or `n`ormal for given `<servo>`. It is almost equivalent to using negative <rate> in given rule, but `<min>, `<max>` limits are applied to value before reversing.
199 `smix reverse` works for non-custom mixers too.
201 e.g. when using the TRI mixer to reverse the tail servo on a tricopter use this:
203 `smix reverse 5 2 r`
205 i.e. when mixing rudder servo slot (`5`) using Stabilized YAW input source (`2`) reverse the direction (`r`)
207 `smix reverse` is a per-profile setting.  So ensure you configure it for your profiles as required.
210 ### Example 1: A KK2.0 wired motor setup
211 Here's an example of a X configuration quad, but the motors are still wired using the KK board motor numbering scheme.
214 KK2.0 Motor Layout
216   1CW      2CCW
217      \    /
218        KK
219      /    \
220   4CCW     3CW
223 1. Use `mixer custom`
224 2. Use `mmix reset`
225 3. Use `mmix 0 1.0,  1.0, -1.0, -1.0` for the Front Left motor. It tells the flight controller the #1 motor is used, provides positive roll, provides negative pitch and is turning CW.
226 4. Use `mmix 1 1.0, -1.0, -1.0,  1.0` for the Front Right motor. It still provides a negative pitch authority, but unlike the front left, it provides negative roll authority and turns CCW.
227 5. Use `mmix 2 1.0, -1.0,  1.0, -1.0` for the Rear Right motor. It has negative roll, provides positive pitch when the speed is increased and turns CW.
228 6. Use `mmix 3 1.0,  1.0,  1.0,  1.0` for the Rear Left motor. Increasing motor speed imparts positive roll, positive pitch and turns CCW.
230 ### Example 2: A HEX-U Copter
232 Here is an example of a U-shaped hex; probably good for herding giraffes in the Sahara. Because the 1 and 6 motors are closer to the roll axis, they impart much less force than the motors mounted twice as far from the FC CG. The effect they have on pitch is the same as the forward motors because they are the same distance from the FC CG. The 2 and 5 motors do not contribute anything to pitch because speeding them up and slowing them down has no effect on the forward/back pitch of the FC.
235 HEX6-U
237 .4........3.
238 ............
239 .5...FC...2.
240 ............
241 ...6....1...
244 |Command| Roll | Pitch | Yaw |
245 | ----- | ---- | ----- | --- |
246 | Use `mmix 0 1.0, -0.5,  1.0, -1.0` | half negative | full positive | CW |
247 | Use `mmix 1 1.0, -1.0,  0.0,  1.0` | full negative | none | CCW |
248 | Use `mmix 2 1.0, -1.0, -1.0, -1.0` | full negative | full negative | CW |
249 | Use `mmix 3 1.0,  1.0, -1.0,  1.0` | full positive | full negative | CCW  |
250 | Use `mmix 4 1.0,  1.0,  0.0, -1.0` | full positive | none | CW |
251 | Use `mmix 5 1.0,  0.5,  1.0,  1.0` | half positive | full positive | CCW |
253 ### Example 3: Custom tricopter
256 mixer CUSTOMTRI
257 mmix reset
258 mmix 0 1.000 0.000 1.333 0.000
259 mmix 1 1.000 -1.000 -0.667 0.000
260 mmix 2 1.000 1.000 -0.667 0.000
261 smix reset
262 smix 0 5 2 100 0 0 100 0
263 profile 0
264 smix reverse 5 2 r
265 profile 1
266 smix reverse 5 2 r
267 profile 2
268 smix reverse 5 2 r
272 ### Example 4: Custom Airplane with Differential Thrust
273 Here is an example of a custom twin engine plane with [Differential Thrust](http://rcvehicles.about.com/od/rcairplanes/ss/RCAirplaneBasic.htm#step8)
274 Motors take the first 2 pins, the servos take pins as indicated in the [Servo slot] chart above.
275 Settings bellow have motor yaw influence at "0.3", you can change this number to have more or less differential thrust over the two motors.
276 Note: You can look at the Motors tab in [Cleanflight Cofigurator](https://chrome.google.com/webstore/detail/cleanflight-configurator/enacoimjcgeinfnnnpajinjgmkahmfgb?hl=en) to see motor and servo outputs.
278 | Pins | Outputs          |
279 |------|------------------|
280 | 1    | Left Engine      |
281 | 2    | Right Engine     |
282 | 3    | Pitch / Elevator |
283 | 4    | Roll / Aileron   |
284 | 5    | Roll / Aileron   |
285 | 6    | Yaw / Rudder     |
286 | 7    | [EMPTY]          |
287 | 8    | [EMPTY]          |
290 mixer CUSTOMAIRPLANE
291 mmix reset
292 mmix 0 1.0 0.0 0.0 0.3   # Left Engine
293 mmix 1 1.0 0.0 0.0 -0.3  # Right Engine
295 smix reset
296 # Rule  Servo   Source  Rate    Speed   Min     Max     Box
297 smix 0 3 0 100 0 0 100 0  # Roll / Aileron
298 smix 1 4 0 100 0 0 100 0  # Roll / Aileron
299 smix 2 5 2 100 0 0 100 0  # Yaw / Rudder
300 smix 3 2 1 100 0 0 100 0  # Pitch / Elevator
304 ### Example 5: Use motor output 0,1,2,4 because your output 3 is broken
305 For this to work you have to make a dummy mmix for motor 3. We do this by just saying it has 0 impact on yaw, roll and pitch.
307 mixer custom
308 mmix reset
309 mmix 0 1.0, -1.0, 1.0, -1.0
310 mmix 1 1.0, -1.0, -1.0,  1.0
311 mmix 2 1.0, 1.0, 1.0, 1.0
312 mmix 3 1.0, 0.0, 0.0, 0.0
313 mmix 4 1.0, 1.0, -1.0, -1.0
314 save