Mittwoch, 4. Januar 2017

STM32 microcontroller #5: USB CDC device

Introduction

The STM32F103 devices offer USB 2.0 support. I will show some firmware (based on an example from SMT32Cube package) that implements a USB CDC (Communication Device Class) device which will send ADC data from the MCU to a host PC. The code uses the STM hardware abstraction layer (HAL) and STM's USB library that is written on top of the HAL library.

References for this project are:
  • STM32Cube USB device library User Manual. (search for UM1734 on the ST-Microelectronics webpage)
  • source code of the CDC_Standalone device example of the STM32Cube package: STM32Cube_FW_F1_V1.3.0/Projects/STM3210C_EVAL/Applications/USB_Device/CDC_Standalone
I stripped the example down to the bare USB functionality and send an added simple ADC measurement (see previous STM32 project). The measured value (a number from 0 to 4095) is converted to ascii text and sent to the host computer. The device is recognized as serial terminal by the host computer.

The firmware

The main application will be written inside main.c. In addition to the files needed for the previous examples, a few more files are needed to get USB running. 

Some of these files need to be modified (e.g. to adjust USB device parameters).
These need to be copied into the project directory. From the directory with an USB example application (a USB-Serial bridge) STM32Cube_FW_F1_V1.3.0/Projects/STM3210C_EVAL/Applications/USB_Device/CDC_Standalone/Src/ these files are needed:
  • usbd_cdc_interface.c in that file we deal with USB communication
  • usbd_conf.c
  • usbd_desc.c

From the directory STM32Cube_FW_F1_V1.3.0/Projects/STM3210C_EVAL/Applications/USB_Device/CDC_Standalone/Inc/ these files are needed:

  • usbd_cdc_interface.h
  • usbd_conf.h
  • usbd_desc.h

And the last two files which only needs to be copied because of an strange #include "USBD_CDC.h" directive (the actual filename is not in capitals)

  • STM32Cube_FW_F1_V1.3.0/Middlewares/ST/STM32_USB_Device_Library/Class/CDC/Src/usbd_cdc.c
  • STM32Cube_FW_F1_V1.3.0/Middlewares/ST/STM32_USB_Device_Library/Class/CDC/Inc/usbd_cdc.h


Other files are also needed, but without any modification. Thus, these files can be compiled into the project from their place in the STM32 Cube package. They only need to be added to the makefile:
From the directory STM32Cube_FW_F1_V1.3.0/Middlewares/ST/STM32_USB_Device_Library/Core/Src

  • usbd_core.c
  • usbd_ctlreq.c
  • usbd_ioreq.c

and from the direcotry STM32Cube_FW_F1_V1.3.0/Middlewares/ST/STM32_USB_Device_Library/Core/Inc:

  • usbd_core.h
  • usbd_ctlreq.h
  • usbd_ioreq.h

Finally, my src/ directory has the following files:

  • main.c main application code
  • main.h
  • stm32f1xx_hal_conf.h
  • usbd_cdc.c
  • usbd_cdc.h
  • usbd_cdc_interface.c USB communication functionality
  • usbd_cdc_interface.h
  • usbd_conf.c Low level USB library
  • usbd_conf.h
  • usbd_desc.c USB vendor-ID (VID) & product-ID (PID)
  • usbd_desc.h


The makefile from the previous examples is adjusted to handle the additional files. It looks like this



########################################################################
# Makefile for STM32F3 MCU using arm-none-eabi-gcc toolchain
#  for compiling, and openocd with st-link-v2 for uploading.
# 
# For project setup, copy linker script into same directory as this
# makefile and create a src/ subdirectory that contains the application
# code and stm32f1xx_hal_conf.h 
#
# Use this at your own risk.
#
# Note: using this makefile for other families some changes.
########################################################################

# root path of STM32Cube package
STM32CUBE_PATH = ../STM32Cube_FW_F1_V1.3.0

