Rework F7 vcp

fix badly configured poll timer
unify to serial_usb_vcp.c
This commit is contained in:
Sami Korhonen 2016-12-24 13:17:36 +02:00
parent c1ed72644f
commit 86f08ee9b3
7 changed files with 99 additions and 258 deletions

View File

@ -718,7 +718,7 @@ VCP_SRC = \
vcp_hal/usbd_desc.c \
vcp_hal/usbd_conf.c \
vcp_hal/usbd_cdc_interface.c \
drivers/serial_usb_vcp_hal.c
drivers/serial_usb_vcp.c
else
VCP_SRC = \
vcp/hw_config.c \

View File

@ -25,10 +25,14 @@
#include "common/utils.h"
#include "io.h"
#if defined(STM32F4)
#include "usb_core.h"
#ifdef STM32F4
#include "usbd_cdc_vcp.h"
#elif defined(STM32F7)
#include "vcp_hal/usbd_cdc_interface.h"
USBD_HandleTypeDef USBD_Device;
#else
#include "usb_core.h"
#include "usb_init.h"
#include "hw_config.h"
#endif
@ -94,9 +98,8 @@ static void usbVcpWriteBuf(serialPort_t *instance, const void *data, int count)
uint32_t start = millis();
const uint8_t *p = data;
uint32_t txed = 0;
while (count > 0) {
txed = CDC_Send_DATA(p, count);
uint32_t txed = CDC_Send_DATA(p, count);
count -= txed;
p += txed;
@ -121,9 +124,8 @@ static bool usbVcpFlush(vcpPort_t *port)
uint32_t start = millis();
uint8_t *p = port->txBuf;
uint32_t txed = 0;
while (count > 0) {
txed = CDC_Send_DATA(p, count);
uint32_t txed = CDC_Send_DATA(p, count);
count -= txed;
p += txed;
@ -181,10 +183,22 @@ serialPort_t *usbVcpOpen(void)
{
vcpPort_t *s;
#ifdef STM32F4
#if defined(STM32F4)
IOInit(IOGetByTag(IO_TAG(PA11)), OWNER_USB, 0);
IOInit(IOGetByTag(IO_TAG(PA12)), OWNER_USB, 0);
USBD_Init(&USB_OTG_dev, USB_OTG_FS_CORE_ID, &USR_desc, &USBD_CDC_cb, &USR_cb);
#elif defined(STM32F7)
/* Init Device Library */
USBD_Init(&USBD_Device, &VCP_Desc, 0);
/* Add Supported Class */
USBD_RegisterClass(&USBD_Device, USBD_CDC_CLASS);
/* Add CDC Interface Class */
USBD_CDC_RegisterInterface(&USBD_Device, &USBD_CDC_fops);
/* Start Device Process */
USBD_Start(&USBD_Device);
#else
Set_System();
Set_USBClock();

View File

@ -1,193 +0,0 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include <stdbool.h>
#include "platform.h"
#include "build/build_config.h"
#include "common/utils.h"
#include "io.h"
#include "vcp_hal/usbd_cdc_interface.h"
#include "system.h"
#include "serial.h"
#include "serial_usb_vcp.h"
#define USB_TIMEOUT 50
static vcpPort_t vcpPort;
USBD_HandleTypeDef USBD_Device;
static void usbVcpSetBaudRate(serialPort_t *instance, uint32_t baudRate)
{
UNUSED(instance);
UNUSED(baudRate);
// TODO implement
}
static void usbVcpSetMode(serialPort_t *instance, portMode_t mode)
{
UNUSED(instance);
UNUSED(mode);
// TODO implement
}
static bool isUsbVcpTransmitBufferEmpty(const serialPort_t *instance)
{
UNUSED(instance);
return true;
}
static uint32_t usbVcpAvailable(const serialPort_t *instance)
{
UNUSED(instance);
uint32_t receiveLength = vcpAvailable();
return receiveLength;
}
static uint8_t usbVcpRead(serialPort_t *instance)
{
UNUSED(instance);
return vcpRead();
}
static void usbVcpWriteBuf(serialPort_t *instance, const void *data, int count)
{
UNUSED(instance);
if (!vcpIsConnected()) {
return;
}
uint32_t start = millis();
const uint8_t *p = data;
while (count > 0) {
uint32_t txed = vcpWrite(p, count);
count -= txed;
p += txed;
if (millis() - start > USB_TIMEOUT) {
break;
}
}
}
static bool usbVcpFlush(vcpPort_t *port)
{
uint8_t count = port->txAt;
port->txAt = 0;
if (count == 0) {
return true;
}
if (!vcpIsConnected()) {
return false;
}
uint32_t start = millis();
uint8_t *p = port->txBuf;
while (count > 0) {
uint32_t txed = vcpWrite(p, count);
count -= txed;
p += txed;
if (millis() - start > USB_TIMEOUT) {
break;
}
}
return count == 0;
}
static void usbVcpWrite(serialPort_t *instance, uint8_t c)
{
vcpPort_t *port = container_of(instance, vcpPort_t, port);
port->txBuf[port->txAt++] = c;
if (!port->buffering || port->txAt >= ARRAYLEN(port->txBuf)) {
usbVcpFlush(port);
}
}
static void usbVcpBeginWrite(serialPort_t *instance)
{
vcpPort_t *port = container_of(instance, vcpPort_t, port);
port->buffering = true;
}
uint32_t usbTxBytesFree()
{
return CDC_Send_FreeBytes();
}
static void usbVcpEndWrite(serialPort_t *instance)
{
vcpPort_t *port = container_of(instance, vcpPort_t, port);
port->buffering = false;
usbVcpFlush(port);
}
static const struct serialPortVTable usbVTable[] = {
{
.serialWrite = usbVcpWrite,
.serialTotalRxWaiting = usbVcpAvailable,
.serialTotalTxFree = usbTxBytesFree,
.serialRead = usbVcpRead,
.serialSetBaudRate = usbVcpSetBaudRate,
.isSerialTransmitBufferEmpty = isUsbVcpTransmitBufferEmpty,
.setMode = usbVcpSetMode,
.writeBuf = usbVcpWriteBuf,
.beginWrite = usbVcpBeginWrite,
.endWrite = usbVcpEndWrite
}
};
serialPort_t *usbVcpOpen(void)
{
vcpPort_t *s;
/* Init Device Library */
USBD_Init(&USBD_Device, &VCP_Desc, 0);
/* Add Supported Class */
USBD_RegisterClass(&USBD_Device, USBD_CDC_CLASS);
/* Add CDC Interface Class */
USBD_CDC_RegisterInterface(&USBD_Device, &USBD_CDC_fops);
/* Start Device Process */
USBD_Start(&USBD_Device);
s = &vcpPort;
s->port.vTable = usbVTable;
return (serialPort_t *)s;
}
uint32_t usbVcpGetBaudRate(serialPort_t *instance)
{
UNUSED(instance);
return vcpBaudrate();
}

View File

@ -51,6 +51,9 @@
#include "usbd_desc.h"
#include "usbd_cdc.h"
#include "usbd_cdc_interface.h"
#include "stdbool.h"
#include "drivers/system.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
#define APP_RX_DATA_SIZE 2048
@ -242,7 +245,7 @@ void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim)
if(USBD_CDC_TransmitPacket(&USBD_Device) == USBD_OK)
{
UserTxBufPtrOut += buffsize;
if (UserTxBufPtrOut == APP_RX_DATA_SIZE)
if (UserTxBufPtrOut == APP_TX_DATA_SIZE)
{
UserTxBufPtrOut = 0;
}
@ -282,7 +285,7 @@ static void TIM_Config(void)
+ Counter direction = Up
*/
TimHandle.Init.Period = (CDC_POLLING_INTERVAL*1000) - 1;
TimHandle.Init.Prescaler = 84-1;
TimHandle.Init.Prescaler = (SystemCoreClock / 2 / (1000000)) - 1;
TimHandle.Init.ClockDivision = 0;
TimHandle.Init.CounterMode = TIM_COUNTERMODE_UP;
if(HAL_TIM_Base_Init(&TimHandle) != HAL_OK)
@ -312,26 +315,25 @@ static void Error_Handler(void)
/* Add your own code here */
}
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
uint8_t vcpRead()
uint32_t CDC_Receive_DATA(uint8_t* recvBuf, uint32_t len)
{
uint8_t ch = 0;
if( (rxBuffPtr != NULL) && (rxAvailable > 0) )
uint32_t count = 0;
if( (rxBuffPtr != NULL))
{
ch = rxBuffPtr[0];
while ((rxAvailable > 0) && count < len)
{
recvBuf[count] = rxBuffPtr[0];
rxBuffPtr++;
rxAvailable--;
}
count++;
if(rxAvailable < 1)
USBD_CDC_ReceivePacket(&USBD_Device);
return ch;
}
}
return count;
}
uint8_t vcpAvailable()
uint32_t CDC_Receive_BytesAvailable(void)
{
return rxAvailable;
}
@ -345,49 +347,67 @@ uint32_t CDC_Send_FreeBytes(void)
(APP_Rx_ptr_out > APP_Rx_ptr_in ? APP_Rx_ptr_out - APP_Rx_ptr_in : APP_RX_DATA_SIZE - APP_Rx_ptr_in + APP_Rx_ptr_in)
but without the impact of the condition check.
*/
return ((UserTxBufPtrOut - UserTxBufPtrIn) + (-((int)(UserTxBufPtrOut <= UserTxBufPtrIn)) & APP_RX_DATA_SIZE)) - 1;
return ((UserTxBufPtrOut - UserTxBufPtrIn) + (-((int)(UserTxBufPtrOut <= UserTxBufPtrIn)) & APP_TX_DATA_SIZE)) - 1;
}
/**
* @brief vcpWrite
* @brief CDC_Send_DATA
* CDC received data to be send over USB IN endpoint are managed in
* this function.
* @param Buf: Buffer of data to be sent
* @param Len: Number of data to be sent (in bytes)
* @retval Result of the opeartion: USBD_OK if all operations are OK else VCP_FAIL
* @retval Bytes sent
*/
uint32_t vcpWrite(const uint8_t* Buf, uint32_t Len)
uint32_t CDC_Send_DATA(const uint8_t* Buf, uint32_t Len)
{
uint32_t ptr_head = UserTxBufPtrIn;
uint32_t ptr_tail = UserTxBufPtrOut;
uint32_t i = 0;
USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*)USBD_Device.pClassData;
while(hcdc->TxState != 0);
for (i = 0; i < Len; i++)
for (uint32_t i = 0; i < Len; i++)
{
// head reached tail
if(ptr_head == (ptr_tail-1))
{
break;
}
UserTxBuffer[ptr_head++] = Buf[i];
if(ptr_head == (APP_RX_DATA_SIZE))
{
ptr_head = 0;
UserTxBuffer[UserTxBufPtrIn] = Buf[i];
UserTxBufPtrIn = (UserTxBufPtrIn + 1) % APP_TX_DATA_SIZE;
while (CDC_Send_FreeBytes() == 0) {
delay(1);
}
}
UserTxBufPtrIn = ptr_head;
return i;
return Len;
}
uint32_t vcpBaudrate()
/*******************************************************************************
* Function Name : usbIsConfigured.
* Description : Determines if USB VCP is configured or not
* Input : None.
* Output : None.
* Return : True if configured.
*******************************************************************************/
uint8_t usbIsConfigured(void)
{
return (USBD_Device.dev_state == USBD_STATE_CONFIGURED);
}
/*******************************************************************************
* Function Name : usbIsConnected.
* Description : Determines if USB VCP is connected ot not
* Input : None.
* Output : None.
* Return : True if connected.
*******************************************************************************/
uint8_t usbIsConnected(void)
{
return (USBD_Device.dev_state != USBD_STATE_DEFAULT);
}
/*******************************************************************************
* Function Name : CDC_BaudRate.
* Description : Get the current baud rate
* Input : None.
* Output : None.
* Return : Baud rate in bps
*******************************************************************************/
uint32_t CDC_BaudRate(void)
{
return LineCoding.bitrate;
}
uint8_t vcpIsConnected()
{
return ((USBD_Device.dev_state == USBD_STATE_CONFIGURED)
|| (USBD_Device.dev_state == USBD_STATE_SUSPENDED));
}
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -63,16 +63,17 @@
/* Periodically, the state of the buffer "UserTxBuffer" is checked.
The period depends on CDC_POLLING_INTERVAL */
#define CDC_POLLING_INTERVAL 1 /* in ms. The max is 65 and the min is 1 */
#define CDC_POLLING_INTERVAL 10 /* in ms. The max is 65 and the min is 1 */
extern USBD_CDC_ItfTypeDef USBD_CDC_fops;
uint8_t vcpRead();
uint8_t vcpAvailable();
uint32_t vcpWrite(const uint8_t* Buf, uint32_t Len);
uint32_t vcpBaudrate();
uint8_t vcpIsConnected();
uint32_t CDC_Send_DATA(const uint8_t *ptrBuffer, uint32_t sendLength);
uint32_t CDC_Send_FreeBytes(void);
uint32_t CDC_Receive_DATA(uint8_t* recvBuf, uint32_t len);
uint32_t CDC_Receive_BytesAvailable(void);
uint8_t usbIsConfigured(void);
uint8_t usbIsConnected(void);
uint32_t CDC_BaudRate(void);
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */

View File

@ -49,13 +49,15 @@
#include "usbd_core.h"
#include "usbd_desc.h"
#include "usbd_conf.h"
#include "platform.h"
#include "build/version.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
#define USBD_VID 0x0483
#define USBD_PID 0x5740
#define USBD_LANGID_STRING 0x409
#define USBD_MANUFACTURER_STRING "STMicroelectronics"
#define USBD_MANUFACTURER_STRING FC_FIRMWARE_NAME
#define USBD_PRODUCT_HS_STRING "STM32 Virtual ComPort in HS Mode"
#define USBD_PRODUCT_FS_STRING "STM32 Virtual ComPort in FS Mode"
#define USBD_CONFIGURATION_HS_STRING "VCP Config"
@ -260,9 +262,9 @@ static void Get_SerialNum(void)
{
uint32_t deviceserial0, deviceserial1, deviceserial2;
deviceserial0 = *(uint32_t*)DEVICE_ID1;
deviceserial1 = *(uint32_t*)DEVICE_ID2;
deviceserial2 = *(uint32_t*)DEVICE_ID3;
deviceserial0 = U_ID_0;
deviceserial1 = U_ID_1;
deviceserial2 = U_ID_2;
deviceserial0 += deviceserial2;

View File

@ -54,9 +54,6 @@
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
#define DEVICE_ID1 (0x1FFF7A10)
#define DEVICE_ID2 (0x1FFF7A14)
#define DEVICE_ID3 (0x1FFF7A18)
#define USB_SIZ_STRING_SERIAL 0x1A
/* Exported macro ------------------------------------------------------------*/