Merge remote-tracking branch 'origin/master' into mmosca-sbus-output-improvements
[inav.git] / docs / API / MSP_extensions.md
blob2ac8dd989f9282753806a48377bb23a40d984523
1 # MSP Extensions
3 INAV 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 INAV 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 in the wiki](https://github.com/iNavFlight/inav/wiki/Modes) 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 INAV firmware with 40 slots 160 bytes would be returned in response to MSP\_MODE\_RANGES,
33 ### MSP\_SET\_MODE\_RANGE
35 The MSP\_SET\_MODE\_RANGE is used to inform the flight controller of
36 auxiliary mode settings. The client *must* return all auxiliary
37 elements, including those that have been disabled or are undefined, by
38 sending this message for all auxiliary slots.
40 | Command | Msg Id | Direction |
41 |---------|--------|-----------|
42 | MSP\_SET\_MODE\_RANGE | 35 | to FC |
45 | Data | Type | Notes |
46 |------|------|-------|
47 | sequence id | uint8 | A monotonically increasing ID, from 0 to the number of slots -1 |
48 | permanentId | uint8 | See [Modes in the wiki](https://github.com/iNavFlight/inav/wiki/Modes) for a definition of the permanent ids |
49 | auxChannelIndex | uint8 | The Aux channel number (indexed from 0) |
50 | rangeStartStep | uint8 | The start value for this element in 'blocks' of 25  where 0 == 900 and 48 == 2100 |
51 | rangeEndStep | uint8 | The end value for this element in 'blocks' of 25 where 0 == 900 and 48 == 2100 |
53 ### Implementation Notes
55 * The client should make no assumptions about the number of slots available. Rather, the number should be computed
56   from the size of the MSP\_MODE\_RANGES message divided by the size of the returned data element (4 bytes);
57 * The client should ensure that all changed items are returned to the flight controller, including those where a
58   switch or range has been disabled;
59 * A 'null' return, with all values other than the sequence id set to 0, must be made for all unused slots, up to
60   the maximum number of slots calculated from the initial message.
62 ## Adjustment Ranges
64 ### MSP\_ADJUSTMENT\_RANGES
66 The MSP\_ADJUSTMENT\_RANGES returns the current adjustment range settings from
67 the flight controller. It should be invoked before any modification is
68 made to the configuration.
70 The message returns a group of 6 unsigned bytes for each 'slot'
71 available in the flight controller. The number of slots should be
72 calculated from the size of the returned message.
74 | Command | Msg Id | Direction | Notes |
75 |---------|--------|-----------|-------|
76 | MSP\_ADJUSTMENT\_RANGES | 52 | to FC | Following this command, the FC returns a block of 6 bytes for each adjustment range 'slot'|
78 Unassigned slots have rangeStartStep == rangeEndStep. Each element contains the following fields.
80 | Data | Type | Notes |
81 |------|------|-------|
82 | adjustmentStateIndex | uint8 | See below |
83 | auxChannelIndex | uint8 | The Aux channel number (indexed from 0) used to activate the adjustment |
84 | rangeStartStep | uint8 | The start value for this element in 'blocks' of 25  where 0 == 900 and 48 == 2100 |
85 | rangeEndStep | uint8 | The end value for this element in 'blocks' of 25 where 0 == 900 and 48 == 2100 |
86 | adjustmentFunction | uint8 | See below |
87 | auxSwitchChannelIndex | uint8 | The Aux channel number used to perform the function (indexed from 0) |
89 Thus, for a INAV firmware with 12 slots 72 bytes would be returned in response to MSP\_ADJUSTMENT\_RANGES,
91 ### MSP\_SET\_ADJUSTMENT\_RANGE
93 The MSP\_SET\_ADJUSTMENT\_RANGE is used to inform the flight controller of
94 adjustment range settings. The client *must* return all adjustment range
95 elements, including those that have been disabled or are undefined, by
96 sending this message for all adjustment range slots.
98 | Command | Msg Id | Direction |
99 |---------|--------|-----------|
100 | MSP\_SET\_ADJUSTMENT\_RANGE | 53 | to FC |
103 | Data | Type | Notes |
104 |------|------|-------|
105 | sequence id | uint8 | A monotonically increasing ID, from 0 to the number of slots -1 |
106 | adjustmentStateIndex | uint8 | See below |
107 | auxChannelIndex | uint8 | The Aux channel number (indexed from 0) |
108 | rangeStartStep | uint8 | The start value for this element in 'blocks' of 25  where 0 == 900 and 48 == 2100 |
109 | rangeEndStep | uint8 | The end value for this element in 'blocks' of 25 where 0 == 900 and 48 == 2100 |
110 | adjustmentFunction | uint8 | See below |
111 | auxSwitchChannelIndex | uint8 | The Aux channel number used to perform the function (indexed from 0) |
113 ### MSP\_SET\_1WIRE
115 The MSP\_SET\_1WIRE is used to enable serial1wire passthrough
116 note: it would be ideal to disable this when armed
118 | Command | Msg Id | Direction |
119 |---------|--------|-----------|
120 | MSP\_SET\_1WIRE  | 243 | to FC |
122 | Data | Type | Notes |
123 |------|------|-------|
124 | esc id | uint8 | A monotonically increasing ID, from 0 to the number of escs -1 |
126 #### AdjustmentIndex
128 The FC maintains internal state for each adjustmentStateIndex, currently 4 simultaneous adjustment states are maintained.  Multiple adjustment ranges
129 can be configured to use the same state but care should be taken not to send multiple adjustment ranges that when active would confict.
131 e.g.  Configuring two identical adjustment ranges using the same slot would conflict, but configuring two adjustment ranges that used
132 only one half of the possible channel range each but used the same adjustmentStateIndex would not conflict.
134 The FC does NOT check for conflicts.
136 #### AdjustmentFunction
138 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.
140 ### Implementation Notes
142 * The client should make no assumptions about the number of slots available. Rather, the number should be computed
143   from the size of the MSP\_ADJUSTMENT\_RANGES message divided by the size of the returned data element (6 bytes);
144 * The client should ensure that all changed items are returned to the flight controller, including those where a
145   switch or range has been disabled;
146 * A 'null' return, with all values except for the sequence id set to 0, must be made for all unused slots,
147   up to the maximum number of slots calculated from the initial message.
149 ## Deprecated MSP
151 The following MSP commands are replaced by the MSP\_MODE\_RANGES and
152 MSP\_SET\_MODE\_RANGE extensions, and are not recognised by
153 INAV.
155 * MSP\_BOX
156 * MSP\_SET\_BOX
158 See also
159 --------
160 [The wiki](https://github.com/iNavFlight/inav/wiki/Modes) describes the user visible implementation for the INAV
161 modes extension.