# specify device type by family, type and number: 
#  (all letters in capitals)
#   e.g. for STM32 F1 03 RBT6
#      FAMILY = F1
#      TYPE = 03
#      NUMBER = X6    (X replaces RBT or C8T)

# device family
FAMILY = F1
# device type
TYPE = 03
# device number
NUMBER = X6
# the CPU
CPU = cortex-m3

# external quarz frequency
HSE_VALUE = 16000000UL

# program name
PROGRAM = main

# list of additional program modules (.o files)
OBJS = \
  usbd_cdc_interface.o \
  usbd_conf.o          \
  usbd_desc.o          \
  usbd_cdc.o           \
 
 
########################################################################
# Changes below this line should not be necessary.
########################################################################


# device name
lc = $(subst A,a,$(subst B,b,$(subst C,c,$(subst D,d,$(subst E,e,$(subst F,f,$(subst G,g,$(subst H,h,$(subst I,i,$(subst J,j,$(subst K,k,$(subst L,l,$(subst M,m,$(subst N,n,$(subst O,o,$(subst P,p,$(subst Q,q,$(subst R,r,$(subst S,s,$(subst T,t,$(subst U,u,$(subst V,v,$(subst W,w,$(subst X,x,$(subst Y,y,$(subst Z,z,$1))))))))))))))))))))))))))
Device = STM32$(FAMILY)$(TYPE)$(call lc,$(NUMBER))
DEVICE = STM32$(FAMILY)$(TYPE)$(NUMBER)
device = $(call lc,$(DEVICE))
family = $(call lc,$(FAMILY))

