mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-25 17:25:20 +03:00
Serial refactor fix (#14007)
* VCP - zero-init USB port in usbVcpOpen * Serial - serialPortIdentifier_e is signed * UART - remove unused serialPortCount * UART - allow compiling spectrum without UART * UART - minor improvements closeSerialPort tests for NULL, no other functional changes
This commit is contained in:
parent
6e79712906
commit
4d697c2ce1
10 changed files with 30 additions and 58 deletions
|
@ -98,7 +98,7 @@ typedef struct serialPort_s {
|
||||||
|
|
||||||
serialIdleCallbackPtr idleCallback;
|
serialIdleCallbackPtr idleCallback;
|
||||||
|
|
||||||
uint8_t identifier; // actually serialPortIdentifier_e; avoid circular header dependency
|
int8_t identifier; // actually serialPortIdentifier_e; avoid circular header dependency
|
||||||
} serialPort_t;
|
} serialPort_t;
|
||||||
|
|
||||||
typedef struct serialPinConfig_s {
|
typedef struct serialPinConfig_s {
|
||||||
|
|
|
@ -24,7 +24,7 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#ifdef USE_UART
|
#if defined(USE_UART) || defined(USE_LPUART) || defined(USE_SOFTSERIAL)
|
||||||
|
|
||||||
#include "build/build_config.h"
|
#include "build/build_config.h"
|
||||||
|
|
||||||
|
@ -34,7 +34,6 @@
|
||||||
|
|
||||||
#include "pg/pg_ids.h"
|
#include "pg/pg_ids.h"
|
||||||
|
|
||||||
#if defined(USE_UART) || defined(USE_LPUART) || defined(USE_SOFTSERIAL)
|
|
||||||
typedef struct serialDefaultPin_s {
|
typedef struct serialDefaultPin_s {
|
||||||
serialPortIdentifier_e ident;
|
serialPortIdentifier_e ident;
|
||||||
ioTag_t rxIO, txIO, inverterIO;
|
ioTag_t rxIO, txIO, inverterIO;
|
||||||
|
@ -103,4 +102,3 @@ void pgResetFn_serialPinConfig(serialPinConfig_t *serialPinConfig)
|
||||||
|
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
#endif
|
|
||||||
|
|
|
@ -56,7 +56,7 @@ void uartPinConfigure(const serialPinConfig_t *pSerialPinConfig)
|
||||||
#if UART_TRAIT_PINSWAP
|
#if UART_TRAIT_PINSWAP
|
||||||
bool swap = false;
|
bool swap = false;
|
||||||
#endif
|
#endif
|
||||||
for (unsigned pindex = 0 ; pindex < UARTHARDWARE_MAX_PINS ; pindex++) {
|
for (unsigned pindex = 0; pindex < UARTHARDWARE_MAX_PINS; pindex++) {
|
||||||
if (cfgRx && cfgRx == hardware->rxPins[pindex].pin) {
|
if (cfgRx && cfgRx == hardware->rxPins[pindex].pin) {
|
||||||
uartdev->rx = hardware->rxPins[pindex];
|
uartdev->rx = hardware->rxPins[pindex];
|
||||||
}
|
}
|
||||||
|
|
|
@ -156,8 +156,6 @@ const char* serialPortNames[SERIAL_PORT_COUNT] = {
|
||||||
#endif
|
#endif
|
||||||
};
|
};
|
||||||
|
|
||||||
static uint8_t serialPortCount;
|
|
||||||
|
|
||||||
const uint32_t baudRates[] = {0, 9600, 19200, 38400, 57600, 115200, 230400, 250000,
|
const uint32_t baudRates[] = {0, 9600, 19200, 38400, 57600, 115200, 230400, 250000,
|
||||||
400000, 460800, 500000, 921600, 1000000, 1500000, 2000000, 2470000}; // see baudRate_e
|
400000, 460800, 500000, 921600, 1000000, 1500000, 2000000, 2470000}; // see baudRate_e
|
||||||
|
|
||||||
|
@ -179,7 +177,7 @@ serialPortConfig_t* serialFindPortConfigurationMutable(serialPortIdentifier_e id
|
||||||
|
|
||||||
const serialPortConfig_t* serialFindPortConfiguration(serialPortIdentifier_e identifier)
|
const serialPortConfig_t* serialFindPortConfiguration(serialPortIdentifier_e identifier)
|
||||||
{
|
{
|
||||||
return findInPortConfigs_identifier(serialConfigMutable()->portConfigs, ARRAYLEN(serialConfig()->portConfigs), identifier);
|
return findInPortConfigs_identifier(serialConfig()->portConfigs, ARRAYLEN(serialConfig()->portConfigs), identifier);
|
||||||
}
|
}
|
||||||
|
|
||||||
PG_REGISTER_WITH_RESET_FN(serialConfig_t, serialConfig, PG_SERIAL_CONFIG, 1);
|
PG_REGISTER_WITH_RESET_FN(serialConfig_t, serialConfig, PG_SERIAL_CONFIG, 1);
|
||||||
|
@ -379,9 +377,9 @@ bool isSerialPortShared(const serialPortConfig_t *portConfig, uint16_t functionM
|
||||||
|
|
||||||
serialPort_t *findSharedSerialPort(uint16_t functionMask, serialPortFunction_e sharedWithFunction)
|
serialPort_t *findSharedSerialPort(uint16_t functionMask, serialPortFunction_e sharedWithFunction)
|
||||||
{
|
{
|
||||||
for (unsigned i = 0; i < ARRAYLEN(serialConfig()->portConfigs); i++) {
|
for (const serialPortConfig_t *candidate = serialConfig()->portConfigs;
|
||||||
const serialPortConfig_t *candidate = &serialConfig()->portConfigs[i];
|
candidate < ARRAYEND(serialConfig()->portConfigs);
|
||||||
|
candidate++) {
|
||||||
if (isSerialPortShared(candidate, functionMask, sharedWithFunction)) {
|
if (isSerialPortShared(candidate, functionMask, sharedWithFunction)) {
|
||||||
const serialPortUsage_t *serialPortUsage = findSerialPortUsageByIdentifier(candidate->identifier);
|
const serialPortUsage_t *serialPortUsage = findSerialPortUsageByIdentifier(candidate->identifier);
|
||||||
if (!serialPortUsage) {
|
if (!serialPortUsage) {
|
||||||
|
@ -437,7 +435,7 @@ bool isSerialConfigValid(serialConfig_t *serialConfigToCheck)
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t bitCount = popcount(portConfig->functionMask);
|
uint8_t bitCount = popcount32(portConfig->functionMask);
|
||||||
|
|
||||||
#ifdef USE_VTX_MSP
|
#ifdef USE_VTX_MSP
|
||||||
if ((portConfig->functionMask & FUNCTION_VTX_MSP) && bitCount == 1) { // VTX MSP has to be shared with RX or MSP serial
|
if ((portConfig->functionMask & FUNCTION_VTX_MSP) && bitCount == 1) { // VTX MSP has to be shared with RX or MSP serial
|
||||||
|
@ -547,6 +545,9 @@ serialPort_t *openSerialPort(
|
||||||
|
|
||||||
void closeSerialPort(serialPort_t *serialPort)
|
void closeSerialPort(serialPort_t *serialPort)
|
||||||
{
|
{
|
||||||
|
if (!serialPort) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
serialPortUsage_t *serialPortUsage = findSerialPortUsageByPort(serialPort);
|
serialPortUsage_t *serialPortUsage = findSerialPortUsageByPort(serialPort);
|
||||||
if (!serialPortUsage) {
|
if (!serialPortUsage) {
|
||||||
// already closed
|
// already closed
|
||||||
|
@ -566,7 +567,6 @@ void serialInit(bool softserialEnabled, serialPortIdentifier_e serialPortToDisab
|
||||||
UNUSED(softserialEnabled);
|
UNUSED(softserialEnabled);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
serialPortCount = SERIAL_PORT_COUNT;
|
|
||||||
memset(&serialPortUsageList, 0, sizeof(serialPortUsageList));
|
memset(&serialPortUsageList, 0, sizeof(serialPortUsageList));
|
||||||
|
|
||||||
for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
|
for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
|
||||||
|
@ -575,7 +575,6 @@ void serialInit(bool softserialEnabled, serialPortIdentifier_e serialPortToDisab
|
||||||
if (serialPortToDisable != SERIAL_PORT_NONE
|
if (serialPortToDisable != SERIAL_PORT_NONE
|
||||||
&& serialPortUsageList[index].identifier == serialPortToDisable) {
|
&& serialPortUsageList[index].identifier == serialPortToDisable) {
|
||||||
serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
|
serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
|
||||||
serialPortCount--;
|
|
||||||
continue; // this index is deleted
|
continue; // this index is deleted
|
||||||
}
|
}
|
||||||
{
|
{
|
||||||
|
@ -584,7 +583,6 @@ void serialInit(bool softserialEnabled, serialPortIdentifier_e serialPortToDisab
|
||||||
if (resourceIndex >= 0 // resource exists
|
if (resourceIndex >= 0 // resource exists
|
||||||
&& !(serialPinConfig()->ioTagTx[resourceIndex] || serialPinConfig()->ioTagRx[resourceIndex])) {
|
&& !(serialPinConfig()->ioTagTx[resourceIndex] || serialPinConfig()->ioTagRx[resourceIndex])) {
|
||||||
serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
|
serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
|
||||||
serialPortCount--;
|
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
@ -596,7 +594,6 @@ void serialInit(bool softserialEnabled, serialPortIdentifier_e serialPortToDisab
|
||||||
#endif
|
#endif
|
||||||
) {
|
) {
|
||||||
serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
|
serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
|
||||||
serialPortCount--;
|
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -608,15 +605,9 @@ void serialRemovePort(serialPortIdentifier_e identifier)
|
||||||
serialPortUsage_t* usage;
|
serialPortUsage_t* usage;
|
||||||
while ((usage = findSerialPortUsageByIdentifier(identifier)) != NULL) {
|
while ((usage = findSerialPortUsageByIdentifier(identifier)) != NULL) {
|
||||||
usage->identifier = SERIAL_PORT_NONE;
|
usage->identifier = SERIAL_PORT_NONE;
|
||||||
serialPortCount--;
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t serialGetAvailablePortCount(void)
|
|
||||||
{
|
|
||||||
return serialPortCount;
|
|
||||||
}
|
|
||||||
|
|
||||||
bool serialIsPortAvailable(serialPortIdentifier_e identifier)
|
bool serialIsPortAvailable(serialPortIdentifier_e identifier)
|
||||||
{
|
{
|
||||||
return findSerialPortUsageByIdentifier(identifier) != NULL;
|
return findSerialPortUsageByIdentifier(identifier) != NULL;
|
||||||
|
|
|
@ -99,7 +99,6 @@ typedef enum {
|
||||||
SERIAL_PORT_UART9,
|
SERIAL_PORT_UART9,
|
||||||
SERIAL_PORT_USART10,
|
SERIAL_PORT_USART10,
|
||||||
SERIAL_PORT_UART10 = SERIAL_PORT_USART10,
|
SERIAL_PORT_UART10 = SERIAL_PORT_USART10,
|
||||||
SERIAL_PORT_USART_MAX = SERIAL_PORT_USART10,
|
|
||||||
|
|
||||||
SERIAL_PORT_USB_VCP = 20,
|
SERIAL_PORT_USB_VCP = 20,
|
||||||
|
|
||||||
|
@ -161,7 +160,6 @@ typedef void serialConsumer(uint8_t);
|
||||||
//
|
//
|
||||||
void serialInit(bool softserialEnabled, serialPortIdentifier_e serialPortToDisable);
|
void serialInit(bool softserialEnabled, serialPortIdentifier_e serialPortToDisable);
|
||||||
void serialRemovePort(serialPortIdentifier_e identifier);
|
void serialRemovePort(serialPortIdentifier_e identifier);
|
||||||
uint8_t serialGetAvailablePortCount(void);
|
|
||||||
bool serialIsPortAvailable(serialPortIdentifier_e identifier);
|
bool serialIsPortAvailable(serialPortIdentifier_e identifier);
|
||||||
bool isSerialConfigValid(serialConfig_t *serialConfig);
|
bool isSerialConfigValid(serialConfig_t *serialConfig);
|
||||||
const serialPortConfig_t *serialFindPortConfiguration(serialPortIdentifier_e identifier);
|
const serialPortConfig_t *serialFindPortConfiguration(serialPortIdentifier_e identifier);
|
||||||
|
|
|
@ -88,8 +88,7 @@ void mspSerialAllocatePorts(void)
|
||||||
|
|
||||||
void mspSerialReleasePortIfAllocated(serialPort_t *serialPort)
|
void mspSerialReleasePortIfAllocated(serialPort_t *serialPort)
|
||||||
{
|
{
|
||||||
for (unsigned portIndex = 0; portIndex < ARRAYLEN(mspPorts); portIndex++) {
|
for (mspPort_t *candidateMspPort = mspPorts; candidateMspPort < ARRAYEND(mspPorts); candidateMspPort++) {
|
||||||
mspPort_t *candidateMspPort = &mspPorts[portIndex];
|
|
||||||
if (candidateMspPort->port == serialPort) {
|
if (candidateMspPort->port == serialPort) {
|
||||||
closeSerialPort(serialPort);
|
closeSerialPort(serialPort);
|
||||||
memset(candidateMspPort, 0, sizeof(mspPort_t));
|
memset(candidateMspPort, 0, sizeof(mspPort_t));
|
||||||
|
@ -99,8 +98,7 @@ void mspSerialReleasePortIfAllocated(serialPort_t *serialPort)
|
||||||
|
|
||||||
mspDescriptor_t getMspSerialPortDescriptor(const serialPortIdentifier_e portIdentifier)
|
mspDescriptor_t getMspSerialPortDescriptor(const serialPortIdentifier_e portIdentifier)
|
||||||
{
|
{
|
||||||
for (unsigned portIndex = 0; portIndex < ARRAYLEN(mspPorts); portIndex++) {
|
for (mspPort_t *candidateMspPort = mspPorts; candidateMspPort < ARRAYEND(mspPorts); candidateMspPort++) {
|
||||||
mspPort_t *candidateMspPort = &mspPorts[portIndex];
|
|
||||||
if (candidateMspPort->port && candidateMspPort->port->identifier == portIdentifier) {
|
if (candidateMspPort->port && candidateMspPort->port->identifier == portIdentifier) {
|
||||||
return candidateMspPort->descriptor;
|
return candidateMspPort->descriptor;
|
||||||
}
|
}
|
||||||
|
@ -111,8 +109,7 @@ mspDescriptor_t getMspSerialPortDescriptor(const serialPortIdentifier_e portIden
|
||||||
#if defined(USE_TELEMETRY)
|
#if defined(USE_TELEMETRY)
|
||||||
void mspSerialReleaseSharedTelemetryPorts(void)
|
void mspSerialReleaseSharedTelemetryPorts(void)
|
||||||
{
|
{
|
||||||
for (unsigned portIndex = 0; portIndex < ARRAYLEN(mspPorts); portIndex++) {
|
for (mspPort_t *candidateMspPort = mspPorts; candidateMspPort < ARRAYEND(mspPorts); candidateMspPort++) {
|
||||||
mspPort_t *candidateMspPort = &mspPorts[portIndex];
|
|
||||||
if (candidateMspPort->sharedWithTelemetry) {
|
if (candidateMspPort->sharedWithTelemetry) {
|
||||||
closeSerialPort(candidateMspPort->port);
|
closeSerialPort(candidateMspPort->port);
|
||||||
memset(candidateMspPort, 0, sizeof(mspPort_t));
|
memset(candidateMspPort, 0, sizeof(mspPort_t));
|
||||||
|
@ -521,8 +518,7 @@ void mspProcessPacket(mspPort_t *mspPort, mspProcessCommandFnPtr mspProcessComma
|
||||||
*/
|
*/
|
||||||
void mspSerialProcess(mspEvaluateNonMspData_e evaluateNonMspData, mspProcessCommandFnPtr mspProcessCommandFn, mspProcessReplyFnPtr mspProcessReplyFn)
|
void mspSerialProcess(mspEvaluateNonMspData_e evaluateNonMspData, mspProcessCommandFnPtr mspProcessCommandFn, mspProcessReplyFnPtr mspProcessReplyFn)
|
||||||
{
|
{
|
||||||
for (unsigned portIndex = 0; portIndex < ARRAYLEN(mspPorts); portIndex++) {
|
for (mspPort_t *mspPort = mspPorts; mspPort < ARRAYEND(mspPorts); mspPort++) {
|
||||||
mspPort_t * const mspPort = &mspPorts[portIndex];
|
|
||||||
if (!mspPort->port) {
|
if (!mspPort->port) {
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
|
@ -577,8 +573,7 @@ void mspSerialProcess(mspEvaluateNonMspData_e evaluateNonMspData, mspProcessComm
|
||||||
|
|
||||||
bool mspSerialWaiting(void)
|
bool mspSerialWaiting(void)
|
||||||
{
|
{
|
||||||
for (unsigned portIndex = 0; portIndex < ARRAYLEN(mspPorts); portIndex++) {
|
for (mspPort_t *mspPort = mspPorts; mspPort < ARRAYEND(mspPorts); mspPort++) {
|
||||||
mspPort_t * const mspPort = &mspPorts[portIndex];
|
|
||||||
if (!mspPort->port) {
|
if (!mspPort->port) {
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
|
@ -600,8 +595,7 @@ int mspSerialPush(serialPortIdentifier_e port, uint8_t cmd, uint8_t *data, int d
|
||||||
{
|
{
|
||||||
int ret = 0;
|
int ret = 0;
|
||||||
|
|
||||||
for (unsigned portIndex = 0; ARRAYLEN(mspPorts); portIndex++) {
|
for (mspPort_t *mspPort = mspPorts; mspPort < ARRAYEND(mspPorts); mspPort++) {
|
||||||
mspPort_t * const mspPort = &mspPorts[portIndex];
|
|
||||||
|
|
||||||
// XXX Kludge!!! Avoid zombie VCP port (avoid VCP entirely for now)
|
// XXX Kludge!!! Avoid zombie VCP port (avoid VCP entirely for now)
|
||||||
if (!mspPort->port
|
if (!mspPort->port
|
||||||
|
@ -629,8 +623,7 @@ uint32_t mspSerialTxBytesFree(void)
|
||||||
{
|
{
|
||||||
uint32_t ret = UINT32_MAX;
|
uint32_t ret = UINT32_MAX;
|
||||||
|
|
||||||
for (unsigned portIndex = 0; portIndex < ARRAYLEN(mspPorts); portIndex++) {
|
for (mspPort_t *mspPort = mspPorts; mspPort < ARRAYEND(mspPorts); mspPort++) {
|
||||||
mspPort_t * const mspPort = &mspPorts[portIndex];
|
|
||||||
if (!mspPort->port) {
|
if (!mspPort->port) {
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
|
|
|
@ -237,7 +237,7 @@ void spektrumBind(rxConfig_t *rxConfig)
|
||||||
if (!portConfig) {
|
if (!portConfig) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
#if defined(USE_UART) || defined(USE_LPUART) || defined(USE_SOFTSERIAL)
|
||||||
const int resourceIndex = serialResourceIndex(portConfig->identifier);
|
const int resourceIndex = serialResourceIndex(portConfig->identifier);
|
||||||
const ioTag_t txPin = serialPinConfig()->ioTagTx[resourceIndex];
|
const ioTag_t txPin = serialPinConfig()->ioTagTx[resourceIndex];
|
||||||
const ioTag_t rxPin = serialPinConfig()->ioTagRx[resourceIndex];
|
const ioTag_t rxPin = serialPinConfig()->ioTagRx[resourceIndex];
|
||||||
|
@ -255,7 +255,7 @@ void spektrumBind(rxConfig_t *rxConfig)
|
||||||
default:
|
default:
|
||||||
bindPin = rxConfig->halfDuplex ? txPin : rxPin;
|
bindPin = rxConfig->halfDuplex ? txPin : rxPin;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
if (!bindPin) {
|
if (!bindPin) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
|
@ -52,7 +52,7 @@ USBD_INFO_T gUsbDevice;
|
||||||
|
|
||||||
#define USB_TIMEOUT 50
|
#define USB_TIMEOUT 50
|
||||||
|
|
||||||
static vcpPort_t vcpPort;
|
static vcpPort_t vcpPort = {0};
|
||||||
|
|
||||||
static void usbVcpSetBaudRate(serialPort_t *instance, uint32_t baudRate)
|
static void usbVcpSetBaudRate(serialPort_t *instance, uint32_t baudRate)
|
||||||
{
|
{
|
||||||
|
@ -203,8 +203,6 @@ static const struct serialPortVTable usbVTable[] = {
|
||||||
|
|
||||||
serialPort_t *usbVcpOpen(void)
|
serialPort_t *usbVcpOpen(void)
|
||||||
{
|
{
|
||||||
vcpPort_t *s;
|
|
||||||
|
|
||||||
IOInit(IOGetByTag(IO_TAG(PA11)), OWNER_USB, 0);
|
IOInit(IOGetByTag(IO_TAG(PA11)), OWNER_USB, 0);
|
||||||
IOInit(IOGetByTag(IO_TAG(PA12)), OWNER_USB, 0);
|
IOInit(IOGetByTag(IO_TAG(PA12)), OWNER_USB, 0);
|
||||||
|
|
||||||
|
@ -216,10 +214,9 @@ serialPort_t *usbVcpOpen(void)
|
||||||
/* USB device and class init */
|
/* USB device and class init */
|
||||||
USBD_Init(&gUsbDevice, USBD_SPEED_FS, &USBD_DESC_VCP, &USBD_CDC_CLASS, USB_DevUserHandler);
|
USBD_Init(&gUsbDevice, USBD_SPEED_FS, &USBD_DESC_VCP, &USBD_CDC_CLASS, USB_DevUserHandler);
|
||||||
|
|
||||||
s = &vcpPort;
|
vcpPort_t *s = &vcpPort;
|
||||||
s->port.vTable = usbVTable;
|
s->port.vTable = usbVTable;
|
||||||
|
return &s->port;
|
||||||
return (serialPort_t *)s;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
uint32_t usbVcpGetBaudRate(serialPort_t *instance)
|
uint32_t usbVcpGetBaudRate(serialPort_t *instance)
|
||||||
|
|
|
@ -50,7 +50,7 @@
|
||||||
|
|
||||||
#define USB_TIMEOUT 50
|
#define USB_TIMEOUT 50
|
||||||
|
|
||||||
static vcpPort_t vcpPort;
|
static vcpPort_t vcpPort = {0};
|
||||||
|
|
||||||
otg_core_type otg_core_struct;
|
otg_core_type otg_core_struct;
|
||||||
|
|
||||||
|
@ -483,8 +483,6 @@ static const struct serialPortVTable usbVTable[] = {
|
||||||
|
|
||||||
serialPort_t *usbVcpOpen(void)
|
serialPort_t *usbVcpOpen(void)
|
||||||
{
|
{
|
||||||
vcpPort_t *s;
|
|
||||||
|
|
||||||
IOInit(IOGetByTag(IO_TAG(PA11)), OWNER_USB, 0);
|
IOInit(IOGetByTag(IO_TAG(PA11)), OWNER_USB, 0);
|
||||||
IOInit(IOGetByTag(IO_TAG(PA12)), OWNER_USB, 0);
|
IOInit(IOGetByTag(IO_TAG(PA12)), OWNER_USB, 0);
|
||||||
usb_gpio_config();
|
usb_gpio_config();
|
||||||
|
@ -504,12 +502,12 @@ serialPort_t *usbVcpOpen(void)
|
||||||
USB_ID,
|
USB_ID,
|
||||||
&cdc_class_handler,
|
&cdc_class_handler,
|
||||||
&cdc_desc_handler);
|
&cdc_desc_handler);
|
||||||
s = &vcpPort;
|
|
||||||
s->port.vTable = usbVTable;
|
|
||||||
|
|
||||||
TxTimerConfig();
|
TxTimerConfig();
|
||||||
|
|
||||||
return (serialPort_t *)s;
|
vcpPort_t *s = &vcpPort;
|
||||||
|
s->port.vTable = usbVTable;
|
||||||
|
return &s->port;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint32_t usbVcpGetBaudRate(serialPort_t *instance)
|
uint32_t usbVcpGetBaudRate(serialPort_t *instance)
|
||||||
|
|
|
@ -63,7 +63,7 @@ USBD_HandleTypeDef USBD_Device;
|
||||||
|
|
||||||
#define USB_TIMEOUT 50
|
#define USB_TIMEOUT 50
|
||||||
|
|
||||||
static vcpPort_t vcpPort;
|
static vcpPort_t vcpPort = {0};
|
||||||
|
|
||||||
static void usbVcpSetBaudRate(serialPort_t *instance, uint32_t baudRate)
|
static void usbVcpSetBaudRate(serialPort_t *instance, uint32_t baudRate)
|
||||||
{
|
{
|
||||||
|
@ -218,8 +218,6 @@ static const struct serialPortVTable usbVTable[] = {
|
||||||
|
|
||||||
serialPort_t *usbVcpOpen(void)
|
serialPort_t *usbVcpOpen(void)
|
||||||
{
|
{
|
||||||
vcpPort_t *s;
|
|
||||||
|
|
||||||
IOInit(IOGetByTag(IO_TAG(PA11)), OWNER_USB, 0);
|
IOInit(IOGetByTag(IO_TAG(PA11)), OWNER_USB, 0);
|
||||||
IOInit(IOGetByTag(IO_TAG(PA12)), OWNER_USB, 0);
|
IOInit(IOGetByTag(IO_TAG(PA12)), OWNER_USB, 0);
|
||||||
|
|
||||||
|
@ -275,10 +273,9 @@ serialPort_t *usbVcpOpen(void)
|
||||||
USB_Interrupts_Config();
|
USB_Interrupts_Config();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
s = &vcpPort;
|
vcpPort_t *s = &vcpPort;
|
||||||
s->port.vTable = usbVTable;
|
s->port.vTable = usbVTable;
|
||||||
|
return &s->port;
|
||||||
return (serialPort_t *)s;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
uint32_t usbVcpGetBaudRate(serialPort_t *instance)
|
uint32_t usbVcpGetBaudRate(serialPort_t *instance)
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue