Add MSP_SET_ADJUSTMENT_RANGE and MSP_ADJUSTMENT_RANGES commands.
This commit is contained in:
parent
ec92a8e6ba
commit
0ba2933611
|
@ -1,57 +1,34 @@
|
|||
# MSP Extensions
|
||||
|
||||
Cleanflight includes a number of extensions to the MultiWii Serial
|
||||
Protocol (MSP). This document describes those extensions in order that
|
||||
3rd part tools may identify cleanflight firmware and react appropriately.
|
||||
Cleanflight includes a number of extensions to the MultiWii Serial Protocol (MSP). This document describes
|
||||
those extensions in order that 3rd party tools may identify cleanflight firmware and react appropriately.
|
||||
|
||||
## MSP_IDENT capabilities
|
||||
Issue the MSP_API_VERSION command to find out if the firmware supports them.
|
||||
|
||||
Cleanflight sets a number of non-standard bits in the MSP_IDENT
|
||||
message in order to identify the firmware. For completeness, this
|
||||
includes flags defined for baseflight.
|
||||
|
||||
|Value|Mnemonic|Notes|Reference|
|
||||
|-----|--------|-----|---------|
|
||||
| 1 << 29 | CAP\_CLEANFLIGHT\_CONFIG | The firmware supports cleanflight configuration options. This is the definitive test for cleanflight firmware | src/main/io/serial_msp.c|
|
||||
| 1 << 30 | CAP\_BASEFLIGHT\_CONFIG | The firmware supports baseflight configuration options. See the baseflight documentation for details. | src/main/io/serial_msp.c |
|
||||
| 1 << 31 | CAP\_PLATFORM\_32BIT | This is a 32bit platform. | src/main/io/serial_msp.c |
|
||||
|
||||
## Modes Extension
|
||||
|
||||
The cleanflight modes extension to MSP supports the extended
|
||||
auxiliary modes introduced 2014-10-14. The CAP\_CLEANFLIGHT\_CONFIG
|
||||
capabilities flag should be used to confirm the availability of
|
||||
extended auxiliary modes. If this flag is not present, the legacy MSP
|
||||
MSP\_BOX and MSP\_SET\_BOX messages should be used.
|
||||
|
||||
Note: In the following descriptions, the format of the original MSP
|
||||
documentation is followed.
|
||||
## Mode Ranges
|
||||
|
||||
### MSP\_MODE\_RANGES
|
||||
|
||||
The MSP\_MODE\_RANGES returns the current auxiliary mode settings from
|
||||
the flight controller. It should be invoked before any modification is
|
||||
made to the configuration.
|
||||
The MSP\_MODE\_RANGES returns the current auxiliary mode settings from the flight controller. It should be invoked
|
||||
before any modification is made to the configuration.
|
||||
|
||||
The message returns a group of 4 unsigned bytes for each 'slot'
|
||||
available in the flight controller. The number of slots should be
|
||||
calculated from the size of the returned message.
|
||||
The message returns a group of 4 unsigned bytes for each 'slot' available in the flight controller. The number of
|
||||
slots should be calculated from the size of the returned message.
|
||||
|
||||
| Command | Msg Id | Direction | Data | Type | Notes |
|
||||
|---------|--------|-----------|------|------|-------|
|
||||
| MSP\_MODE\_RANGES | 34 | to FC | (none) | N/A | Following this command, the FC returns a block of 4 bytes for each auxiliary mode 'slot'|
|
||||
| Command | Msg Id | Direction | Notes |
|
||||
|---------|--------|-----------|-------|
|
||||
| MSP\_MODE\_RANGES | 34 | to FC | Following this command, the FC returns a block of 4 bytes for each auxiliary mode 'slot'|
|
||||
|
||||
Unassigned slots have rangeStartStep == rangeEndStep. Each element contains the following fields.
|
||||
|
||||
| Command | Msg Id | Direction | Data | Type | Notes |
|
||||
|---------|--------|-----------|------|------|-------|
|
||||
| | | returned from FC | permanentId | uint8 | See Modes.md for a definition of the permanent ids |
|
||||
| | | returned from FC | auxChannelIndex | uint8 | The Aux switch number (indexed from 0) |
|
||||
| | | returned from FC | rangeStartStep | uint8 | The start value for this element in 'blocks' of 25 where 0 == 900 and 48 == 2100 |
|
||||
| | | returned from FC | rangeEndStep | uint8 | The end value for this element in 'blocks' of 25 where 0 == 900 and 48 == 2100 |
|
||||
| Data | Type | Notes |
|
||||
|------|------|-------|
|
||||
| permanentId | uint8 | See Modes.md for a definition of the permanent ids |
|
||||
| auxChannelIndex | uint8 | The Aux switch number (indexed from 0) |
|
||||
| rangeStartStep | uint8 | The start value for this element in 'blocks' of 25 where 0 == 900 and 48 == 2100 |
|
||||
| rangeEndStep | uint8 | The end value for this element in 'blocks' of 25 where 0 == 900 and 48 == 2100 |
|
||||
|
||||
Thus, for a cleanflight firmware with 40 slots for auxiliary settings,
|
||||
160 bytes would be returned in response to MSP\_MODE\_RANGES,
|
||||
Thus, for a cleanflight firmware with 40 slots 160 bytes would be returned in response to MSP\_MODE\_RANGES,
|
||||
|
||||
### MSP\_SET\_MODE\_RANGE
|
||||
|
||||
|
@ -60,32 +37,107 @@ auxiliary mode settings. The client *must* return all auxiliary
|
|||
elements, including those that have been disabled or are undefined, by
|
||||
sending this message for all auxiliary slots.
|
||||
|
||||
| Command | Msg Id | Direction | Data | Type | Notes |
|
||||
|---------|--------|-----------|------|------|-------|
|
||||
| MSP\_SET\_MODE\_RANGE | 35 | to FC | sequence id | uint8 | A monotonically increasing ID, from 0 to the number of slots -1 |
|
||||
| | | | permanentId | uint8 | See Modes.md for a definition of the permanent ids |
|
||||
| | | | auxChannelIndex | uint8 | The Aux switch number (indexed from 0) |
|
||||
| | | | rangeStartStep | uint8 | The start value for this element in 'blocks' of 25 where 0 == 900 and 48 == 2100 |
|
||||
| | | | rangeEndStep | uint8 | The end value for this element in 'blocks' of 25 where 0 == 900 and 48 == 2100 |
|
||||
| Command | Msg Id | Direction |
|
||||
|---------|--------|-----------|
|
||||
| MSP\_SET\_MODE\_RANGE | 35 | to FC |
|
||||
|
||||
## Implementation Notes
|
||||
|
||||
* The client should make no assumptions about the number of slots
|
||||
available. Rather, the number should be computed from the size of
|
||||
the MSP\_MODE\_RANGES message divided by the size of the returned
|
||||
data element (4 bytes);
|
||||
* The client should ensure that all changed items are returned to the
|
||||
flight controller, including those where a switch or range has been
|
||||
disabled;
|
||||
* A 'null' return (with rangeStartStep == rangeEndStep) must be made for all
|
||||
unused slots, up to the maximum number of slots calculated from the initial
|
||||
message.
|
||||
| Data | Type | Notes |
|
||||
|------|------|-------|
|
||||
| sequence id | uint8 | A monotonically increasing ID, from 0 to the number of slots -1 |
|
||||
| permanentId | uint8 | See Modes.md for a definition of the permanent ids |
|
||||
| auxChannelIndex | uint8 | The Aux channel number (indexed from 0) |
|
||||
| rangeStartStep | uint8 | The start value for this element in 'blocks' of 25 where 0 == 900 and 48 == 2100 |
|
||||
| rangeEndStep | uint8 | The end value for this element in 'blocks' of 25 where 0 == 900 and 48 == 2100 |
|
||||
|
||||
### Implementation Notes
|
||||
|
||||
* The client should make no assumptions about the number of slots available. Rather, the number should be computed
|
||||
from the size of the MSP\_MODE\_RANGES message divided by the size of the returned data element (4 bytes);
|
||||
* The client should ensure that all changed items are returned to the flight controller, including those where a
|
||||
switch or range has been disabled;
|
||||
* A 'null' return, with all values other than the sequence id set to 0, must be made for all unused slots, up to
|
||||
the maximum number of slots calculated from the initial message.
|
||||
|
||||
## Adjustment Ranges
|
||||
|
||||
### MSP\_ADJUSTMENT\_RANGES
|
||||
|
||||
The MSP\_ADJUSTMENT\_RANGES returns the current adjustment range settings from
|
||||
the flight controller. It should be invoked before any modification is
|
||||
made to the configuration.
|
||||
|
||||
The message returns a group of 6 unsigned bytes for each 'slot'
|
||||
available in the flight controller. The number of slots should be
|
||||
calculated from the size of the returned message.
|
||||
|
||||
| Command | Msg Id | Direction | Notes |
|
||||
|---------|--------|-----------|-------|
|
||||
| MSP\_ADJUSTMENT\_RANGES | 52 | to FC | Following this command, the FC returns a block of 6 bytes for each adjustment range 'slot'|
|
||||
|
||||
Unassigned slots have rangeStartStep == rangeEndStep. Each element contains the following fields.
|
||||
|
||||
| Data | Type | Notes |
|
||||
|------|------|-------|
|
||||
| adjustmentStateIndex | uint8 | See below |
|
||||
| auxChannelIndex | uint8 | The Aux channel number (indexed from 0) used to activate the adjustment |
|
||||
| rangeStartStep | uint8 | The start value for this element in 'blocks' of 25 where 0 == 900 and 48 == 2100 |
|
||||
| rangeEndStep | uint8 | The end value for this element in 'blocks' of 25 where 0 == 900 and 48 == 2100 |
|
||||
| adjustmentFunction | uint8 | See below |
|
||||
| auxSwitchChannelIndex | uint8 | The Aux channel number used to perform the function (indexed from 0) |
|
||||
|
||||
Thus, for a cleanflight firmware with 12 slots 72 bytes would be returned in response to MSP\_ADJUSTMENT\_RANGES,
|
||||
|
||||
### MSP\_SET\_ADJUSTMENT\_RANGE
|
||||
|
||||
The MSP\_SET\_ADJUSTMENT\_RANGE is used to inform the flight controller of
|
||||
adjustment range settings. The client *must* return all adjustment range
|
||||
elements, including those that have been disabled or are undefined, by
|
||||
sending this message for all adjustment range slots.
|
||||
|
||||
| Command | Msg Id | Direction |
|
||||
|---------|--------|-----------|
|
||||
| MSP\_SET\_ADJUSTMENT\_RANGE | 53 | to FC |
|
||||
|
||||
|
||||
| Data | Type | Notes |
|
||||
|------|------|-------|
|
||||
| sequence id | uint8 | A monotonically increasing ID, from 0 to the number of slots -1 |
|
||||
| adjustmentStateIndex | uint8 | See below |
|
||||
| auxChannelIndex | uint8 | The Aux channel number (indexed from 0) |
|
||||
| rangeStartStep | uint8 | The start value for this element in 'blocks' of 25 where 0 == 900 and 48 == 2100 |
|
||||
| rangeEndStep | uint8 | The end value for this element in 'blocks' of 25 where 0 == 900 and 48 == 2100 |
|
||||
| adjustmentFunction | uint8 | See below |
|
||||
| auxSwitchChannelIndex | uint8 | The Aux channel number used to perform the function (indexed from 0) |
|
||||
|
||||
#### AdjustmentIndex
|
||||
|
||||
The FC maintains internal state for each adjustmentStateIndex, currently 4 simultaneous adjustment states are maintained. Multiple adjustment ranges
|
||||
can be configured to use the same state but care should be taken not to send multiple adjustment ranges that when active would confict.
|
||||
|
||||
e.g. Configuring two identical adjustment ranges using the same slot would conflict, but configuring two adjustment ranges that used
|
||||
only one half of the possible channel range each but used the same adjustmentStateIndex would not conflict.
|
||||
|
||||
The FC does NOT check for conflicts.
|
||||
|
||||
#### AdjustmentFunction
|
||||
|
||||
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.
|
||||
|
||||
### Implementation Notes
|
||||
|
||||
* The client should make no assumptions about the number of slots available. Rather, the number should be computed
|
||||
from the size of the MSP\_ADJUSTMENT\_RANGES message divided by the size of the returned data element (6 bytes);
|
||||
* The client should ensure that all changed items are returned to the flight controller, including those where a
|
||||
switch or range has been disabled;
|
||||
* A 'null' return, with all values except for the sequence id set to 0, must be made for all unused slots,
|
||||
up to the maximum number of slots calculated from the initial message.
|
||||
|
||||
## Deprecated MSP
|
||||
|
||||
The following MSP commands are replaced by the MSP\_MODE\_RANGES and
|
||||
MSP\_SET\_MODE\_RANGE extensions, and are not recognised by
|
||||
cleanflight where CAP\_CLEANFLIGHT\_CONFIG is set.
|
||||
cleanflight.
|
||||
|
||||
* MSP\_BOX
|
||||
* MSP\_SET\_BOX
|
||||
|
|
|
@ -197,6 +197,9 @@ const char *boardIdentifier = TARGET_BOARD_IDENTIFIER;
|
|||
#define MSP_RSSI_CONFIG 50
|
||||
#define MSP_SET_RSSI_CONFIG 51
|
||||
|
||||
#define MSP_ADJUSTMENT_RANGES 52
|
||||
#define MSP_SET_ADJUSTMENT_RANGE 53
|
||||
|
||||
//
|
||||
// Baseflight MSP commands (if enabled they exist in Cleanflight)
|
||||
//
|
||||
|
@ -849,8 +852,26 @@ static bool processOutCommand(uint8_t cmdMSP)
|
|||
serialize8(mac->range.endStep);
|
||||
}
|
||||
break;
|
||||
case MSP_ADJUSTMENT_RANGES:
|
||||
headSerialReply(MAX_ADJUSTMENT_RANGE_COUNT * (
|
||||
1 + // adjustment index/slot
|
||||
1 + // aux channel index
|
||||
1 + // start step
|
||||
1 + // end step
|
||||
1 + // adjustment function
|
||||
1 // aux switch channel index
|
||||
));
|
||||
for (i = 0; i < MAX_ADJUSTMENT_RANGE_COUNT; i++) {
|
||||
adjustmentRange_t *adjRange = ¤tProfile->adjustmentRanges[i];
|
||||
serialize8(adjRange->adjustmentIndex);
|
||||
serialize8(adjRange->auxChannelIndex);
|
||||
serialize8(adjRange->range.startStep);
|
||||
serialize8(adjRange->range.endStep);
|
||||
serialize8(adjRange->adjustmentFunction);
|
||||
serialize8(adjRange->auxSwitchChannelIndex);
|
||||
}
|
||||
break;
|
||||
case MSP_BOXNAMES:
|
||||
// headSerialReply(sizeof(boxnames) - 1);
|
||||
serializeBoxNamesReply();
|
||||
break;
|
||||
case MSP_BOXIDS:
|
||||
|
@ -1097,6 +1118,26 @@ static bool processInCommand(void)
|
|||
headSerialError(0);
|
||||
}
|
||||
break;
|
||||
case MSP_SET_ADJUSTMENT_RANGE:
|
||||
i = read8();
|
||||
if (i < MAX_ADJUSTMENT_RANGE_COUNT) {
|
||||
adjustmentRange_t *adjRange = ¤tProfile->adjustmentRanges[i];
|
||||
i = read8();
|
||||
if (i < MAX_SIMULTANEOUS_ADJUSTMENT_COUNT) {
|
||||
adjRange->adjustmentIndex = i;
|
||||
adjRange->auxChannelIndex = read8();
|
||||
adjRange->range.startStep = read8();
|
||||
adjRange->range.endStep = read8();
|
||||
adjRange->adjustmentFunction = read8();
|
||||
adjRange->auxSwitchChannelIndex = read8();
|
||||
} else {
|
||||
headSerialError(0);
|
||||
}
|
||||
} else {
|
||||
headSerialError(0);
|
||||
}
|
||||
break;
|
||||
|
||||
case MSP_SET_RC_TUNING:
|
||||
currentControlRateProfile->rcRate8 = read8();
|
||||
currentControlRateProfile->rcExpo8 = read8();
|
||||
|
|
Loading…
Reference in New Issue