vpath %.c $(STM32CUBE_PATH)/Drivers/STM32$(FAMILY)xx_HAL_Driver/Src/                     \
$(STM32CUBE_PATH)/Drivers/CMSIS/Device/ST/STM32$(FAMILY)xx/Source/Templates/ \ $(STM32CUBE_PATH)/Middlewares/ST/STM32_USB_Device_Library/Core/Src/ \ src # $(STM32CUBE_PATH)/Drivers/BSP/STM3210E_EVAL/ \ vpath %.h $(STM32CUBE_PATH)/Drivers/STM32$(FAMILY)xx_HAL_Driver/Inc/ \ $(STM32CUBE_PATH)/Drivers/CMSIS/Device/ST/STM32$(FAMILY)xx/Include/ \ $(STM32CUBE_PATH)/Drivers/BSP/STM3210E_EVAL/ \ $(STM32CUBE_PATH)/Middlewares/Third_Party/FreeRTOS/Source/include/ \ $(STM32CUBE_PATH)/Middlewares/ST/STM32_USB_Device_Library/Core/Inc/ \ $(STM32CUBE_PATH)/Middlewares/ST/STM32_USB_Device_Library/Class/CDC/Inc/ \ src vpath %.s $(STM32CUBE_PATH)/Drivers/CMSIS/Device/ST/STM32$(FAMILY)xx/Source/Templates/gcc/ vpath %.o obj CFLAGS = -I $(STM32CUBE_PATH)/Drivers/CMSIS/Device/ST/STM32$(FAMILY)xx/Include \ -I $(STM32CUBE_PATH)/Drivers/CMSIS/Include \ -I $(STM32CUBE_PATH)/Drivers/STM32$(FAMILY)xx_HAL_Driver/Inc/ \ -I $(STM32CUBE_PATH)/Drivers/BSP/STM3210E_EVAL/ \ -I $(STM32CUBE_PATH)/Middlewares/ST/STM32_USB_Device_Library/Core/Inc/ \ -I $(STM32CUBE_PATH)/Middlewares/ST/STM32_USB_Device_Library/Class/CDC/Inc/ \ -I src \ -Wall -Os -std=c99 -mcpu=$(CPU) -mlittle-endian -mthumb -D$(Device) -DHSE_VALUE=$(HSE_VALUE) # the stm32 hardware abstraction library STM_HAL_OBJS = $(shell ls $(STM32CUBE_PATH)/Drivers/STM32$(FAMILY)xx_HAL_Driver/Src | sed 's/\.c/\.o/g') STM_USB_OBJS = usbd_core.o usbd_ctlreq.o usbd_ioreq.o # startup and system initialization code STM_BASIC_OBJS = \ system_stm32$(family)xx.o \ startup_$(device).o \ # generic rules %.o: %.c %.h arm-none-eabi-gcc $(CFLAGS) -c $< -o $@ %.o: %.c arm-none-eabi-gcc $(CFLAGS) -c $< -o $@ %.o: %.s arm-none-eabi-gcc $(CFLAGS) -c $< -o $@ # main target all: $(PROGRAM).hex @echo $(STM_HAL_OBJS) @echo $(family) $(PROGRAM).hex: $(PROGRAM).elf arm-none-eabi-objcopy -Oihex $(PROGRAM).elf $(PROGRAM).hex $(PROGRAM).elf: $(PROGRAM).o $(OBJS) $(STM_HAL_OBJS) $(STM_USB_OBJS) $(STM_BASIC_OBJS) $(DEVICE)_FLASH.ld arm-none-eabi-gcc $(CFLAGS) -T $(DEVICE)_FLASH.ld \ -Wl,--gc-sections $(PROGRAM).o $(OBJS) $(STM_HAL_OBJS) $(STM_USB_OBJS) $(STM_BASIC_OBJS) -o $(PROGRAM).elf # make a local copy of the linkcer script that has no '0' characters # (why are there lines starting with '0' ?) LINKER_SCRIPT = $(STM32CUBE_PATH)/Drivers/CMSIS/Device/ST/STM32F1xx/Source/Templates/gcc/linker/$(DEVICE)_FLASH.ld $(DEVICE)_FLASH.ld: $(LINKER_SCRIPT) sed 's/^0/ /g' $(LINKER_SCRIPT) > $(DEVICE)_FLASH.ld flash: $(PROGRAM).hex sudo openocd -f /usr/share/openocd/scripts/interface/stlink-v2.cfg \ -f /usr/share/openocd/scripts/target/stm32$(family)x.cfg \ -c "program $(PROGRAM).hex verify reset exit" clean: rm -f *.o $(PROGRAM).elf *.ld .PHONY: all flash clean

Here is the main.c which does clock configuration, ADC configuration and USB setup. The infinite main loop does nothing but taking one ADC value and store it in the golbal variable adc_value. This global variable is used by the USB device driver code and send as response to any data that comes from the host PC.


/**
  ******************************************************************************
  * @file    based on: USB_Device/CDC_Standalone/Src/main.c 
  ******************************************************************************
  *
  * <h2><center>&copy; Copyright © 2015 STMicroelectronics International N.V. 
  * All rights reserved.</center></h2>
  *
  * Redistribution and use in source and binary forms, with or without 
  * modification, are permitted, provided that the following conditions are met:
  *
  * 1. Redistribution of source code must retain the above copyright notice, 
  *    this list of conditions and the following disclaimer.
  * 2. Redistributions in binary form must reproduce the above copyright notice,
  *    this list of conditions and the following disclaimer in the documentation
  *    and/or other materials provided with the distribution.
  * 3. Neither the name of STMicroelectronics nor the names of other 
  *    contributors to this software may be used to endorse or promote products 
  *    derived from this software without specific written permission.
  * 4. This software, including modifications and/or derivative works of this 
  *    software, must execute solely and exclusively on microcontroller or
  *    microprocessor devices manufactured by or for STMicroelectronics.
  * 5. Redistribution and use of this software other than as permitted under 
  *    this license is void and will automatically terminate your rights under 
  *    this license. 
  *
  * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" 
  * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT 
  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A 
  * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY
  * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT 
  * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
  * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, 
  * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 
  * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 
  * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
  * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
  *
  ******************************************************************************
  */

