Merge pull request #11024 from ctzsnooze/update-Rx.md-note-about-ADC-filter
[betaflight.git] / docs / API / MSP_extensions.md
blob9212728cec478cdb281e9bd26f3ba3bfddcf44f7
1 # MSP Extensions
3 Cleanflight includes a number of extensions to the MultiWii Serial Protocol (MSP). This document describes 
4 those extensions in order that 3rd party tools may identify cleanflight firmware and react appropriately.
6 Issue the MSP_API_VERSION command to find out if the firmware supports them.
8 ## Mode Ranges
10 ### MSP\_MODE\_RANGES
12 The MSP\_MODE\_RANGES returns the current auxiliary mode settings from the flight controller. It should be invoked
13 before any modification is made to the configuration.
15 The message returns a group of 4 unsigned bytes for each 'slot' available in the flight controller. The number of
16 slots should be calculated from the size of the returned message.
18 | Command | Msg Id | Direction | Notes |
19 |---------|--------|-----------|-------|
20 | MSP\_MODE\_RANGES | 34 | to FC | Following this command, the FC returns a block of 4 bytes for each auxiliary mode 'slot'|
22 Unassigned slots have rangeStartStep == rangeEndStep. Each element contains the following fields.
24 | Data | Type | Notes |
25 |------|------|-------|
26 | permanentId | uint8 | See Modes.md for a definition of the permanent ids |
27 | auxChannelIndex | uint8 | The Aux switch number (indexed from 0) |
28 | rangeStartStep | uint8 | The start value for this element in 'blocks' of 25  where 0 == 900 and 48 == 2100 |
29 | rangeEndStep | uint8 | The end value for this element in 'blocks' of 25 where 0 == 900 and 48 == 2100 |
31 Thus, for a cleanflight firmware with 40 slots 160 bytes would be returned in response to MSP\_MODE\_RANGES.
33 ### MSP\_MODE\_RANGES\_EXTRA
35 The MSP\_MODE\_RANGES\_EXTRA returns the extra mode setting parameters from the flight controller. It should be invoked
36 in conjunction with MSP\_MODE\_RANGES before any modification is made to the configuration.
38 The message returns the number of extra elements followed by a group of bytes for each 'slot' available in the flight
39 controller. The number of slots should be the same as for MSP\_MODE\_RANGES, calculated from the size of the returned
40 message and the number of bytes per group.
42 | Command | Msg Id | Direction | Notes |
43 |---------|--------|-----------|-------|
44 | MSP\_MODE\_RANGES\_EXTRA | 238 | to FC | Following this command, the FC returns a block of bytes for each auxiliary mode 'slot'|
46 The return message is prepended with the number of bytes per element (3 bytes). Each element contains the
47 following fields:
49 | Data | Type | Notes |
50 |------|------|-------|
51 | permanentId | uint8 | See Modes.md for a definition of the permanent ids |
52 | modeLogic | uint8 | 0 = Logic AND; 1 = Logic OR |
53 | linkedTo | uint8 | Permanent id to which this mode is linked. |
55 Thus, for a cleanflight firmware with 20 slots, 61 bytes (including prepended size) would be returned in response to
56 MSP\_MODE\_RANGES\_EXTRA.
58 ### MSP\_SET\_MODE\_RANGE
60 The MSP\_SET\_MODE\_RANGE is used to inform the flight controller of
61 auxiliary mode settings. The client *must* return all auxiliary
62 elements, including those that have been disabled or are undefined, by
63 sending this message for all auxiliary slots.
65 | Command | Msg Id | Direction |
66 |---------|--------|-----------|
67 | MSP\_SET\_MODE\_RANGE | 35 | to FC |
70 | Data | Type | Notes |
71 |------|------|-------|
72 | sequence id | uint8 | A monotonically increasing ID, from 0 to the number of slots -1 |
73 | permanentId | uint8 | See Modes.md for a definition of the permanent ids |
74 | auxChannelIndex | uint8 | The Aux channel number (indexed from 0) |
75 | rangeStartStep | uint8 | The start value for this element in 'blocks' of 25  where 0 == 900 and 48 == 2100 |
76 | rangeEndStep | uint8 | The end value for this element in 'blocks' of 25 where 0 == 900 and 48 == 2100 |
78 ### Implementation Notes
80 * The client should make no assumptions about the number of slots available. Rather, the number should be computed 
81   from the size of the MSP\_MODE\_RANGES message divided by the size of the returned data element (4 bytes);
82 * The client should ensure that all changed items are returned to the flight controller, including those where a
83   switch or range has been disabled;
84 * A 'null' return, with all values other than the sequence id set to 0, must be made for all unused slots, up to
85   the maximum number of slots calculated from the initial message.
87 ## Adjustment Ranges
89 ### MSP\_ADJUSTMENT\_RANGES
91 The MSP\_ADJUSTMENT\_RANGES returns the current adjustment range settings from
92 the flight controller. It should be invoked before any modification is
93 made to the configuration.
95 The message returns a group of 6 unsigned bytes for each 'slot'
96 available in the flight controller. The number of slots should be
97 calculated from the size of the returned message.
99 | Command | Msg Id | Direction | Notes |
100 |---------|--------|-----------|-------|
101 | MSP\_ADJUSTMENT\_RANGES | 52 | to FC | Following this command, the FC returns a block of 6 bytes for each adjustment range 'slot'|
103 Unassigned slots have rangeStartStep == rangeEndStep. Each element contains the following fields.
105 | Data | Type | Notes |
106 |------|------|-------|
107 | adjustmentStateIndex | uint8 | See below |
108 | auxChannelIndex | uint8 | The Aux channel number (indexed from 0) used to activate the adjustment |
109 | rangeStartStep | uint8 | The start value for this element in 'blocks' of 25  where 0 == 900 and 48 == 2100 |
110 | rangeEndStep | uint8 | The end value for this element in 'blocks' of 25 where 0 == 900 and 48 == 2100 |
111 | adjustmentFunction | uint8 | See below |
112 | auxSwitchChannelIndex | uint8 | The Aux channel number used to perform the function (indexed from 0) |
114 Thus, for a cleanflight firmware with 12 slots 72 bytes would be returned in response to MSP\_ADJUSTMENT\_RANGES,
116 ### MSP\_SET\_ADJUSTMENT\_RANGE
118 The MSP\_SET\_ADJUSTMENT\_RANGE is used to inform the flight controller of
119 adjustment range settings. The client *must* return all adjustment range
120 elements, including those that have been disabled or are undefined, by
121 sending this message for all adjustment range slots.
123 | Command | Msg Id | Direction |
124 |---------|--------|-----------|
125 | MSP\_SET\_ADJUSTMENT\_RANGE | 53 | to FC |
128 | Data | Type | Notes |
129 |------|------|-------|
130 | sequence id | uint8 | A monotonically increasing ID, from 0 to the number of slots -1 |
131 | adjustmentStateIndex | uint8 | See below |
132 | auxChannelIndex | uint8 | The Aux channel number (indexed from 0) |
133 | rangeStartStep | uint8 | The start value for this element in 'blocks' of 25  where 0 == 900 and 48 == 2100 |
134 | rangeEndStep | uint8 | The end value for this element in 'blocks' of 25 where 0 == 900 and 48 == 2100 |
135 | adjustmentFunction | uint8 | See below |
136 | auxSwitchChannelIndex | uint8 | The Aux channel number used to perform the function (indexed from 0) |
138 ### MSP\_SET\_1WIRE
140 The MSP\_SET\_1WIRE is used to enable serial1wire passthrough
141 note: it would be ideal to disable this when armed
143 | Command | Msg Id | Direction |
144 |---------|--------|-----------|
145 | MSP\_SET\_1WIRE  | 243 | to FC |
147 | Data | Type | Notes |
148 |------|------|-------|
149 | esc id | uint8 | A monotonically increasing ID, from 0 to the number of escs -1 |
151 #### AdjustmentIndex
153 The FC maintains internal state for each adjustmentStateIndex, currently 4 simultaneous adjustment states are maintained.  Multiple adjustment ranges
154 can be configured to use the same state but care should be taken not to send multiple adjustment ranges that when active would confict.
156 e.g.  Configuring two identical adjustment ranges using the same slot would conflict, but configuring two adjustment ranges that used 
157 only one half of the possible channel range each but used the same adjustmentStateIndex would not conflict.
159 The FC does NOT check for conflicts.
161 #### AdjustmentFunction
163 There are many adjustments that can be made, the numbers of them and their use is found in the documentation of the cli `adjrange` command in the 'Inflight Adjustents' section.
165 ### Implementation Notes
167 * The client should make no assumptions about the number of slots available. Rather, the number should be computed 
168   from the size of the MSP\_ADJUSTMENT\_RANGES message divided by the size of the returned data element (6 bytes);
169 * The client should ensure that all changed items are returned to the flight controller, including those where a
170   switch or range has been disabled;
171 * A 'null' return, with all values except for the sequence id set to 0, must be made for all unused slots,
172   up to the maximum number of slots calculated from the initial message.
174 ## Deprecated MSP
176 The following MSP commands are replaced by the MSP\_MODE\_RANGES and
177 MSP\_SET\_MODE\_RANGE extensions, and are not recognised by
178 cleanflight.
180 * MSP\_BOX
181 * MSP\_SET\_BOX
183 See also
184 --------
185 [Modes.md](../Modes.md) describes the user visible implementation for the cleanflight
186 modes extension.