1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-16 04:45:24 +03:00

Support configuring AUX 5 to 8.

The MSP is changed in a way that might provide some backwards
compatibility.  The first 4 channels are sent/read as before followed by
the next 4 channels.

If I client ignores extra data received it should be backwards
compatible.

Clients can looks for the new capability bit which indicates the MSP
protocol supports AUX 1-8.
This commit is contained in:
Dominic Clifton 2014-06-04 19:30:43 +01:00
parent 68f428d73a
commit d718f5b9d6
6 changed files with 30 additions and 12 deletions

View file

@ -72,6 +72,7 @@ extern int16_t debug[4]; // FIXME dependency on mw.c
#define CAP_DYNBALANCE ((uint32_t)1 << 2)
#define CAP_FLAPS ((uint32_t)1 << 3)
#define CAP_CHANNEL_FORWARDING ((uint32_t)1 << 4)
#define CAP_ACTIVATE_AUX1_TO_AUX8 ((uint32_t)1 << 5)
#define MSP_IDENT 100 //out message multitype + multiwii version + protocol version + capability variable
#define MSP_STATUS 101 //out message cycletime & errors_count & sensor present & box activation & current setting number
@ -130,6 +131,8 @@ extern int16_t debug[4]; // FIXME dependency on mw.c
#define INBUF_SIZE 64
#define ACTIVATE_MASK 0xFFF // see
struct box_t {
const uint8_t boxIndex; // this is from boxnames enum
const char *boxName; // GUI-readable box name
@ -448,7 +451,9 @@ static void evaluateCommand(void)
break;
case MSP_SET_BOX:
for (i = 0; i < numberBoxItems; i++)
currentProfile.activate[availableBoxes[i]] = read16();
currentProfile.activate[availableBoxes[i]] = read16() & ACTIVATE_MASK;
for (i = 0; i < numberBoxItems; i++)
currentProfile.activate[availableBoxes[i]] |= (read16() & ACTIVATE_MASK) << 16;
headSerialReply(0);
break;
case MSP_SET_RC_TUNING:
@ -501,7 +506,7 @@ static void evaluateCommand(void)
serialize8(MW_VERSION);
serialize8(masterConfig.mixerConfiguration); // type of multicopter
serialize8(MSP_VERSION); // MultiWii Serial Protocol Version
serialize32(CAP_PLATFORM_32BIT | CAP_DYNBALANCE | (masterConfig.airplaneConfig.flaps_speed ? CAP_FLAPS : 0) | CAP_CHANNEL_FORWARDING); // "capability"
serialize32(CAP_PLATFORM_32BIT | CAP_DYNBALANCE | (masterConfig.airplaneConfig.flaps_speed ? CAP_FLAPS : 0) | CAP_CHANNEL_FORWARDING | CAP_ACTIVATE_AUX1_TO_AUX8); // "capability"
break;
case MSP_STATUS:
headSerialReply(11);
@ -682,9 +687,11 @@ static void evaluateCommand(void)
serializeNames(pidnames);
break;
case MSP_BOX:
headSerialReply(2 * numberBoxItems);
headSerialReply(4 * numberBoxItems);
for (i = 0; i < numberBoxItems; i++)
serialize16(currentProfile.activate[availableBoxes[i]]);
serialize16(currentProfile.activate[availableBoxes[i]] & ACTIVATE_MASK);
for (i = 0; i < numberBoxItems; i++)
serialize16((currentProfile.activate[availableBoxes[i]] >> 16) & ACTIVATE_MASK);
break;
case MSP_BOXNAMES:
// headSerialReply(sizeof(boxnames) - 1);