#include "main.h"
#include "stm32f1xx.h"

USBD_HandleTypeDef USBD_Device;

// A global variable to hold the latest ADC value
uint32_t adc_value = 0; 

void SysTick_Handler(void)
{
  HAL_IncTick();
}

// An additional interrupt routine for incoming USB packets
extern PCD_HandleTypeDef hpcd;
void USB_LP_CAN1_RX0_IRQHandler(void)
{
  HAL_PCD_IRQHandler(&hpcd);
}

void SystemClock_Config(void)
{
  // Configure PLL with HSE_VALUE = 16000000UL = 16 MHz
  // PLL configuration: 
  //   PLLCLK = (HSE / 2) * PLLMUL = (16 / 2) * 9 = 72 MHz 
  RCC_OscInitTypeDef oscinitstruct = 
  {
          .OscillatorType      = RCC_OSCILLATORTYPE_HSE,
          .HSEState            = RCC_HSE_ON,
          .LSEState            = RCC_LSE_OFF,
          .HSIState            = RCC_HSI_OFF,
          .HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT,
          .HSEPredivValue      = RCC_HSE_PREDIV_DIV2,
          .PLL.PLLState        = RCC_PLL_ON,
          .PLL.PLLSource       = RCC_PLLSOURCE_HSE,
          .PLL.PLLMUL          = RCC_PLL_MUL9 
  };
  HAL_RCC_OscConfig(&oscinitstruct);

  // USB clock selection 
  RCC_PeriphCLKInitTypeDef rccperiphclkinit = 
  {
          .PeriphClockSelection = RCC_PERIPHCLK_USB,
          // divide 72 MHz by 1.5 -> 48 MHz for USB
          .UsbClockSelection = RCC_USBCLKSOURCE_PLL_DIV1_5 
  };
  HAL_RCCEx_PeriphCLKConfig(&rccperiphclkinit);
   
  // Select PLL as system clock source and configure 
  // the HCLK, PCLK1 and PCLK2 clocks dividers 
  RCC_ClkInitTypeDef clkinitstruct = 
  {
          .ClockType      =   RCC_CLOCKTYPE_SYSCLK 
                            | RCC_CLOCKTYPE_HCLK 
                            | RCC_CLOCKTYPE_PCLK1 
                            | RCC_CLOCKTYPE_PCLK2,
          .SYSCLKSource   = RCC_SYSCLKSOURCE_PLLCLK,
          .AHBCLKDivider  = RCC_SYSCLK_DIV1,
          .APB2CLKDivider = RCC_HCLK_DIV2,
          .APB1CLKDivider = RCC_HCLK_DIV1
  };
  HAL_RCC_ClockConfig(&clkinitstruct, FLASH_LATENCY_2);
}

void ConfigureADC(ADC_HandleTypeDef *AdcHandle)
{
    GPIO_InitTypeDef gpioInit;
 
    __HAL_RCC_GPIOC_CLK_ENABLE();
    __HAL_RCC_ADC1_CLK_ENABLE();

    gpioInit.Pin = GPIO_PIN_1;
    gpioInit.Mode = GPIO_MODE_ANALOG;
    gpioInit.Pull = GPIO_NOPULL;
    HAL_GPIO_Init(GPIOC, &gpioInit);

    AdcHandle->Instance = ADC1;
 
    AdcHandle->Init.ScanConvMode = DISABLE;
    AdcHandle->Init.ContinuousConvMode = ENABLE;
    AdcHandle->Init.DiscontinuousConvMode = DISABLE;
    AdcHandle->Init.NbrOfDiscConversion = 0;
    AdcHandle->Init.ExternalTrigConv = ADC_EXTERNALTRIGCONV_T1_CC1;
    AdcHandle->Init.DataAlign = ADC_DATAALIGN_RIGHT;
    AdcHandle->Init.NbrOfConversion = 1;
 
    HAL_ADC_Init(AdcHandle);
 
    ADC_ChannelConfTypeDef adcChannel;
    adcChannel.Channel = ADC_CHANNEL_1;
    adcChannel.Rank = 1;
    adcChannel.SamplingTime = ADC_SAMPLETIME_7CYCLES_5;
 
    HAL_ADC_ConfigChannel(AdcHandle, &adcChannel);
}

