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

@ -58,7 +58,7 @@ void mixerUseConfigs(servoParam_t *servoConfToUse, flight3DConfig_t *flight3DCon
#define FLASH_WRITE_ADDR (0x08000000 + (uint32_t)((FLASH_PAGE_SIZE * FLASH_PAGE_COUNT) - FLASH_TO_RESERVE_FOR_CONFIG)) // use the last flash pages for storage master_t masterConfig; // master config struct with data independent from profiles
profile_t currentProfile; // profile config struct
static const uint8_t EEPROM_CONF_VERSION = 70;
static const uint8_t EEPROM_CONF_VERSION = 71;
static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims)
{

View File

@ -42,7 +42,7 @@ typedef struct profile_s {
uint8_t acc_unarmedcal; // turn automatic acc compensation on/off
uint16_t activate[CHECKBOX_ITEM_COUNT]; // activate switches
uint32_t activate[CHECKBOX_ITEM_COUNT]; // activate switches, bitmask, 3 bits per channel, lower 16 bits aux1-4, upper 16 bits aux 5-8
// Radio/ESC-related configuration
uint8_t deadband; // introduce a deadband around the stick center for pitch and roll axis. Must be greater than zero.

View File

@ -59,7 +59,7 @@ throttleStatus_e calculateThrottleStatus(rxConfig_t *rxConfig, uint16_t deadband
return THROTTLE_HIGH;
}
void processRcStickPositions(rxConfig_t *rxConfig, throttleStatus_e throttleStatus, uint16_t *activate, bool retarded_arm)
void processRcStickPositions(rxConfig_t *rxConfig, throttleStatus_e throttleStatus, uint32_t *activate, bool retarded_arm)
{
static uint8_t rcDelayCommand; // this indicates the number of time (multiple of RC measurement at 50Hz) the sticks must be maintained to run or switch off motors
static uint8_t rcSticks; // this hold sticks position for command combos

View File

@ -25,7 +25,11 @@ typedef enum rc_alias {
AUX1,
AUX2,
AUX3,
AUX4
AUX4,
AUX5,
AUX6,
AUX7,
AUX8
} rc_alias_e;
typedef enum {
@ -59,6 +63,6 @@ extern int16_t rcCommand[4];
bool areSticksInApModePosition(uint16_t ap_mode);
throttleStatus_e calculateThrottleStatus(rxConfig_t *rxConfig, uint16_t deadband3d_throttle);
void processRcStickPositions(rxConfig_t *rxConfig, throttleStatus_e throttleStatus, uint16_t *activate, bool retarded_arm);
void processRcStickPositions(rxConfig_t *rxConfig, throttleStatus_e throttleStatus, uint32_t *activate, bool retarded_arm);

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);

View File

@ -353,7 +353,7 @@ void loop(void)
static int16_t initialThrottleHold;
#endif
static uint32_t loopTime;
uint16_t auxState = 0;
uint32_t auxState = 0;
updateRx();
@ -393,6 +393,7 @@ void loop(void)
// Check AUX switches
// auxState is a bitmask, 3 bits per channel. aux1 is first.
// lower 16 bits contain aux 1 to 4, upper 16 bits contain aux 5 to 8
//
// the three bits are as follows:
// bit 1 is SET when the stick is less than 1300
@ -400,8 +401,14 @@ void loop(void)
// bit 3 is SET when the stick is above 1700
// if the value is 1300 or 1700 NONE of the three bits are set.
for (i = 0; i < 4; i++)
auxState |= (rcData[AUX1 + i] < 1300) << (3 * i) | (1300 < rcData[AUX1 + i] && rcData[AUX1 + i] < 1700) << (3 * i + 1) | (rcData[AUX1 + i] > 1700) << (3 * i + 2);
for (i = 0; i < 4; i++) {
auxState |= (rcData[AUX1 + i] < 1300) << (3 * i) |
(1300 < rcData[AUX1 + i] && rcData[AUX1 + i] < 1700) << (3 * i + 1) |
(rcData[AUX1 + i] > 1700) << (3 * i + 2);
auxState |= ((rcData[AUX5 + i] < 1300) << (3 * i) |
(1300 < rcData[AUX5 + i] && rcData[AUX5 + i] < 1700) << (3 * i + 1) |
(rcData[AUX5 + i] > 1700) << (3 * i + 2)) << 16;
}
for (i = 0; i < CHECKBOX_ITEM_COUNT; i++)
rcOptions[i] = (auxState & currentProfile.activate[i]) > 0;