1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-21 15:25:36 +03:00

Support UART3 and I2C on Paris Air Hero 32 Flex port (aka Naze32_SP).

This change also allows serial ports to be removed at runtime.  e.g.
UART3 on Naze32 and SoftSerial 1 & 2 when softserial is not enabled.
This commit is contained in:
Dominic Clifton 2015-05-22 20:48:39 +01:00
parent f2013ab863
commit a370d60595
5 changed files with 92 additions and 18 deletions

View file

@ -53,7 +53,7 @@
static serialConfig_t *serialConfig; static serialConfig_t *serialConfig;
static serialPortUsage_t serialPortUsageList[SERIAL_PORT_COUNT]; static serialPortUsage_t serialPortUsageList[SERIAL_PORT_COUNT];
serialPortIdentifier_e serialPortIdentifiers[SERIAL_PORT_COUNT] = { const serialPortIdentifier_e const serialPortIdentifiers[SERIAL_PORT_COUNT] = {
#ifdef USE_VCP #ifdef USE_VCP
SERIAL_PORT_USB_VCP, SERIAL_PORT_USB_VCP,
#endif #endif
@ -74,7 +74,9 @@ serialPortIdentifier_e serialPortIdentifiers[SERIAL_PORT_COUNT] = {
#endif #endif
}; };
uint32_t baudRates[] = {0, 9600, 19200, 38400, 57600, 115200, 230400, 250000}; // see baudRate_e static uint8_t serialPortCount;
const uint32_t const baudRates[] = {0, 9600, 19200, 38400, 57600, 115200, 230400, 250000}; // see baudRate_e
#define BAUD_RATE_COUNT (sizeof(baudRates) / sizeof(baudRates[0])) #define BAUD_RATE_COUNT (sizeof(baudRates) / sizeof(baudRates[0]))
@ -226,16 +228,22 @@ bool isSerialConfigValid(serialConfig_t *serialConfigToCheck)
return true; return true;
} }
bool doesConfigurationUsePort(serialPortIdentifier_e identifier) serialPortConfig_t *serialFindPortConfiguration(serialPortIdentifier_e identifier)
{ {
uint8_t index; uint8_t index;
for (index = 0; index < SERIAL_PORT_COUNT; index++) { for (index = 0; index < SERIAL_PORT_COUNT; index++) {
serialPortConfig_t *candidate = &serialConfig->portConfigs[index]; serialPortConfig_t *candidate = &serialConfig->portConfigs[index];
if (candidate->identifier == identifier && candidate->functionMask) { if (candidate->identifier == identifier) {
return true; return candidate;
} }
} }
return false; return NULL;
}
bool doesConfigurationUsePort(serialPortIdentifier_e identifier)
{
serialPortConfig_t *candidate = serialFindPortConfiguration(identifier);
return candidate != NULL && candidate->functionMask;
} }
serialPort_t *openSerialPort( serialPort_t *openSerialPort(
@ -324,6 +332,7 @@ void serialInit(serialConfig_t *initialSerialConfig, bool softserialEnabled)
serialConfig = initialSerialConfig; serialConfig = initialSerialConfig;
serialPortCount = SERIAL_PORT_COUNT;
memset(&serialPortUsageList, 0, sizeof(serialPortUsageList)); memset(&serialPortUsageList, 0, sizeof(serialPortUsageList));
for (index = 0; index < SERIAL_PORT_COUNT; index++) { for (index = 0; index < SERIAL_PORT_COUNT; index++) {
@ -339,11 +348,37 @@ void serialInit(serialConfig_t *initialSerialConfig, bool softserialEnabled)
#endif #endif
) { ) {
serialPortUsageList[index].identifier = SERIAL_PORT_NONE; serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
serialPortCount--;
} }
} }
} }
} }
void serialRemovePort(serialPortIdentifier_e identifier)
{
for (uint8_t index = 0; index < SERIAL_PORT_COUNT; index++) {
if (serialPortUsageList[index].identifier == identifier) {
serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
serialPortCount--;
}
}
}
uint8_t serialGetAvailablePortCount(void)
{
return serialPortCount;
}
bool serialIsPortAvailable(serialPortIdentifier_e identifier)
{
for (uint8_t index = 0; index < SERIAL_PORT_COUNT; index++) {
if (serialPortUsageList[index].identifier == identifier) {
return true;
}
}
return false;
}
void handleSerial(void) void handleSerial(void)
{ {
#ifdef USE_CLI #ifdef USE_CLI

View file

@ -46,7 +46,7 @@ typedef enum {
BAUD_250000, BAUD_250000,
} baudRate_e; } baudRate_e;
extern uint32_t baudRates[]; extern const uint32_t const baudRates[];
// serial port identifiers are now fixed, these values are used by MSP commands. // serial port identifiers are now fixed, these values are used by MSP commands.
typedef enum { typedef enum {
@ -61,7 +61,7 @@ typedef enum {
SERIAL_PORT_IDENTIFIER_MAX = SERIAL_PORT_SOFTSERIAL2 SERIAL_PORT_IDENTIFIER_MAX = SERIAL_PORT_SOFTSERIAL2
} serialPortIdentifier_e; } serialPortIdentifier_e;
extern serialPortIdentifier_e serialPortIdentifiers[SERIAL_PORT_COUNT]; extern const serialPortIdentifier_e const serialPortIdentifiers[SERIAL_PORT_COUNT];
// //
// runtime // runtime
@ -96,7 +96,11 @@ typedef struct serialConfig_s {
// //
// configuration // configuration
// //
void serialRemovePort(serialPortIdentifier_e identifier);
uint8_t serialGetAvailablePortCount(void);
bool serialIsPortAvailable(serialPortIdentifier_e identifier);
bool isSerialConfigValid(serialConfig_t *serialConfig); bool isSerialConfigValid(serialConfig_t *serialConfig);
serialPortConfig_t *serialFindPortConfiguration(serialPortIdentifier_e identifier);
bool doesConfigurationUsePort(serialPortIdentifier_e portIdentifier); bool doesConfigurationUsePort(serialPortIdentifier_e portIdentifier);
serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function); serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function);
serialPortConfig_t *findNextSerialPortConfig(serialPortFunction_e function); serialPortConfig_t *findNextSerialPortConfig(serialPortFunction_e function);
@ -123,6 +127,7 @@ void waitForSerialPortToFinishTransmitting(serialPort_t *serialPort);
baudRate_e lookupBaudRateIndex(uint32_t baudRate); baudRate_e lookupBaudRateIndex(uint32_t baudRate);
// //
// msp/cli/bootloader // msp/cli/bootloader
// //

View file

@ -1183,9 +1183,12 @@ static bool processOutCommand(uint8_t cmdMSP)
case MSP_CF_SERIAL_CONFIG: case MSP_CF_SERIAL_CONFIG:
headSerialReply( headSerialReply(
((sizeof(uint8_t) + sizeof(uint16_t) + (sizeof(uint8_t) * 4)) * SERIAL_PORT_COUNT) ((sizeof(uint8_t) + sizeof(uint16_t) + (sizeof(uint8_t) * 4)) * serialGetAvailablePortCount())
); );
for (i = 0; i < SERIAL_PORT_COUNT; i++) { for (i = 0; i < SERIAL_PORT_COUNT; i++) {
if (!serialIsPortAvailable(masterConfig.serialConfig.portConfigs[i].identifier)) {
continue;
};
serialize8(masterConfig.serialConfig.portConfigs[i].identifier); serialize8(masterConfig.serialConfig.portConfigs[i].identifier);
serialize16(masterConfig.serialConfig.portConfigs[i].functionMask); serialize16(masterConfig.serialConfig.portConfigs[i].functionMask);
serialize8(masterConfig.serialConfig.portConfigs[i].msp_baudrateIndex); serialize8(masterConfig.serialConfig.portConfigs[i].msp_baudrateIndex);
@ -1595,17 +1598,28 @@ static bool processInCommand(void)
{ {
uint8_t portConfigSize = sizeof(uint8_t) + sizeof(uint16_t) + (sizeof(uint8_t) * 4); uint8_t portConfigSize = sizeof(uint8_t) + sizeof(uint16_t) + (sizeof(uint8_t) * 4);
if ((SERIAL_PORT_COUNT * portConfigSize) != currentPort->dataSize) { if (currentPort->dataSize % portConfigSize != 0) {
headSerialError(0); headSerialError(0);
break; break;
} }
for (i = 0; i < SERIAL_PORT_COUNT; i++) {
masterConfig.serialConfig.portConfigs[i].identifier = read8(); uint8_t remainingPortsInPacket = currentPort->dataSize / portConfigSize;
masterConfig.serialConfig.portConfigs[i].functionMask = read16();
masterConfig.serialConfig.portConfigs[i].msp_baudrateIndex = read8(); while (remainingPortsInPacket--) {
masterConfig.serialConfig.portConfigs[i].gps_baudrateIndex = read8(); uint8_t identifier = read8();
masterConfig.serialConfig.portConfigs[i].telemetry_baudrateIndex = read8();
masterConfig.serialConfig.portConfigs[i].blackbox_baudrateIndex = read8(); serialPortConfig_t *portConfig = serialFindPortConfiguration(identifier);
if (!portConfig) {
headSerialError(0);
break;
}
portConfig->identifier = identifier;
portConfig->functionMask = read16();
portConfig->msp_baudrateIndex = read8();
portConfig->gps_baudrateIndex = read8();
portConfig->telemetry_baudrateIndex = read8();
portConfig->blackbox_baudrateIndex = read8();
} }
} }
break; break;

View file

@ -278,10 +278,22 @@ void init(void)
updateHardwareRevision(); updateHardwareRevision();
#endif #endif
#if defined(NAZE)
if (hardwareRevision == NAZE32_SP) {
serialRemovePort(SERIAL_PORT_SOFTSERIAL2);
} else {
serialRemovePort(SERIAL_PORT_USART3);
}
#endif
#ifdef USE_I2C #ifdef USE_I2C
#if defined(NAZE) #if defined(NAZE)
if (hardwareRevision != NAZE32_SP) { if (hardwareRevision != NAZE32_SP) {
i2cInit(I2C_DEVICE); i2cInit(I2C_DEVICE);
} else {
if (!doesConfigurationUsePort(SERIAL_PORT_USART3)) {
i2cInit(I2C_DEVICE);
}
} }
#elif defined(CC3D) #elif defined(CC3D)
if (!doesConfigurationUsePort(SERIAL_PORT_USART3)) { if (!doesConfigurationUsePort(SERIAL_PORT_USART3)) {

View file

@ -119,9 +119,10 @@
#define USE_USART1 #define USE_USART1
#define USE_USART2 #define USE_USART2
#define USE_USART3
#define USE_SOFTSERIAL1 #define USE_SOFTSERIAL1
#define USE_SOFTSERIAL2 #define USE_SOFTSERIAL2
#define SERIAL_PORT_COUNT 4 #define SERIAL_PORT_COUNT 5
#define SOFTSERIAL_1_TIMER TIM3 #define SOFTSERIAL_1_TIMER TIM3
#define SOFTSERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5 #define SOFTSERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5
@ -130,6 +131,13 @@
#define SOFTSERIAL_2_TIMER_RX_HARDWARE 6 // PWM 7 #define SOFTSERIAL_2_TIMER_RX_HARDWARE 6 // PWM 7
#define SOFTSERIAL_2_TIMER_TX_HARDWARE 7 // PWM 8 #define SOFTSERIAL_2_TIMER_TX_HARDWARE 7 // PWM 8
// USART3 only on NAZE32_SP - Flex Port
#define USART3_RX_PIN Pin_11
#define USART3_TX_PIN Pin_10
#define USART3_GPIO GPIOB
#define USART3_APB1_PERIPHERALS RCC_APB1Periph_USART3
#define USART3_APB2_PERIPHERALS RCC_APB2Periph_GPIOB
#define USE_I2C #define USE_I2C
#define I2C_DEVICE (I2CDEV_2) #define I2C_DEVICE (I2CDEV_2)