int main(void)
{
  // Reset of all peripherals, Initializes the Flash interface and the Systick. 
  HAL_Init();
  // Configure the system clock to 72 MHz 
  SystemClock_Config();
  // 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);

  // Configure the ADC peripheral
  ADC_HandleTypeDef    AdcHandle;
  ConfigureADC(&AdcHandle);

  for (;;)
  {
    // ADC measurment, result is globally available in the variable "acd_value"
    HAL_ADC_Start(&AdcHandle);
    HAL_ADC_PollForConversion(&AdcHandle, 1000); // 1000 is timeout in miliseconds
    adc_value = HAL_ADC_GetValue(&AdcHandle);
    HAL_ADC_Stop(&AdcHandle);
  }
}


/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

Clock configuration

The file main.c has to be extended to configure the USB clock. This is done by adding some lines to the SystemClock_Config function. USB runs with 48 MHz, created by a PLL inside the chip. The  PLL has to be set up depending on the sytem clock configuration. I run the system with 72 MHz and need a division by 1.5 to arrive at 48 MHz. In case the main frequency would be 48 MHz, a division by 1 would be needed.

The device driver

The CDC device library is used by providing a high level driver interface. This consists of a C struct with four function pointers. These functions are called in different situations. For example, the CDC_Itf_Receive function is called by the USB CDC library in case some data arrived from the host PC. All functions are passed to the CDC library by this structure:


USBD_CDC_ItfTypeDef USBD_CDC_fops =
{
    CDC_Itf_Init,       // called once in the initialization phase
    CDC_Itf_DeInit,     // called during shutdown of the USB pripheral
    CDC_Itf_Control,    //
    CDC_Itf_Receive     // called whenever some data arrived
};

This struct and all the functions are defined in the files usbd_cdc_interface.h and usbd_cdc_interface.c (code below).


/**
  ******************************************************************************
  * @file    base on: USB_Device/CDC_Standalone/Src/usbd_cdc_interface.c
  ******************************************************************************
  * @attention
  *
  * <h2><center>&copy; Copyright © 2015 STMicroelectronics International N.V. 
  * All rights reserved.</center></h2>
  *
  * Redistribution and use in source and binary forms, with or without 
  * modification, are permitted, provided that the following conditions are met:
  *
  * 1. Redistribution of source code must retain the above copyright notice, 
  *    this list of conditions and the following disclaimer.
  * 2. Redistributions in binary form must reproduce the above copyright notice,
  *    this list of conditions and the following disclaimer in the documentation
  *    and/or other materials provided with the distribution.
  * 3. Neither the name of STMicroelectronics nor the names of other 
  *    contributors to this software may be used to endorse or promote products 
  *    derived from this software without specific written permission.
  * 4. This software, including modifications and/or derivative works of this 
  *    software, must execute solely and exclusively on microcontroller or
  *    microprocessor devices manufactured by or for STMicroelectronics.
  * 5. Redistribution and use of this software other than as permitted under 
  *    this license is void and will automatically terminate your rights under 
  *    this license. 
  *
  * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" 
  * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT 
  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A 
  * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY
  * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT 
  * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
  * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, 
  * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 
  * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 
  * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
  * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
  *
  ******************************************************************************
  */

#include "main.h"

#define APP_RX_DATA_SIZE  2048
#define APP_TX_DATA_SIZE  2048

