Support programming of Arduino devices in serial passthrough mode (#5129)

* Support DTR in serial passthrough mode to enable programming of Arduino
based devices such as MinimOSD.

Use 'serialpassthrough 5 57600 rxtx 56' and then use Ardino to program MinimOSD
Use 'serialpassthrough 5 115200' and then use MWOSD configurator to setup

* Fix comment for CDC_SetCtrlLineStateCb routine

* Handle F7 CDC interface

* Use strToPin() to allow easy port/pin specification

* Fix use of CDC_SetCtrlLineStateCb for all processor types

* Only set baud when specified

* Fix unit tests for cli

* Only register callback if needed

* Fix white space

* Provide implementation of IOConfigGPIO in SITL

* Update serialpassthrough help text

* DTR handling through serial drivers

* Fix F3, F7 and SITL builds

* If serialpassthrough command specifies baud rate of 0, set baud rate over USB. MWOSD configurator can now access config and reflash MinimOSD without rebooting and changing baud rate.

* Fix F3 build

* Fix failing unit tests

* Use resources to declare DTR pin assignment

* Don't assert DTR during normal operation as MW_OSD doesn't like it

* MW_OSD must be built with MAX_SOFTRESET defined in order to support DTR resets

* Minimise changes after dropping DTR pin param from serialpassthrough cmd

* Remove DTR pin param from serialpassthrough cmd

* Treat ioDtrTag as boolean in conditional statements

* Tidy buffer check

* Check buffer size in CDC_Itf_Control

* Fix unit test

* Add documentation for DTR

* Add note on MAX_SOFTRESET to documentation

* Remove superfluous function definitions

* Fix tabs

* Fix tabs

* Removed superfluous entried from vtable

* Backout whitespace changes unrelated to this PR

* Pass true/false to IOWrite()

* Fix line coding packing

* Add LINE_CODING structure defintion

* Revise serial documentation

* Prevent tx buffer overflow in serialPassthrough()

* Revert change unrelated to PR

* Review feedback from ledvinap

* Fix unit test

* Use PINIO to drive DTR

* Fix unit test

* Remove change unrelated to PR

* Fix SITL build

* Use shifted bits for mask definition

* Fix serialpassthrough documentation

* Only compile PINIO functionality if USE_PINIO defined

* IOConfigGPIO not needed

* Move cbCtrlLine callback to cli.c

* serialPassthrough params changed

* Check packed structure size

* Fix unit test

* Tidy up baud rate handling
This commit is contained in:
SteveCEvans 2018-03-21 10:17:31 +00:00 committed by Michael Keller
parent 46291a8374
commit 5558174d33
23 changed files with 347 additions and 33 deletions

View File

@ -87,16 +87,63 @@ The allowable baud rates are as follows:
Cleanflight can enter a special passthrough mode whereby it passes serial data through to a device connected to a UART/SoftSerial port. This is useful to change the configuration of a Cleanflight peripheral such as an OSD, bluetooth dongle, serial RX etc.
To initiate passthrough mode, use the CLI command `serialpassthrough` This command takes three arguments.
To initiate passthrough mode, use the CLI command `serialpassthrough` This command takes four arguments.
serialpassthrough <id> [baud] [mode]
serialpassthrough <id> [baud] [mode] [DTR PINIO]
ID is the internal identifier of the serial port from Cleanflight source code (see serialPortIdentifier_e in the source). For instance UART1-UART4 are 0-3 and SoftSerial1/SoftSerial2 are 30/31 respectively. Baud is the desired baud rate, and mode is a combination of the keywords rx and tx (rxtx is full duplex). The baud and mode parameters can be used to override the configured values for the specified port.
ID is the internal identifier of the serial port from Cleanflight source code (see serialPortIdentifier_e in the source). For instance UART1-UART4 are 0-3 and SoftSerial1/SoftSerial2 are 30/31 respectively. Baud is the desired baud rate, and mode is a combination of the keywords rx and tx (rxtx is full duplex). The baud and mode parameters can be used to override the configured values for the specified port. `DTR PINIO` identifies the PINIO resource which is optionally connected to a DTR line of the attached device.
For example. If you have your MWOSD connected to UART 2, you could enable communicaton to this device using the following command. This command does not specify the baud rate or mode, using the one configured for the port (see above).
serialpassthrough 1
If a baud rate is not specified, or is set to 0, then `serialpassthrough` supports changing of the baud rate over USB. This allows tools such as the MWOSD GUI to dynamically set the baud rate to, for example 57600 for reflashing the MWOSD firmware and then 115200 for adjusting settings without having to powercycle your flight control board between the two.
_To use a tool such as the MWOSD GUI, it is necessary to disconnect or exit Cleanflight configurator._
**To exit serial passthrough mode, power cycle your flight control board.**
In order to reflash an Arduino based device such as a MWOSD via `serialpassthrough` if is necessary to connect the DTR line in addition to the RX and TX serial lines. The DTR is used as a reset line to invoke the bootloader. The DTR line may be connected to any GPIO pin on the flight control board. This pin must then be associated with a PINIO resource, the instance of which is then passed to the serialpassthrough command. The DTR line associated with any given UART may be set using the CLI command `resource` specifying it as a PINIO resource.
For example, the following configuration for an OpenPilot Revolution shows the UART6 serial port to be configured with TX on pin C06, RX on pin C07 and a DTR connection using PINIO on pin C08.
```
resource SERIAL_TX 1 A09
resource SERIAL_TX 3 B10
resource SERIAL_TX 4 A00
resource SERIAL_TX 6 C06
resource SERIAL_RX 1 A10
resource SERIAL_RX 3 B11
resource SERIAL_RX 6 C07
resource PINIO 1 C08
```
To assign the DTR line to another pin use the following command.
```
resource PINIO 1 c05
```
To disassociate DTR from a pin use the following command.
```
resource PINIO 1 none
```
Having configured a PINIO resource assocaited with a DTR line as per the above example, connection to an MWOSD attached to an Openpilot Revolution could be achieved using the following command.
```serialpassthrough 5 0 rxtx 1```
This will connect using UART 6, with the baud rate set over USB, full duplex, and with DTR driven on PINIO resource 1.
A (desirable) side effect of configuring the DTR line to be associated with a PINIO resource, is that when the FC is reset, the attached Arduino device will also be reset.
Note that if DTR is left configured on a port being used with a standard build of MWOSD firmware, the display will break-up when the flight controller is reset. This is because, by default, the MWOSD does not correctly handle resets from DTR. There are two solutions to this:
1. Assign the DTR pin using the resource command above prior to reflashing MWOSD, and then dissasociate DTR from the pin.
2. Rebuild MWOSD with MAX_SOFTRESET defined. The MWOSD will then be reset correctly every time the flight controller is reset.

View File

@ -547,7 +547,7 @@ uint8_t usbd_cdc_Setup (void *pdev,
else /* No Data request */
{
/* Transfer the command to the interface layer */
APP_FOPS.pIf_Ctrl(req->bRequest, NULL, 0);
APP_FOPS.pIf_Ctrl(req->bRequest, (uint8_t *)&req->wValue, sizeof(req->wValue));
}
return USBD_OK;

View File

@ -86,6 +86,24 @@ void serialSetMode(serialPort_t *instance, portMode_e mode)
instance->vTable->setMode(instance, mode);
}
void serialSetCtrlLineStateCb(serialPort_t *serialPort, void (*cb)(void *context, uint16_t ctrlLineState), void *context)
{
// If a callback routine for changes to control line state is supported by the underlying
// driver, then set the callback.
if (serialPort->vTable->setCtrlLineStateCb) {
serialPort->vTable->setCtrlLineStateCb(serialPort, cb, context);
}
}
void serialSetBaudRateCb(serialPort_t *serialPort, void (*cb)(serialPort_t *context, uint32_t baud), serialPort_t *context)
{
// If a callback routine for changes to baud rate is supported by the underlying
// driver, then set the callback.
if (serialPort->vTable->setBaudRateCb) {
serialPort->vTable->setBaudRateCb(serialPort, cb, context);
}
}
void serialWriteBufShim(void *instance, const uint8_t *data, int count)
{
serialWriteBuf((serialPort_t *)instance, data, count);

View File

@ -48,6 +48,10 @@ typedef enum {
SERIAL_BIDIR_NOPULL = 1 << 5, // disable pulls in BIDIR RX mode
} portOptions_e;
// Define known line control states which may be passed up by underlying serial driver callback
#define CTRL_LINE_STATE_DTR (1 << 0)
#define CTRL_LINE_STATE_RTS (1 << 1)
typedef void (*serialReceiveCallbackPtr)(uint16_t data, void *rxCallbackData); // used by serial drivers to return frames to app
typedef struct serialPort_s {
@ -105,6 +109,8 @@ struct serialPortVTable {
bool (*isSerialTransmitBufferEmpty)(const serialPort_t *instance);
void (*setMode)(serialPort_t *instance, portMode_e mode);
void (*setCtrlLineStateCb)(serialPort_t *instance, void (*cb)(void *instance, uint16_t ctrlLineState), void *context);
void (*setBaudRateCb)(serialPort_t *instance, void (*cb)(serialPort_t *context, uint32_t baud), serialPort_t *context);
void (*writeBuf)(serialPort_t *instance, const void *data, int count);
// Optional functions used to buffer large writes.
@ -119,6 +125,8 @@ void serialWriteBuf(serialPort_t *instance, const uint8_t *data, int count);
uint8_t serialRead(serialPort_t *instance);
void serialSetBaudRate(serialPort_t *instance, uint32_t baudRate);
void serialSetMode(serialPort_t *instance, portMode_e mode);
void serialSetCtrlLineStateCb(serialPort_t *instance, void (*cb)(void *context, uint16_t ctrlLineState), void *context);
void serialSetBaudRateCb(serialPort_t *instance, void (*cb)(serialPort_t *context, uint32_t baud), serialPort_t *context);
bool isSerialTransmitBufferEmpty(const serialPort_t *instance);
void serialPrint(serialPort_t *instance, const char *str);
uint32_t serialGetBaudRate(serialPort_t *instance);

View File

@ -842,6 +842,8 @@ const struct serialPortVTable escSerialVTable[] = {
.serialSetBaudRate = escSerialSetBaudRate,
.isSerialTransmitBufferEmpty = isEscSerialTransmitBufferEmpty,
.setMode = escSerialSetMode,
.setCtrlLineStateCb = NULL,
.setBaudRateCb = NULL,
.writeBuf = NULL,
.beginWrite = NULL,
.endWrite = NULL

View File

@ -635,6 +635,8 @@ static const struct serialPortVTable softSerialVTable = {
.serialSetBaudRate = softSerialSetBaudRate,
.isSerialTransmitBufferEmpty = isSoftSerialTransmitBufferEmpty,
.setMode = softSerialSetMode,
.setCtrlLineStateCb = NULL,
.setBaudRateCb = NULL,
.writeBuf = NULL,
.beginWrite = NULL,
.endWrite = NULL

View File

@ -263,6 +263,8 @@ static const struct serialPortVTable tcpVTable = {
.serialSetBaudRate = NULL,
.isSerialTransmitBufferEmpty = isTcpTransmitBufferEmpty,
.setMode = NULL,
.setCtrlLineStateCb = NULL,
.setBaudRateCb = NULL,
.writeBuf = NULL,
.beginWrite = NULL,
.endWrite = NULL,

View File

@ -274,6 +274,8 @@ const struct serialPortVTable uartVTable[] = {
.serialSetBaudRate = uartSetBaudRate,
.isSerialTransmitBufferEmpty = isUartTransmitBufferEmpty,
.setMode = uartSetMode,
.setCtrlLineStateCb = NULL,
.setBaudRateCb = NULL,
.writeBuf = NULL,
.beginWrite = NULL,
.endWrite = NULL,

View File

@ -361,6 +361,8 @@ const struct serialPortVTable uartVTable[] = {
.serialSetBaudRate = uartSetBaudRate,
.isSerialTransmitBufferEmpty = isUartTransmitBufferEmpty,
.setMode = uartSetMode,
.setCtrlLineStateCb = NULL,
.setBaudRateCb = NULL,
.writeBuf = NULL,
.beginWrite = NULL,
.endWrite = NULL,

View File

@ -67,6 +67,22 @@ static void usbVcpSetMode(serialPort_t *instance, portMode_e mode)
// TODO implement
}
static void usbVcpSetCtrlLineStateCb(serialPort_t *instance, void (*cb)(void *context, uint16_t ctrlLineState), void *context)
{
UNUSED(instance);
// Register upper driver control line state callback routine with USB driver
CDC_SetCtrlLineStateCb((void (*)(void *context, uint16_t ctrlLineState))cb, context);
}
static void usbVcpSetBaudRateCb(serialPort_t *instance, void (*cb)(serialPort_t *context, uint32_t baud), serialPort_t *context)
{
UNUSED(instance);
// Register upper driver baud rate callback routine with USB driver
CDC_SetBaudRateCb((void (*)(void *context, uint32_t baud))cb, (void *)context);
}
static bool isUsbVcpTransmitBufferEmpty(const serialPort_t *instance)
{
UNUSED(instance);
@ -178,6 +194,8 @@ static const struct serialPortVTable usbVTable[] = {
.serialSetBaudRate = usbVcpSetBaudRate,
.isSerialTransmitBufferEmpty = isUsbVcpTransmitBufferEmpty,
.setMode = usbVcpSetMode,
.setCtrlLineStateCb = usbVcpSetCtrlLineStateCb,
.setBaudRateCb = usbVcpSetBaudRateCb,
.writeBuf = usbVcpWriteBuf,
.beginWrite = usbVcpBeginWrite,
.endWrite = usbVcpEndWrite

View File

@ -917,6 +917,15 @@ static void cliSerial(char *cmdline)
}
#ifndef SKIP_SERIAL_PASSTHROUGH
#ifdef USE_PINIO
static void cbCtrlLine(void *context, uint16_t ctrl)
{
int pinioDtr = (int)(long)context;
pinioSet(pinioDtr, !(ctrl & CTRL_LINE_STATE_DTR));
}
#endif /* USE_PINIO */
static void cliSerialPassthrough(char *cmdline)
{
if (isEmpty(cmdline)) {
@ -926,6 +935,10 @@ static void cliSerialPassthrough(char *cmdline)
int id = -1;
uint32_t baud = 0;
bool enableBaudCb = false;
#ifdef USE_PINIO
int pinioDtr = 0;
#endif /* USE_PINIO */
unsigned mode = 0;
char *saveptr;
char* tok = strtok_r(cmdline, " ", &saveptr);
@ -945,21 +958,32 @@ static void cliSerialPassthrough(char *cmdline)
if (strstr(tok, "tx") || strstr(tok, "TX"))
mode |= MODE_TX;
break;
#ifdef USE_PINIO
case 3:
pinioDtr = atoi(tok);
break;
#endif /* USE_PINIO */
}
index++;
tok = strtok_r(NULL, " ", &saveptr);
}
if (baud == 0) {
enableBaudCb = true;
}
cliPrintf("Port %d ", id);
serialPort_t *passThroughPort;
serialPortUsage_t *passThroughPortUsage = findSerialPortUsageByIdentifier(id);
if (!passThroughPortUsage || passThroughPortUsage->serialPort == NULL) {
if (!baud) {
cliPrintLine("closed, specify baud.");
return;
if (enableBaudCb) {
// Set default baud
baud = 57600;
}
if (!mode)
if (!mode) {
mode = MODE_RXTX;
}
passThroughPort = openSerialPort(id, FUNCTION_NONE, NULL, NULL,
baud, mode,
@ -968,17 +992,30 @@ static void cliSerialPassthrough(char *cmdline)
cliPrintLine("could not be opened.");
return;
}
if (enableBaudCb) {
cliPrintf("opened, default baud = %d.\r\n", baud);
} else {
cliPrintf("opened, baud = %d.\r\n", baud);
}
} else {
passThroughPort = passThroughPortUsage->serialPort;
// If the user supplied a mode, override the port's mode, otherwise
// leave the mode unchanged. serialPassthrough() handles one-way ports.
cliPrintLine("already open.");
// Set the baud rate if specified
if (baud) {
cliPrintf("already open, setting baud = %d.\n\r", baud);
serialSetBaudRate(passThroughPort, baud);
} else {
cliPrintf("already open, baud = %d.\n\r", passThroughPort->baudRate);
}
if (mode && passThroughPort->mode != mode) {
cliPrintf("mode changed from %d to %d.\r\n",
cliPrintf("Mode changed from %d to %d.\r\n",
passThroughPort->mode, mode);
serialSetMode(passThroughPort, mode);
}
// If this port has a rx callback associated we need to remove it now.
// Otherwise no data will be pushed in the serial port buffer!
if (passThroughPort->rxCallback) {
@ -986,8 +1023,23 @@ static void cliSerialPassthrough(char *cmdline)
}
}
// If no baud rate is specified allow to be set via USB
if (enableBaudCb) {
cliPrintLine("Baud rate change over USB enabled.");
// Register the right side baud rate setting routine with the left side which allows setting of the UART
// baud rate over USB without setting it using the serialpassthrough command
serialSetBaudRateCb(cliPort, serialSetBaudRate, passThroughPort);
}
cliPrintLine("Forwarding, power cycle to exit.");
#ifdef USE_PINIO
// Register control line state callback
if (pinioDtr) {
serialSetCtrlLineStateCb(cliPort, cbCtrlLine, (void *)(intptr_t)(pinioDtr - 1));
}
#endif /* USE_PINIO */
serialPassthrough(cliPort, passThroughPort, NULL, NULL);
}
#endif
@ -3753,7 +3805,7 @@ const clicmd_t cmdTable[] = {
#endif
CLI_COMMAND_DEF("serial", "configure serial ports", NULL, cliSerial),
#ifndef SKIP_SERIAL_PASSTHROUGH
CLI_COMMAND_DEF("serialpassthrough", "passthrough serial data to port", "<id> [baud] [mode] : passthrough to serial", cliSerialPassthrough),
CLI_COMMAND_DEF("serialpassthrough", "passthrough serial data to port", "<id> [baud] [mode] [DTR PINIO]: passthrough to serial", cliSerialPassthrough),
#endif
#ifdef USE_SERVOS
CLI_COMMAND_DEF("servo", "configure servos", NULL, cliServo),

View File

@ -58,6 +58,8 @@
#include "telemetry/telemetry.h"
#endif
#include "pg/pinio.h"
static serialPortUsage_t serialPortUsageList[SERIAL_PORT_COUNT];
const serialPortIdentifier_e serialPortIdentifiers[SERIAL_PORT_COUNT] = {
@ -429,7 +431,6 @@ void closeSerialPort(serialPort_t *serialPort)
}
// TODO wait until data has been transmitted.
serialPort->rxCallback = NULL;
serialPortUsage->function = FUNCTION_NONE;
@ -540,6 +541,8 @@ void serialPassthrough(serialPort_t *left, serialPort_t *right, serialConsumer *
if (serialRxBytesWaiting(left)) {
LED0_ON;
uint8_t c = serialRead(left);
// Make sure there is space in the tx buffer
while (!serialTxBytesFree(right));
serialWrite(right, c);
leftC(c);
LED0_OFF;
@ -547,6 +550,8 @@ void serialPassthrough(serialPort_t *left, serialPort_t *right, serialConsumer *
if (serialRxBytesWaiting(right)) {
LED0_ON;
uint8_t c = serialRead(right);
// Make sure there is space in the tx buffer
while (!serialTxBytesFree(left));
serialWrite(left, c);
rightC(c);
LED0_OFF;

View File

@ -217,6 +217,7 @@
#define USE_UART6
#define UART6_RX_PIN PC7
#define UART6_TX_PIN PC6
#define PINIO1_PIN PC8 // DTR pin
#define USE_SOFTSERIAL1
#define USE_SOFTSERIAL2

View File

@ -56,6 +56,7 @@
#define USE_UART1 // Flexi Port
#define UART1_RX_PIN PB7
#define UART1_TX_PIN PB6
#define PINIO1_PIN PB10 // DTR pin
#define USE_UART2 // Main Port
#define UART2_RX_PIN PA3

View File

@ -55,6 +55,11 @@ extern __IO uint32_t receiveLength; // HJI
uint8_t receiveBuffer[64]; // HJI
uint32_t sendLength; // HJI
static void IntToUnicode(uint32_t value, uint8_t *pbuf, uint8_t len);
static void (*ctrlLineStateCb)(void *context, uint16_t ctrlLineState);
static void *ctrlLineStateCbContext;
static void (*baudRateCb)(void *context, uint32_t baud);
static void *baudRateCbContext;
/* Extern variables ----------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
@ -112,6 +117,10 @@ void Set_System(void)
GPIO_Init(GPIOA, &GPIO_InitStructure);
#endif
// Initialise callbacks
ctrlLineStateCb = NULL;
baudRateCb = NULL;
/* Configure the EXTI line 18 connected internally to the USB IP */
EXTI_ClearITPendingBit(EXTI_Line18);
EXTI_InitStructure.EXTI_Line = EXTI_Line18;
@ -388,4 +397,30 @@ uint32_t CDC_BaudRate(void)
return Virtual_Com_Port_GetBaudRate();
}
/*******************************************************************************
* Function Name : CDC_SetBaudRateCb
* Description : Set a callback to call when baud rate changes
* Input : callback function and context.
* Output : None.
* Return : None.
*******************************************************************************/
void CDC_SetBaudRateCb(void (*cb)(void *context, uint32_t baud), void *context)
{
baudRateCbContext = context;
baudRateCb = cb;
}
/*******************************************************************************
* Function Name : CDC_SetCtrlLineStateCb
* Description : Set a callback to call when control line state changes
* Input : callback function and context.
* Output : None.
* Return : None.
*******************************************************************************/
void CDC_SetCtrlLineStateCb(void (*cb)(void *context, uint16_t ctrlLineState), void *context)
{
ctrlLineStateCbContext = context;
ctrlLineStateCb = cb;
}
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -66,6 +66,8 @@ uint32_t CDC_Receive_BytesAvailable(void);
uint8_t usbIsConfigured(void); // HJI
uint8_t usbIsConnected(void); // HJI
uint32_t CDC_BaudRate(void);
void CDC_SetCtrlLineStateCb(void (*cb)(void *context, uint16_t ctrlLineState), void *context);
void CDC_SetBaudRateCb(void (*cb)(void *context, uint32_t baud), void *context);
/* External variables --------------------------------------------------------*/
extern __IO uint32_t packetSent; // HJI

View File

@ -31,7 +31,7 @@
/* Includes ------------------------------------------------------------------*/
/* Exported types ------------------------------------------------------------*/
typedef struct {
typedef struct __attribute__ ((packed)) {
uint32_t bitrate;
uint8_t format;
uint8_t paritytype;

View File

@ -85,6 +85,11 @@ TIM_HandleTypeDef TimHandle;
/* USB handler declaration */
extern USBD_HandleTypeDef USBD_Device;
static void (*ctrlLineStateCb)(void *context, uint16_t ctrlLineState);
static void *ctrlLineStateCbContext;
static void (*baudRateCb)(void *context, uint32_t baud);
static void *baudRateCbContext;
/* Private function prototypes -----------------------------------------------*/
static int8_t CDC_Itf_Init(void);
static int8_t CDC_Itf_DeInit(void);
@ -133,6 +138,9 @@ static int8_t CDC_Itf_Init(void)
USBD_CDC_SetTxBuffer(&USBD_Device, UserTxBuffer, 0);
USBD_CDC_SetRxBuffer(&USBD_Device, UserRxBuffer);
ctrlLineStateCb = NULL;
baudRateCb = NULL;
return (USBD_OK);
}
@ -158,7 +166,8 @@ static int8_t CDC_Itf_DeInit(void)
*/
static int8_t CDC_Itf_Control (uint8_t cmd, uint8_t* pbuf, uint16_t length)
{
UNUSED(length);
LINE_CODING* plc = (LINE_CODING*)pbuf;
switch (cmd)
{
case CDC_SEND_ENCAPSULATED_COMMAND:
@ -182,26 +191,36 @@ static int8_t CDC_Itf_Control (uint8_t cmd, uint8_t* pbuf, uint16_t length)
break;
case CDC_SET_LINE_CODING:
LineCoding.bitrate = (uint32_t)(pbuf[0] | (pbuf[1] << 8) |\
(pbuf[2] << 16) | (pbuf[3] << 24));
LineCoding.format = pbuf[4];
LineCoding.paritytype = pbuf[5];
LineCoding.datatype = pbuf[6];
if (pbuf && (length == sizeof (LINE_CODING))) {
LineCoding.bitrate = plc->bitrate;
LineCoding.format = plc->format;
LineCoding.paritytype = plc->paritytype;
LineCoding.datatype = plc->datatype;
// If a callback is provided, tell the upper driver of changes in baud rate
if (baudRateCb) {
baudRateCb(baudRateCbContext, LineCoding.bitrate);
}
}
break;
case CDC_GET_LINE_CODING:
pbuf[0] = (uint8_t)(LineCoding.bitrate);
pbuf[1] = (uint8_t)(LineCoding.bitrate >> 8);
pbuf[2] = (uint8_t)(LineCoding.bitrate >> 16);
pbuf[3] = (uint8_t)(LineCoding.bitrate >> 24);
pbuf[4] = LineCoding.format;
pbuf[5] = LineCoding.paritytype;
pbuf[6] = LineCoding.datatype;
if (pbuf && (length == sizeof (LineCoding))) {
plc->bitrate = LineCoding.bitrate;
plc->format = LineCoding.format;
plc->paritytype = LineCoding.paritytype;
plc->datatype = LineCoding.datatype;
}
break;
case CDC_SET_CONTROL_LINE_STATE:
/* Add your code here */
// If a callback is provided, tell the upper driver of changes in DTR/RTS state
if (pbuf && (length == sizeof (uint16_t))) {
if (ctrlLineStateCb) {
ctrlLineStateCb(ctrlLineStateCbContext, *((uint16_t *)pbuf));
}
}
break;
case CDC_SEND_BREAK:
@ -410,4 +429,31 @@ uint32_t CDC_BaudRate(void)
{
return LineCoding.bitrate;
}
/*******************************************************************************
* Function Name : CDC_SetBaudRateCb
* Description : Set a callback to call when baud rate changes
* Input : callback function and context.
* Output : None.
* Return : None.
*******************************************************************************/
void CDC_SetBaudRateCb(void (*cb)(void *context, uint32_t baud), void *context)
{
baudRateCbContext = context;
baudRateCb = cb;
}
/*******************************************************************************
* Function Name : CDC_SetCtrlLineStateCb
* Description : Set a callback to call when control line state changes
* Input : callback function and context.
* Output : None.
* Return : None.
*******************************************************************************/
void CDC_SetCtrlLineStateCb(void (*cb)(void *context, uint16_t ctrlLineState), void *context)
{
ctrlLineStateCbContext = context;
ctrlLineStateCb = cb;
}
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -65,6 +65,18 @@
The period depends on CDC_POLLING_INTERVAL */
#define CDC_POLLING_INTERVAL 10 /* in ms. The max is 65 and the min is 1 */
/* Exported typef ------------------------------------------------------------*/
/* The following structures groups all needed parameters to be configured for the
ComPort. These parameters can modified on the fly by the host through CDC class
command class requests. */
typedef struct __attribute__ ((packed))
{
uint32_t bitrate;
uint8_t format;
uint8_t paritytype;
uint8_t datatype;
} LINE_CODING;
extern USBD_CDC_ItfTypeDef USBD_CDC_fops;
uint32_t CDC_Send_DATA(const uint8_t *ptrBuffer, uint32_t sendLength);
@ -74,6 +86,8 @@ uint32_t CDC_Receive_BytesAvailable(void);
uint8_t usbIsConfigured(void);
uint8_t usbIsConnected(void);
uint32_t CDC_BaudRate(void);
void CDC_SetCtrlLineStateCb(void (*cb)(void *context, uint16_t ctrlLineState), void *context);
void CDC_SetBaudRateCb(void (*cb)(void *context, uint32_t baud), void *context);
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */

View File

@ -58,6 +58,11 @@ static uint16_t VCP_DeInit(void);
static uint16_t VCP_Ctrl(uint32_t Cmd, uint8_t* Buf, uint32_t Len);
static uint16_t VCP_DataTx(const uint8_t* Buf, uint32_t Len);
static uint16_t VCP_DataRx(uint8_t* Buf, uint32_t Len);
static void (*ctrlLineStateCb)(void* context, uint16_t ctrlLineState);
static void *ctrlLineStateCbContext;
static void (*baudRateCb)(void *context, uint32_t baud);
static void *baudRateCbContext;
CDC_IF_Prop_TypeDef VCP_fops = {VCP_Init, VCP_DeInit, VCP_Ctrl, VCP_DataTx, VCP_DataRx };
@ -71,6 +76,8 @@ CDC_IF_Prop_TypeDef VCP_fops = {VCP_Init, VCP_DeInit, VCP_Ctrl, VCP_DataTx, VCP_
static uint16_t VCP_Init(void)
{
bDeviceState = CONFIGURED;
ctrlLineStateCb = NULL;
baudRateCb = NULL;
return USBD_OK;
}
@ -104,7 +111,6 @@ void ust_cpy(LINE_CODING* plc2, const LINE_CODING* plc1)
*/
static uint16_t VCP_Ctrl(uint32_t Cmd, uint8_t* Buf, uint32_t Len)
{
(void)Len;
LINE_CODING* plc = (LINE_CODING*)Buf;
assert_param(Len>=sizeof(LINE_CODING));
@ -124,6 +130,12 @@ static uint16_t VCP_Ctrl(uint32_t Cmd, uint8_t* Buf, uint32_t Len)
//Note - hw flow control on UART 1-3 and 6 only
case SET_LINE_CODING:
// If a callback is provided, tell the upper driver of changes in baud rate
if (plc && (Len == sizeof (*plc))) {
if (baudRateCb) {
baudRateCb(baudRateCbContext, plc->bitrate);
}
}
ust_cpy(&g_lc, plc); //Copy into structure to save for later
break;
@ -134,8 +146,12 @@ static uint16_t VCP_Ctrl(uint32_t Cmd, uint8_t* Buf, uint32_t Len)
case SET_CONTROL_LINE_STATE:
/* Not needed for this driver */
//RSW - This tells how to set RTS and DTR
// If a callback is provided, tell the upper driver of changes in DTR/RTS state
if (plc && (Len == sizeof (uint16_t))) {
if (ctrlLineStateCb) {
ctrlLineStateCb(ctrlLineStateCbContext, *((uint16_t *)Buf));
}
}
break;
case SEND_BREAK:
@ -292,4 +308,30 @@ uint32_t CDC_BaudRate(void)
return g_lc.bitrate;
}
/*******************************************************************************
* Function Name : CDC_SetBaudRateCb
* Description : Set a callback to call when baud rate changes
* Input : callback function and context.
* Output : None.
* Return : None.
*******************************************************************************/
void CDC_SetBaudRateCb(void (*cb)(void *context, uint32_t baud), void *context)
{
baudRateCbContext = context;
baudRateCb = cb;
}
/*******************************************************************************
* Function Name : CDC_SetCtrlLineStateCb
* Description : Set a callback to call when control line state changes
* Input : callback function and context.
* Output : None.
* Return : None.
*******************************************************************************/
void CDC_SetCtrlLineStateCb(void (*cb)(void *context, uint16_t ctrlLineState), void *context)
{
ctrlLineStateCbContext = context;
ctrlLineStateCb = cb;
}
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -44,6 +44,8 @@ uint32_t CDC_Receive_BytesAvailable(void);
uint8_t usbIsConfigured(void); // HJI
uint8_t usbIsConnected(void); // HJI
uint32_t CDC_BaudRate(void);
void CDC_SetCtrlLineStateCb(void (*cb)(void *context, uint16_t ctrlLineState), void *context);
void CDC_SetBaudRateCb(void (*cb)(void *context, uint32_t baud), void *context);
/* External variables --------------------------------------------------------*/
extern __IO uint32_t bDeviceState; /* USB device status */
@ -61,7 +63,7 @@ typedef enum _DEVICE_STATE {
/* The following structures groups all needed parameters to be configured for the
ComPort. These parameters can modified on the fly by the host through CDC class
command class requests. */
typedef struct
typedef struct __attribute__ ((packed))
{
uint32_t bitrate;
uint8_t format;

View File

@ -265,5 +265,10 @@ void generateLedConfig(ledConfig_t *, char *, size_t) {}
bool isSerialTransmitBufferEmpty(const serialPort_t *) {return true; }
void serialWrite(serialPort_t *, uint8_t ch) { printf("%c", ch);}
void serialSetCtrlLineStateCb(serialPort_t *, void (*)(void *, uint16_t ), void *) {}
void serialSetCtrlLineStateDtrPin(serialPort_t *, ioTag_t ) {}
void serialSetCtrlLineState(serialPort_t *, uint16_t ) {}
void serialSetBaudRateCb(serialPort_t *, void (*)(serialPort_t *context, uint32_t baud), serialPort_t *) {}
}

View File

@ -71,4 +71,12 @@ extern "C" {
serialPort_t *openSoftSerial(softSerialPortIndex_e, serialReceiveCallbackPtr, void *, uint32_t, portMode_e, portOptions_e) {
return NULL;
}
void serialSetCtrlLineStateCb(serialPort_t *, void (*)(void *, uint16_t ), void *) {}
void serialSetCtrlLineState(serialPort_t *, uint16_t ) {}
uint32_t serialTxBytesFree(const serialPort_t *) {return 1;}
void serialSetBaudRateCb(serialPort_t *, void (*)(serialPort_t *context, uint32_t baud), serialPort_t *) {}
void pinioSet(int, bool) {}
}