USBD_CDC_LineCodingTypeDef LineCoding =
  {
    115200, // baud rate
    0x00,   // stop bits-1
    0x00,   // parity - none
    0x08    // nb. of bits 8
  };

uint8_t UserRxBuffer[APP_RX_DATA_SIZE];// Received Data over USB are stored in this buffer
uint8_t UserTxBuffer[APP_TX_DATA_SIZE];// Received Data over UART (CDC interface) are stored in this buffer

extern USBD_HandleTypeDef  USBD_Device;

static int8_t CDC_Itf_Init     (void);
static int8_t CDC_Itf_DeInit   (void);
static int8_t CDC_Itf_Control  (uint8_t cmd, uint8_t* pbuf, uint16_t length);
static int8_t CDC_Itf_Receive  (uint8_t* pbuf, uint32_t *Len);

USBD_CDC_ItfTypeDef USBD_CDC_fops = 
{
  CDC_Itf_Init,
  CDC_Itf_DeInit,
  CDC_Itf_Control,
  CDC_Itf_Receive
};

static int8_t CDC_Itf_Init(void)
{
  USBD_CDC_SetTxBuffer(&USBD_Device, UserTxBuffer, 0);
  USBD_CDC_SetRxBuffer(&USBD_Device, UserRxBuffer);
  
  return (USBD_OK);
}

static int8_t CDC_Itf_DeInit(void)
{
  return (USBD_OK);
}

static int8_t CDC_Itf_Control (uint8_t cmd, uint8_t* pbuf, uint16_t length)
{ 
  switch (cmd) 
  {
  case CDC_SEND_ENCAPSULATED_COMMAND:
    break;

  case CDC_GET_ENCAPSULATED_RESPONSE:
    break;

  case CDC_SET_COMM_FEATURE:
    break;

  case CDC_GET_COMM_FEATURE:
    break;

  case CDC_CLEAR_COMM_FEATURE:
    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];
    
    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;     
    
    break;

  case CDC_SET_CONTROL_LINE_STATE:
    break;

  case CDC_SEND_BREAK:
    break;    
    
  default:
    break;
  }
  return (USBD_OK);
}


static int8_t CDC_Itf_Receive(uint8_t* Buf, uint32_t *Len)
{
  // clear the buffer with whitespaces
  if (UserTxBuffer[0]==0)
    for (int i = 0 ; i <10 ; ++i)
        UserTxBuffer[i] = ' ';

  if (*Len)
  {
    UserTxBuffer[0]=Buf[0];
    UserTxBuffer[1]='=';
  }
  // convert adc_value into ascii digits
  uint32_t div = 1000;
  uint32_t val = adc_value;
  int idx = 2;
  while(div)
  {
    UserTxBuffer[idx++] = '0' + val/div;
    val %= div;
    div /= 10;
  }
  // add newline and string termination
  UserTxBuffer[7] = '\r';
  UserTxBuffer[8] = '\n';
  UserTxBuffer[9] = 0;

  // Sent the buffer
  USBD_CDC_SetTxBuffer(&USBD_Device, (uint8_t*)&UserTxBuffer, 9);
  USBD_CDC_TransmitPacket(&USBD_Device);

  // prepare to receive the next USB packet
  USBD_CDC_ReceivePacket(&USBD_Device);
  return (USBD_OK);
}

/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/


The hardware

The only difference to the previous project is an additional 1k5 pull up (to 3.3 V) resistor at the D+ line of the USB connector. I added this on a bread board (It would be nice to have the option to put it directly on the pcb).

Action!

After flashing the device, the device should be detected by the host operating system (type lsusb in a terminal to list all USB devices), and a serial device should appear. On my computer this is /dev/ttyACM0
After connecting to it with picocom /dev/ttyACM0 I can send characters to the device by pressing keys on the keyboard. The device will answer with the character followed by an '=' sign followed by the last measured ADC value.

Keine Kommentare:

Kommentar veröffentlichen