code format

This commit is contained in:
crinq
2017-09-06 04:20:06 +02:00
parent 749d6d50bc
commit 9fb4b146fc
129 changed files with 8831 additions and 9378 deletions

View File

@@ -45,7 +45,7 @@
#ifndef __adc_H
#define __adc_H
#ifdef __cplusplus
extern "C" {
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/

View File

@@ -45,7 +45,7 @@
#ifndef __dac_H
#define __dac_H
#ifdef __cplusplus
extern "C" {
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/

View File

@@ -43,7 +43,7 @@
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __MAIN_H
#define __MAIN_H
/* Includes ------------------------------------------------------------------*/
/* Includes ------------------------------------------------------------------*/
/* USER CODE BEGIN Includes */
@@ -57,11 +57,11 @@
/**
* @}
*/
*/
/**
* @}
*/
*/
#endif /* __MAIN_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -45,7 +45,7 @@
#ifndef __opamp_H
#define __opamp_H
#ifdef __cplusplus
extern "C" {
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/

View File

@@ -30,14 +30,14 @@
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F3xx_HAL_CONF_H
#define __STM32F3xx_HAL_CONF_H
#ifdef __cplusplus
extern "C" {
extern "C" {
#endif
#include "main.h"
@@ -48,8 +48,8 @@
/**
* @brief This is the list of modules to be used in the HAL driver
*/
#define HAL_MODULE_ENABLED
#define HAL_MODULE_ENABLED
#define HAL_ADC_MODULE_ENABLED
/*#define HAL_CAN_MODULE_ENABLED */
/*#define HAL_CEC_MODULE_ENABLED */
@@ -93,16 +93,16 @@
* This value is used by the RCC HAL module to compute the system frequency
* (when HSE is used as system clock source, directly or through the PLL).
*/
#if !defined (HSE_VALUE)
#define HSE_VALUE ((uint32_t)8000000) /*!< Value of the External oscillator in Hz */
#if !defined(HSE_VALUE)
#define HSE_VALUE ((uint32_t)8000000) /*!< Value of the External oscillator in Hz */
#endif /* HSE_VALUE */
/**
* @brief In the following line adjust the External High Speed oscillator (HSE) Startup
* Timeout value
*/
#if !defined (HSE_STARTUP_TIMEOUT)
#define HSE_STARTUP_TIMEOUT ((uint32_t)100) /*!< Time out for HSE start up, in ms */
#if !defined(HSE_STARTUP_TIMEOUT)
#define HSE_STARTUP_TIMEOUT ((uint32_t)100) /*!< Time out for HSE start up, in ms */
#endif /* HSE_STARTUP_TIMEOUT */
/**
@@ -110,38 +110,38 @@
* This value is used by the RCC HAL module to compute the system frequency
* (when HSI is used as system clock source, directly or through the PLL).
*/
#if !defined (HSI_VALUE)
#define HSI_VALUE ((uint32_t)8000000) /*!< Value of the Internal oscillator in Hz*/
#if !defined(HSI_VALUE)
#define HSI_VALUE ((uint32_t)8000000) /*!< Value of the Internal oscillator in Hz*/
#endif /* HSI_VALUE */
/**
* @brief In the following line adjust the Internal High Speed oscillator (HSI) Startup
* Timeout value
*/
#if !defined (HSI_STARTUP_TIMEOUT)
#define HSI_STARTUP_TIMEOUT ((uint32_t)5000) /*!< Time out for HSI start up */
#endif /* HSI_STARTUP_TIMEOUT */
#if !defined(HSI_STARTUP_TIMEOUT)
#define HSI_STARTUP_TIMEOUT ((uint32_t)5000) /*!< Time out for HSI start up */
#endif /* HSI_STARTUP_TIMEOUT */
/**
* @brief Internal Low Speed oscillator (LSI) value.
*/
#if !defined (LSI_VALUE)
#define LSI_VALUE ((uint32_t)40000)
#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz
The real value may vary depending on the variations
in voltage and temperature. */
#if !defined(LSI_VALUE)
#define LSI_VALUE ((uint32_t)40000)
#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz \
The real value may vary depending on the variations \
in voltage and temperature. */
/**
* @brief External Low Speed oscillator (LSE) value.
*/
#if !defined (LSE_VALUE)
#define LSE_VALUE ((uint32_t)32768) /*!< Value of the External Low Speed oscillator in Hz */
#endif /* LSE_VALUE */
#if !defined(LSE_VALUE)
#define LSE_VALUE ((uint32_t)32768) /*!< Value of the External Low Speed oscillator in Hz */
#endif /* LSE_VALUE */
/**
* @brief Time out for LSE start up value in ms.
*/
#if !defined (LSE_STARTUP_TIMEOUT)
#define LSE_STARTUP_TIMEOUT ((uint32_t)5000) /*!< Time out for LSE start up, in ms */
#if !defined(LSE_STARTUP_TIMEOUT)
#define LSE_STARTUP_TIMEOUT ((uint32_t)5000) /*!< Time out for LSE start up, in ms */
#endif /* LSE_STARTUP_TIMEOUT */
/**
@@ -151,8 +151,8 @@
* - External clock generated through external PLL component on EVAL 303 (based on MCO or crystal)
* - External clock not generated on EVAL 373
*/
#if !defined (EXTERNAL_CLOCK_VALUE)
#define EXTERNAL_CLOCK_VALUE ((uint32_t)8000000) /*!< Value of the External oscillator in Hz*/
#if !defined(EXTERNAL_CLOCK_VALUE)
#define EXTERNAL_CLOCK_VALUE ((uint32_t)8000000) /*!< Value of the External oscillator in Hz*/
#endif /* EXTERNAL_CLOCK_VALUE */
/* Tip: To avoid modifying this file each time you need to use different HSE,
@@ -161,14 +161,14 @@
/* ########################### System Configuration ######################### */
/**
* @brief This is the HAL system configuration section
*/
*/
#define VDD_VALUE ((uint32_t)3300) /*!< Value of VDD in mv */
#define TICK_INT_PRIORITY ((uint32_t)0) /*!< tick interrupt priority (lowest by default) */
#define USE_RTOS 0
#define PREFETCH_ENABLE 1
#define INSTRUCTION_CACHE_ENABLE 0
#define DATA_CACHE_ENABLE 0
#define VDD_VALUE ((uint32_t)3300) /*!< Value of VDD in mv */
#define TICK_INT_PRIORITY ((uint32_t)0) /*!< tick interrupt priority (lowest by default) */
#define USE_RTOS 0
#define PREFETCH_ENABLE 1
#define INSTRUCTION_CACHE_ENABLE 0
#define DATA_CACHE_ENABLE 0
/* ########################## Assert Selection ############################## */
/**
@@ -183,139 +183,139 @@
*/
#ifdef HAL_RCC_MODULE_ENABLED
#include "stm32f3xx_hal_rcc.h"
#include "stm32f3xx_hal_rcc.h"
#endif /* HAL_RCC_MODULE_ENABLED */
#ifdef HAL_GPIO_MODULE_ENABLED
#include "stm32f3xx_hal_gpio.h"
#include "stm32f3xx_hal_gpio.h"
#endif /* HAL_GPIO_MODULE_ENABLED */
#ifdef HAL_DMA_MODULE_ENABLED
#include "stm32f3xx_hal_dma.h"
#include "stm32f3xx_hal_dma.h"
#endif /* HAL_DMA_MODULE_ENABLED */
#ifdef HAL_CORTEX_MODULE_ENABLED
#include "stm32f3xx_hal_cortex.h"
#include "stm32f3xx_hal_cortex.h"
#endif /* HAL_CORTEX_MODULE_ENABLED */
#ifdef HAL_ADC_MODULE_ENABLED
#include "stm32f3xx_hal_adc.h"
#include "stm32f3xx_hal_adc.h"
#endif /* HAL_ADC_MODULE_ENABLED */
#ifdef HAL_CAN_MODULE_ENABLED
#include "stm32f3xx_hal_can.h"
#include "stm32f3xx_hal_can.h"
#endif /* HAL_CAN_MODULE_ENABLED */
#ifdef HAL_CEC_MODULE_ENABLED
#include "stm32f3xx_hal_cec.h"
#include "stm32f3xx_hal_cec.h"
#endif /* HAL_CEC_MODULE_ENABLED */
#ifdef HAL_COMP_MODULE_ENABLED
#include "stm32f3xx_hal_comp.h"
#include "stm32f3xx_hal_comp.h"
#endif /* HAL_COMP_MODULE_ENABLED */
#ifdef HAL_CRC_MODULE_ENABLED
#include "stm32f3xx_hal_crc.h"
#include "stm32f3xx_hal_crc.h"
#endif /* HAL_CRC_MODULE_ENABLED */
#ifdef HAL_DAC_MODULE_ENABLED
#include "stm32f3xx_hal_dac.h"
#include "stm32f3xx_hal_dac.h"
#endif /* HAL_DAC_MODULE_ENABLED */
#ifdef HAL_FLASH_MODULE_ENABLED
#include "stm32f3xx_hal_flash.h"
#include "stm32f3xx_hal_flash.h"
#endif /* HAL_FLASH_MODULE_ENABLED */
#ifdef HAL_SRAM_MODULE_ENABLED
#include "stm32f3xx_hal_sram.h"
#include "stm32f3xx_hal_sram.h"
#endif /* HAL_SRAM_MODULE_ENABLED */
#ifdef HAL_NOR_MODULE_ENABLED
#include "stm32f3xx_hal_nor.h"
#include "stm32f3xx_hal_nor.h"
#endif /* HAL_NOR_MODULE_ENABLED */
#ifdef HAL_NAND_MODULE_ENABLED
#include "stm32f3xx_hal_nand.h"
#include "stm32f3xx_hal_nand.h"
#endif /* HAL_NAND_MODULE_ENABLED */
#ifdef HAL_PCCARD_MODULE_ENABLED
#include "stm32f3xx_hal_pccard.h"
#endif /* HAL_PCCARD_MODULE_ENABLED */
#include "stm32f3xx_hal_pccard.h"
#endif /* HAL_PCCARD_MODULE_ENABLED */
#ifdef HAL_HRTIM_MODULE_ENABLED
#include "stm32f3xx_hal_hrtim.h"
#include "stm32f3xx_hal_hrtim.h"
#endif /* HAL_HRTIM_MODULE_ENABLED */
#ifdef HAL_I2C_MODULE_ENABLED
#include "stm32f3xx_hal_i2c.h"
#include "stm32f3xx_hal_i2c.h"
#endif /* HAL_I2C_MODULE_ENABLED */
#ifdef HAL_I2S_MODULE_ENABLED
#include "stm32f3xx_hal_i2s.h"
#include "stm32f3xx_hal_i2s.h"
#endif /* HAL_I2S_MODULE_ENABLED */
#ifdef HAL_IRDA_MODULE_ENABLED
#include "stm32f3xx_hal_irda.h"
#include "stm32f3xx_hal_irda.h"
#endif /* HAL_IRDA_MODULE_ENABLED */
#ifdef HAL_IWDG_MODULE_ENABLED
#include "stm32f3xx_hal_iwdg.h"
#include "stm32f3xx_hal_iwdg.h"
#endif /* HAL_IWDG_MODULE_ENABLED */
#ifdef HAL_OPAMP_MODULE_ENABLED
#include "stm32f3xx_hal_opamp.h"
#include "stm32f3xx_hal_opamp.h"
#endif /* HAL_OPAMP_MODULE_ENABLED */
#ifdef HAL_PCD_MODULE_ENABLED
#include "stm32f3xx_hal_pcd.h"
#include "stm32f3xx_hal_pcd.h"
#endif /* HAL_PCD_MODULE_ENABLED */
#ifdef HAL_PWR_MODULE_ENABLED
#include "stm32f3xx_hal_pwr.h"
#include "stm32f3xx_hal_pwr.h"
#endif /* HAL_PWR_MODULE_ENABLED */
#ifdef HAL_RTC_MODULE_ENABLED
#include "stm32f3xx_hal_rtc.h"
#include "stm32f3xx_hal_rtc.h"
#endif /* HAL_RTC_MODULE_ENABLED */
#ifdef HAL_SDADC_MODULE_ENABLED
#include "stm32f3xx_hal_sdadc.h"
#include "stm32f3xx_hal_sdadc.h"
#endif /* HAL_SDADC_MODULE_ENABLED */
#ifdef HAL_SMARTCARD_MODULE_ENABLED
#include "stm32f3xx_hal_smartcard.h"
#include "stm32f3xx_hal_smartcard.h"
#endif /* HAL_SMARTCARD_MODULE_ENABLED */
#ifdef HAL_SMBUS_MODULE_ENABLED
#include "stm32f3xx_hal_smbus.h"
#include "stm32f3xx_hal_smbus.h"
#endif /* HAL_SMBUS_MODULE_ENABLED */
#ifdef HAL_SPI_MODULE_ENABLED
#include "stm32f3xx_hal_spi.h"
#include "stm32f3xx_hal_spi.h"
#endif /* HAL_SPI_MODULE_ENABLED */
#ifdef HAL_TIM_MODULE_ENABLED
#include "stm32f3xx_hal_tim.h"
#include "stm32f3xx_hal_tim.h"
#endif /* HAL_TIM_MODULE_ENABLED */
#ifdef HAL_TSC_MODULE_ENABLED
#include "stm32f3xx_hal_tsc.h"
#include "stm32f3xx_hal_tsc.h"
#endif /* HAL_TSC_MODULE_ENABLED */
#ifdef HAL_UART_MODULE_ENABLED
#include "stm32f3xx_hal_uart.h"
#include "stm32f3xx_hal_uart.h"
#endif /* HAL_UART_MODULE_ENABLED */
#ifdef HAL_USART_MODULE_ENABLED
#include "stm32f3xx_hal_usart.h"
#include "stm32f3xx_hal_usart.h"
#endif /* HAL_USART_MODULE_ENABLED */
#ifdef HAL_WWDG_MODULE_ENABLED
#include "stm32f3xx_hal_wwdg.h"
#include "stm32f3xx_hal_wwdg.h"
#endif /* HAL_WWDG_MODULE_ENABLED */
/* Exported macro ------------------------------------------------------------*/
#ifdef USE_FULL_ASSERT
#ifdef USE_FULL_ASSERT
/**
* @brief The assert_param macro is used for function's parameters check.
* @param expr: If expr is false, it calls assert_failed function
@@ -324,13 +324,13 @@
* If expr is true, it returns no value.
* @retval None
*/
#define assert_param(expr) ((expr) ? (void)0 : assert_failed((uint8_t *)__FILE__, __LINE__))
#define assert_param(expr) ((expr) ? (void)0 : assert_failed((uint8_t *)__FILE__, __LINE__))
/* Exported functions ------------------------------------------------------- */
void assert_failed(uint8_t* file, uint32_t line);
void assert_failed(uint8_t *file, uint32_t line);
#else
#define assert_param(expr) ((void)0)
#endif /* USE_FULL_ASSERT */
#define assert_param(expr) ((void)0)
#endif /* USE_FULL_ASSERT */
#ifdef __cplusplus
}
#endif

View File

@@ -36,8 +36,8 @@
#define __STM32F3xx_IT_H
#ifdef __cplusplus
extern "C" {
#endif
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
/* Exported types ------------------------------------------------------------*/

View File

@@ -45,7 +45,7 @@
#ifndef __tim_H
#define __tim_H
#ifdef __cplusplus
extern "C" {
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
@@ -65,9 +65,9 @@ extern TIM_HandleTypeDef htim8;
extern void Error_Handler(void);
void MX_TIM8_Init(void);
void HAL_TIM_MspPostInit(TIM_HandleTypeDef *htim);
/* USER CODE BEGIN Prototypes */

View File

@@ -45,7 +45,7 @@
#ifndef __usb_device_H
#define __usb_device_H
#ifdef __cplusplus
extern "C" {
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
@@ -55,7 +55,7 @@
extern USBD_HandleTypeDef hUsbDeviceFS;
/* USB_Device init function */
/* USB_Device init function */
void MX_USB_DEVICE_Init(void);
#ifdef __cplusplus

View File

@@ -46,7 +46,7 @@
#define __USBD_CDC_IF_H
#ifdef __cplusplus
extern "C" {
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "usbd_cdc.h"
@@ -56,82 +56,82 @@
/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
* @{
*/
/** @defgroup USBD_CDC_IF
* @brief header
* @{
*/
*/
/** @defgroup USBD_CDC_IF_Exported_Defines
* @{
*/
*/
/* USER CODE BEGIN EXPORTED_DEFINES */
/* USER CODE END EXPORTED_DEFINES */
/**
* @}
*/
*/
/** @defgroup USBD_CDC_IF_Exported_Types
* @{
*/
*/
/* USER CODE BEGIN EXPORTED_TYPES */
/* USER CODE END EXPORTED_TYPES */
/**
* @}
*/
*/
/** @defgroup USBD_CDC_IF_Exported_Macros
* @{
*/
*/
/* USER CODE BEGIN EXPORTED_MACRO */
/* USER CODE END EXPORTED_MACRO */
/**
* @}
*/
*/
/** @defgroup USBD_AUDIO_IF_Exported_Variables
* @{
*/
extern USBD_CDC_ItfTypeDef USBD_Interface_fops_FS;
*/
extern USBD_CDC_ItfTypeDef USBD_Interface_fops_FS;
/* USER CODE BEGIN EXPORTED_VARIABLES */
/* USER CODE END EXPORTED_VARIABLES */
/**
* @}
*/
*/
/** @defgroup USBD_CDC_IF_Exported_FunctionsPrototype
* @{
*/
uint8_t CDC_Transmit_FS(uint8_t* Buf, uint16_t Len);
*/
uint8_t CDC_Transmit_FS(uint8_t *Buf, uint16_t Len);
/* USER CODE BEGIN EXPORTED_FUNCTIONS */
//void cdc_init(void);
int cdc_tx(void* data, uint32_t len);
int cdc_tx(void *data, uint32_t len);
int cdc_getline(char *ptr, int len);
int cdc_is_connected();
void cdc_poll();
/* USER CODE END EXPORTED_FUNCTIONS */
/**
* @}
*/
*/
/**
* @}
*/
*/
/**
* @}
*/
*/
#ifdef __cplusplus
}
#endif
#endif /* __USBD_CDC_IF_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -45,7 +45,7 @@
#ifndef __USBD_CONF__H__
#define __USBD_CONF__H__
#ifdef __cplusplus
extern "C" {
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include <stdio.h>
@@ -58,115 +58,117 @@
/** @addtogroup USBD_OTG_DRIVER
* @{
*/
/** @defgroup USBD_CONF
* @brief usb otg low level driver configuration file
* @{
*/
*/
/** @defgroup USBD_CONF_Exported_Defines
* @{
*/
*/
/*---------- -----------*/
#define USBD_MAX_NUM_INTERFACES 1
#define USBD_MAX_NUM_INTERFACES 1
/*---------- -----------*/
#define USBD_MAX_NUM_CONFIGURATION 1
#define USBD_MAX_NUM_CONFIGURATION 1
/*---------- -----------*/
#define USBD_MAX_STR_DESC_SIZ 512
#define USBD_MAX_STR_DESC_SIZ 512
/*---------- -----------*/
#define USBD_SUPPORT_USER_STRING 0
#define USBD_SUPPORT_USER_STRING 0
/*---------- -----------*/
#define USBD_DEBUG_LEVEL 0
#define USBD_DEBUG_LEVEL 0
/*---------- -----------*/
#define USBD_SELF_POWERED 1
#define USBD_SELF_POWERED 1
/*---------- -----------*/
#define USBD_CDC_INTERVAL 1000
#define USBD_CDC_INTERVAL 1000
/****************************************/
/* #define for FS and HS identification */
#define DEVICE_FS 0
#define DEVICE_FS 0
/** @defgroup USBD_Exported_Macros
* @{
*/
*/
/* Memory management macros */
#define USBD_malloc (uint32_t *)USBD_static_malloc
#define USBD_free USBD_static_free
#define USBD_memset /* Not used */
#define USBD_memcpy /* Not used */
/* Memory management macros */
#define USBD_malloc (uint32_t *)USBD_static_malloc
#define USBD_free USBD_static_free
#define USBD_memset /* Not used */
#define USBD_memcpy /* Not used */
#define USBD_Delay HAL_Delay
#define USBD_Delay HAL_Delay
/* For footprint reasons and since only one allocation is handled in the HID class
driver, the malloc/free is changed into a static allocation method */
void *USBD_static_malloc(uint32_t size);
void USBD_static_free(void *p);
void USBD_static_free(void *p);
/* DEBUG macros */
#if (USBD_DEBUG_LEVEL > 0)
#define USBD_UsrLog(...) printf(__VA_ARGS__);\
printf("\n");
/* DEBUG macros */
#if(USBD_DEBUG_LEVEL > 0)
#define USBD_UsrLog(...) \
printf(__VA_ARGS__); \
printf("\n");
#else
#define USBD_UsrLog(...)
#endif
#if (USBD_DEBUG_LEVEL > 1)
#define USBD_ErrLog(...) printf("ERROR: ") ;\
printf(__VA_ARGS__);\
printf("\n");
#else
#define USBD_ErrLog(...)
#endif
#if (USBD_DEBUG_LEVEL > 2)
#define USBD_DbgLog(...) printf("DEBUG : ") ;\
printf(__VA_ARGS__);\
printf("\n");
#else
#define USBD_DbgLog(...)
#define USBD_UsrLog(...)
#endif
#if(USBD_DEBUG_LEVEL > 1)
#define USBD_ErrLog(...) \
printf("ERROR: "); \
printf(__VA_ARGS__); \
printf("\n");
#else
#define USBD_ErrLog(...)
#endif
#if(USBD_DEBUG_LEVEL > 2)
#define USBD_DbgLog(...) \
printf("DEBUG : "); \
printf(__VA_ARGS__); \
printf("\n");
#else
#define USBD_DbgLog(...)
#endif
/**
* @}
*/
*/
/**
* @}
*/
*/
/** @defgroup USBD_CONF_Exported_Types
* @{
*/
*/
/**
* @}
*/
*/
/** @defgroup USBD_CONF_Exported_Macros
* @{
*/
*/
/**
* @}
*/
*/
/** @defgroup USBD_CONF_Exported_Variables
* @{
*/
*/
/**
* @}
*/
*/
/** @defgroup USBD_CONF_Exported_FunctionsPrototype
* @{
*/
*/
/**
* @}
*/
*/
#ifdef __cplusplus
}
#endif
@@ -175,10 +177,9 @@ void USBD_static_free(void *p);
/**
* @}
*/
*/
/**
* @}
*/
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -47,7 +47,7 @@
#define __USBD_DESC__H__
#ifdef __cplusplus
extern "C" {
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "usbd_def.h"
@@ -55,11 +55,11 @@
/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
* @{
*/
/** @defgroup USB_DESC
* @brief general defines for the usb device library file
* @{
*/
*/
/** @defgroup USB_DESC_Exported_Defines
* @{
@@ -67,37 +67,37 @@
/**
* @}
*/
*/
/** @defgroup USBD_DESC_Exported_TypesDefinitions
* @{
*/
/**
* @}
*/
*/
/** @defgroup USBD_DESC_Exported_Macros
* @{
*/
*/
/**
* @}
*/
*/
/** @defgroup USBD_DESC_Exported_Variables
* @{
*/
*/
extern USBD_DescriptorsTypeDef FS_Desc;
/**
* @}
*/
*/
/** @defgroup USBD_DESC_Exported_FunctionsPrototype
* @{
*/
*/
/**
* @}
*/
*/
#ifdef __cplusplus
}
#endif
@@ -106,9 +106,9 @@ extern USBD_DescriptorsTypeDef FS_Desc;
/**
* @}
*/
*/
/**
* @}
*/
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

File diff suppressed because it is too large Load Diff

View File

@@ -11,73 +11,73 @@ HAL_PIN(pos);
HAL_PIN(a);
HAL_PIN(b);
TIM_HandleTypeDef htim1;
TIM_HandleTypeDef htim1;
static void nrt_init(volatile void * ctx_ptr, volatile hal_pin_inst_t * pin_ptr){
static void nrt_init(volatile void *ctx_ptr, volatile hal_pin_inst_t *pin_ptr) {
// struct enc_ctx_t * ctx = (struct enc_ctx_t *)ctx_ptr;
// struct enc_pin_ctx_t * pins = (struct enc_pin_ctx_t *)pin_ptr;
__HAL_RCC_TIM1_CLK_ENABLE();
/**TIM1 GPIO Configuration
PA8 ------> TIM1_CH1
PA9 ------> TIM1_CH2
*/
GPIO_InitTypeDef GPIO_InitStruct;
GPIO_InitStruct.Pin = GPIO_PIN_8|GPIO_PIN_9;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_PULLUP;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Pin = GPIO_PIN_8 | GPIO_PIN_9;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_PULLUP;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Alternate = GPIO_AF6_TIM1;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
TIM_Encoder_InitTypeDef sConfig;
TIM_MasterConfigTypeDef sMasterConfig;
htim1.Instance = TIM1;
htim1.Init.Prescaler = 0;
htim1.Init.CounterMode = TIM_COUNTERMODE_UP;
htim1.Init.Period = 2000;
htim1.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
htim1.Instance = TIM1;
htim1.Init.Prescaler = 0;
htim1.Init.CounterMode = TIM_COUNTERMODE_UP;
htim1.Init.Period = 2000;
htim1.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
htim1.Init.RepetitionCounter = 0;
// htim1.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
sConfig.EncoderMode = TIM_ENCODERMODE_TI12;//TIM_ENCODERMODE_TI1??
sConfig.IC1Polarity = TIM_ICPOLARITY_RISING;
sConfig.EncoderMode = TIM_ENCODERMODE_TI12; //TIM_ENCODERMODE_TI1??
sConfig.IC1Polarity = TIM_ICPOLARITY_RISING;
sConfig.IC1Selection = TIM_ICSELECTION_DIRECTTI;
sConfig.IC1Prescaler = TIM_ICPSC_DIV1;
sConfig.IC1Filter = 0;
sConfig.IC2Polarity = TIM_ICPOLARITY_RISING;
sConfig.IC1Filter = 0;
sConfig.IC2Polarity = TIM_ICPOLARITY_RISING;
sConfig.IC2Selection = TIM_ICSELECTION_DIRECTTI;
sConfig.IC2Prescaler = TIM_ICPSC_DIV1;
sConfig.IC2Filter = 0;
sConfig.IC2Filter = 0;
HAL_TIM_Encoder_Init(&htim1, &sConfig);
sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
sMasterConfig.MasterOutputTrigger2 = TIM_TRGO2_RESET;
sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
HAL_TIMEx_MasterConfigSynchronization(&htim1, &sMasterConfig);
HAL_TIM_Encoder_Start(&htim1, TIM_CHANNEL_1 | TIM_CHANNEL_2);
}
static void rt_func(float period, volatile void * ctx_ptr, volatile hal_pin_inst_t * pin_ptr){
static void rt_func(float period, volatile void *ctx_ptr, volatile hal_pin_inst_t *pin_ptr) {
// struct enc_ctx_t * ctx = (struct enc_ctx_t *)ctx_ptr;
struct enc_pin_ctx_t * pins = (struct enc_pin_ctx_t *)pin_ptr;
PIN(a) = HAL_GPIO_ReadPin(GPIOA, GPIO_PIN_8);
PIN(b) = HAL_GPIO_ReadPin(GPIOA, GPIO_PIN_9);
struct enc_pin_ctx_t *pins = (struct enc_pin_ctx_t *)pin_ptr;
PIN(a) = HAL_GPIO_ReadPin(GPIOA, GPIO_PIN_8);
PIN(b) = HAL_GPIO_ReadPin(GPIOA, GPIO_PIN_9);
PIN(pos) = mod(TIM1->CNT * 2.0f * M_PI / 2000.0f);
}
hal_comp_t enc_comp_struct = {
.name = "enc",
.nrt = 0,
.rt = rt_func,
.frt = 0,
.nrt_init = nrt_init,
.rt_start = 0,
.frt_start = 0,
.rt_stop = 0,
.frt_stop = 0,
.ctx_size = 0,
.pin_count = sizeof(struct enc_pin_ctx_t) / sizeof(struct hal_pin_inst_t),
.name = "enc",
.nrt = 0,
.rt = rt_func,
.frt = 0,
.nrt_init = nrt_init,
.rt_start = 0,
.frt_start = 0,
.rt_stop = 0,
.frt_stop = 0,
.ctx_size = 0,
.pin_count = sizeof(struct enc_pin_ctx_t) / sizeof(struct hal_pin_inst_t),
};

View File

@@ -27,37 +27,37 @@ HAL_PIN(enw);
//fault output
HAL_PIN(fault);
HAL_PIN(min_on); // min on time [s]
HAL_PIN(min_off); // min off time [s]
HAL_PIN(min_on); // min on time [s]
HAL_PIN(min_off); // min off time [s]
static void nrt_init(volatile void * ctx_ptr, volatile hal_pin_inst_t * pin_ptr){
static void nrt_init(volatile void *ctx_ptr, volatile hal_pin_inst_t *pin_ptr) {
// struct hv_ctx_t * ctx = (struct hv_ctx_t *)ctx_ptr;
struct hv_pin_ctx_t * pins = (struct hv_pin_ctx_t *)pin_ptr;
PIN(enu) = 1.0;
PIN(env) = 1.0;
PIN(enw) = 1.0;
PIN(min_on) = 0.00000035;
struct hv_pin_ctx_t *pins = (struct hv_pin_ctx_t *)pin_ptr;
PIN(enu) = 1.0;
PIN(env) = 1.0;
PIN(enw) = 1.0;
PIN(min_on) = 0.00000035;
PIN(min_off) = 0.000005;
GPIO_InitTypeDef GPIO_InitStruct;
//PA15 HV EN
GPIO_InitStruct.Pin = GPIO_PIN_15;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Pin = GPIO_PIN_15;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
//PB7 HV FAULT
GPIO_InitStruct.Pin = GPIO_PIN_7;
GPIO_InitStruct.Pin = GPIO_PIN_7;
GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
}
static void rt_func(float period, volatile void * ctx_ptr, volatile hal_pin_inst_t * pin_ptr){
static void rt_func(float period, volatile void *ctx_ptr, volatile hal_pin_inst_t *pin_ptr) {
// struct hv_ctx_t * ctx = (struct hv_ctx_t *)ctx_ptr;
struct hv_pin_ctx_t * pins = (struct hv_pin_ctx_t *)pin_ptr;
struct hv_pin_ctx_t *pins = (struct hv_pin_ctx_t *)pin_ptr;
float udc = MAX(PIN(udc), 0.1);
//convert voltages to PWM output compare values
@@ -65,35 +65,34 @@ static void rt_func(float period, volatile void * ctx_ptr, volatile hal_pin_inst
int32_t v = (int32_t)(CLAMP(PIN(v), 0.0, udc) / udc * 4800.0);
int32_t w = (int32_t)(CLAMP(PIN(w), 0.0, udc) / udc * 4800.0);
//convert on and off times to PWM output compare values
int32_t min_on = (int32_t)(4800.0 * 15000.0 * PIN(min_on) + 0.5);
int32_t min_on = (int32_t)(4800.0 * 15000.0 * PIN(min_on) + 0.5);
int32_t min_off = (int32_t)(4800.0 * 15000.0 * PIN(min_off) + 0.5);
if((u > 0 && u < min_on) || (v > 0 && v < min_on) || (w > 0 && w < min_on)){
if((u > 0 && u < min_on) || (v > 0 && v < min_on) || (w > 0 && w < min_on)) {
u += min_on;
v += min_on;
w += min_on;
}
if((u > 4800 - min_off) || (v > 4800 - min_off) || (w > 4800 - min_off)){
if((u > 4800 - min_off) || (v > 4800 - min_off) || (w > 4800 - min_off)) {
u -= min_off;
v -= min_off;
w -= min_off;
}
#ifdef PWM_INVERT
PWM_U = 4800-CLAMP(u, 0, 4800 - min_off);
PWM_V = 4800-CLAMP(v, 0, 4800 - min_off);
PWM_W = 4800-CLAMP(w, 0, 4800 - min_off);
PWM_U = 4800 - CLAMP(u, 0, 4800 - min_off);
PWM_V = 4800 - CLAMP(v, 0, 4800 - min_off);
PWM_W = 4800 - CLAMP(w, 0, 4800 - min_off);
#else
PWM_U = CLAMP(u, 0, 4800 - min_off);
PWM_V = CLAMP(v, 0, 4800 - min_off);
PWM_W = CLAMP(w, 0, 4800 - min_off);
#endif
if(PIN(hv_temp) < 85.0){
if(PIN(hv_temp) < 85.0) {
HAL_GPIO_WritePin(GPIOA, GPIO_PIN_15, PIN(en) > 0 ? GPIO_PIN_SET : GPIO_PIN_RESET);
}
else{
} else {
HAL_GPIO_WritePin(GPIOA, GPIO_PIN_15, GPIO_PIN_RESET);
}
//TODO: check enable timing on fault pin
@@ -101,15 +100,15 @@ static void rt_func(float period, volatile void * ctx_ptr, volatile hal_pin_inst
}
hal_comp_t hv_comp_struct = {
.name = "hv",
.nrt = 0,
.rt = rt_func,
.frt = 0,
.nrt_init = nrt_init,
.rt_start = 0,
.frt_start = 0,
.rt_stop = 0,
.frt_stop = 0,
.ctx_size = 0,
.pin_count = sizeof(struct hv_pin_ctx_t) / sizeof(struct hal_pin_inst_t),
.name = "hv",
.nrt = 0,
.rt = rt_func,
.frt = 0,
.nrt_init = nrt_init,
.rt_start = 0,
.frt_start = 0,
.rt_stop = 0,
.frt_stop = 0,
.ctx_size = 0,
.pin_count = sizeof(struct hv_pin_ctx_t) / sizeof(struct hal_pin_inst_t),
};

View File

@@ -14,25 +14,26 @@ HAL_PIN(uq);
HAL_PIN(udc);
static void rt_func(float period, volatile void * ctx_ptr, volatile hal_pin_inst_t * pin_ptr){
static void rt_func(float period, volatile void *ctx_ptr, volatile hal_pin_inst_t *pin_ptr) {
// struct hv_ctx_t * ctx = (struct hv_ctx_t *)ctx_ptr;
struct hvdc_pin_ctx_t * pins = (struct hvdc_pin_ctx_t *)pin_ptr;
float udc = MAX(PIN(udc), 1.0);
int32_t dcpwm = (int32_t)(PIN(uq)/2.0/udc * 4800.0);
PWM_U = CLAMP(2400 + dcpwm , 50, 4750);
PWM_V = CLAMP(2400 - dcpwm , 50, 4750);
struct hvdc_pin_ctx_t *pins = (struct hvdc_pin_ctx_t *)pin_ptr;
float udc = MAX(PIN(udc), 1.0);
int32_t dcpwm = (int32_t)(PIN(uq) / 2.0 / udc * 4800.0);
PWM_U = CLAMP(2400 + dcpwm, 50, 4750);
PWM_V = CLAMP(2400 - dcpwm, 50, 4750);
}
hal_comp_t hvdc_comp_struct = {
.name = "hvdc",
.nrt = 0,
.rt = rt_func,
.frt = 0,
.nrt_init = 0,
.rt_start = 0,
.frt_start = 0,
.rt_stop = 0,
.frt_stop = 0,
.ctx_size = 0,
.pin_count = sizeof(struct hvdc_pin_ctx_t) / sizeof(struct hal_pin_inst_t),
.name = "hvdc",
.nrt = 0,
.rt = rt_func,
.frt = 0,
.nrt_init = 0,
.rt_start = 0,
.frt_start = 0,
.rt_stop = 0,
.frt_stop = 0,
.ctx_size = 0,
.pin_count = sizeof(struct hvdc_pin_ctx_t) / sizeof(struct hal_pin_inst_t),
};

View File

@@ -26,127 +26,129 @@ HAL_PIN(mot_temp);
uint32_t adc_12_buf[10];
uint32_t adc_34_buf[10];
struct io_ctx_t{
struct io_ctx_t {
float u_offset;
float v_offset;
float w_offset;
};
#define ARES 4096.0// analog resolution, 12 bit
#define ARES 4096.0 // analog resolution, 12 bit
#define ADC(a) ((a) / ARES * AREF)
#define HV_TEMP_PULLUP 10000
#define HV_R(a) (HV_TEMP_PULLUP / (AREF / (a) - 1))
#define HV_R(a) (HV_TEMP_PULLUP / (AREF / (a)-1))
#define MOT_TEMP_PULLUP 10000
#define MOT_TEMP_PULLMID 51000
#define MOT_TEMP_PULLDOWN 10000
#define MOT_TEMP_REF 15.26
#define MOT_REF(a) ((a) * (MOT_TEMP_PULLMID + MOT_TEMP_PULLDOWN) / MOT_TEMP_PULLDOWN)
#define MOT_R(a) (MOT_TEMP_PULLUP / (MOT_TEMP_REF / (a) - 1))
#define MOT_R(a) (MOT_TEMP_PULLUP / (MOT_TEMP_REF / (a)-1))
#define ARES 4096.0// analog resolution, 12 bit
#define ARES 4096.0 // analog resolution, 12 bit
#define VOLT(a) ((a) / (ARES) * (AREF) / (VDIVDOWN) * ((VDIVUP) + (VDIVDOWN)))
//#define TEMP(a) (log10f((a) * (AREF) / (ARES) * (TPULLUP) / ((AREF) - (a) * (AREF) / (ARES))) * (-53.0) + 290.0)
#define SHUNT_GAIN 16.0
#define AMP(a, gain) (((a) * AREF / ARES / (gain) - AREF / (SHUNT_PULLUP + SHUNT_SERIE) * SHUNT_SERIE) / (SHUNT * SHUNT_PULLUP) * (SHUNT_PULLUP + SHUNT_SERIE))
#define AMP(a, gain) (((a)*AREF / ARES / (gain)-AREF / (SHUNT_PULLUP + SHUNT_SERIE) * SHUNT_SERIE) / (SHUNT * SHUNT_PULLUP) * (SHUNT_PULLUP + SHUNT_SERIE))
float r2temp(float r){
r = r / 1000;
const int step = 10;
float r2temp(float r) {
r = r / 1000;
const int step = 10;
const int start = -10;
//-10..100
const float temp[] = {271.7, 158.2, 95.23, 59.07, 37.64, 24.59, 16.43, 11.21, 7.798, 5.518, 3.972, 2.902};
for(int i = 1; i < ARRAY_SIZE(temp); i++){
if(temp[i] < r){
for(int i = 1; i < ARRAY_SIZE(temp); i++) {
if(temp[i] < r) {
float a = temp[i - 1];
float b = temp[i];
return(-(r - b) / (a - b) * step + i * step + start);
return (-(r - b) / (a - b) * step + i * step + start);
}
}
return(temp[ARRAY_SIZE(temp)] + step);
return (temp[ARRAY_SIZE(temp)] + step);
}
static void nrt_init(volatile void * ctx_ptr, volatile hal_pin_inst_t * pin_ptr){
static void nrt_init(volatile void *ctx_ptr, volatile hal_pin_inst_t *pin_ptr) {
// struct io_ctx_t * ctx = (struct io_ctx_t *)ctx_ptr;
// struct io_pin_ctx_t * pins = (struct io_pin_ctx_t *)pin_ptr;
GPIO_InitTypeDef GPIO_InitStruct;
//PA8 LED
GPIO_InitStruct.Pin = GPIO_PIN_8;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Pin = GPIO_PIN_8;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
DMA1_Channel1->CCR &= (uint16_t)(~DMA_CCR_EN);
DMA1_Channel1->CPAR = (uint32_t)&(ADC12_COMMON->CDR);
DMA1_Channel1->CMAR = (uint32_t)adc_12_buf;
DMA1_Channel1->CPAR = (uint32_t) & (ADC12_COMMON->CDR);
DMA1_Channel1->CMAR = (uint32_t)adc_12_buf;
DMA1_Channel1->CNDTR = 6;
DMA1_Channel1->CCR = DMA_CCR_MINC | DMA_CCR_PL_0 | DMA_CCR_MSIZE_1 | DMA_CCR_PSIZE_1 | DMA_CCR_CIRC;
DMA1_Channel1->CCR = DMA_CCR_MINC | DMA_CCR_PL_0 | DMA_CCR_MSIZE_1 | DMA_CCR_PSIZE_1 | DMA_CCR_CIRC;
ADC1->CFGR |= ADC_CFGR_DMAEN | ADC_CFGR_DMACFG;
DMA1_Channel1->CCR |= DMA_CCR_EN;
// ADC12_COMMON->CCR |= ADC12_CCR_MDMA_1;
DMA2_Channel5->CCR &= (uint16_t)(~DMA_CCR_EN);
DMA2_Channel5->CPAR = (uint32_t)&(ADC34_COMMON->CDR);
DMA2_Channel5->CMAR = (uint32_t)adc_34_buf;
DMA2_Channel5->CPAR = (uint32_t) & (ADC34_COMMON->CDR);
DMA2_Channel5->CMAR = (uint32_t)adc_34_buf;
DMA2_Channel5->CNDTR = 6;
DMA2_Channel5->CCR = DMA_CCR_MINC | DMA_CCR_PL_0 | DMA_CCR_MSIZE_1 | DMA_CCR_PSIZE_1 | DMA_CCR_CIRC;
DMA2_Channel5->CCR = DMA_CCR_MINC | DMA_CCR_PL_0 | DMA_CCR_MSIZE_1 | DMA_CCR_PSIZE_1 | DMA_CCR_CIRC;
ADC3->CFGR |= ADC_CFGR_DMAEN | ADC_CFGR_DMACFG;
DMA2_Channel5->CCR |= DMA_CCR_EN;
// ADC34_COMMON->CCR |= ADC34_CCR_MDMA_1;
}
static void rt_func(float period, volatile void * ctx_ptr, volatile hal_pin_inst_t * pin_ptr){
struct io_ctx_t * ctx = (struct io_ctx_t *)ctx_ptr;
struct io_pin_ctx_t * pins = (struct io_pin_ctx_t *)pin_ptr;
static void rt_func(float period, volatile void *ctx_ptr, volatile hal_pin_inst_t *pin_ptr) {
struct io_ctx_t *ctx = (struct io_ctx_t *)ctx_ptr;
struct io_pin_ctx_t *pins = (struct io_pin_ctx_t *)pin_ptr;
while(!(DMA1->ISR & DMA_ISR_TCIF1)) {
}
while(!(DMA2->ISR & DMA_ISR_TCIF5)) {
}
while(!(DMA1->ISR & DMA_ISR_TCIF1)){}
while(!(DMA2->ISR & DMA_ISR_TCIF5)){}
DMA1->IFCR = DMA_IFCR_CTCIF1;
DMA2->IFCR = DMA_IFCR_CTCIF5;
uint32_t a12 = adc_12_buf[0] + adc_12_buf[1] + adc_12_buf[2] + adc_12_buf[3] + adc_12_buf[4];
uint32_t a34 = adc_34_buf[0] + adc_34_buf[1] + adc_34_buf[2] + adc_34_buf[3] + adc_34_buf[4];
if(ctx->u_offset == 0){
if(ctx->u_offset == 0) {
ctx->w_offset = AMP((float)(a12 & 0xFFFF) / 5.0, SHUNT_GAIN);
ctx->u_offset = AMP((float)(a12 >> 16) / 5.0, SHUNT_GAIN);
ctx->v_offset = AMP((float)(a34 & 0xFFFF) / 5.0, SHUNT_GAIN);
}
PIN(iw) = -AMP((float)(a12 & 0xFFFF) / 5.0, SHUNT_GAIN) + ctx->w_offset; // 1u
PIN(iu) = -AMP((float)(a12 >> 16) / 5.0, SHUNT_GAIN) + ctx->u_offset;
PIN(iv) = -AMP((float)(a34 & 0xFFFF) / 5.0, SHUNT_GAIN) + ctx->v_offset;
PIN(w) = VOLT(adc_12_buf[5] & 0xFFFF) * 0.05 + PIN(w) * 0.95; // 0.6u
PIN(v) = VOLT(adc_12_buf[5] >> 16) * 0.05 + PIN(v) * 0.95;
PIN(u) = VOLT(adc_34_buf[5] & 0xFFFF) * 0.05 + PIN(u) * 0.95;
PIN(udc) = VOLT(adc_34_buf[5] >> 16) * 0.05 + PIN(udc) * 0.95;
PIN(iw) = -AMP((float)(a12 & 0xFFFF) / 5.0, SHUNT_GAIN) + ctx->w_offset; // 1u
PIN(iu) = -AMP((float)(a12 >> 16) / 5.0, SHUNT_GAIN) + ctx->u_offset;
PIN(iv) = -AMP((float)(a34 & 0xFFFF) / 5.0, SHUNT_GAIN) + ctx->v_offset;
PIN(w) = VOLT(adc_12_buf[5] & 0xFFFF) * 0.05 + PIN(w) * 0.95; // 0.6u
PIN(v) = VOLT(adc_12_buf[5] >> 16) * 0.05 + PIN(v) * 0.95;
PIN(u) = VOLT(adc_34_buf[5] & 0xFFFF) * 0.05 + PIN(u) * 0.95;
PIN(udc) = VOLT(adc_34_buf[5] >> 16) * 0.05 + PIN(udc) * 0.95;
PIN(udc_pwm) = PIN(udc) / 2.0;
PIN(hv_temp) = r2temp(HV_R(ADC(adc_34_buf[0] >> 16))) * 0.01 + PIN(hv_temp) * 0.99; // 5.5u
PIN(mot_temp) = MOT_R(MOT_REF(ADC(adc_34_buf[3] >> 16))); // 1.4u
HAL_GPIO_WritePin(GPIOA, GPIO_PIN_8, PIN(led) > 0 ? GPIO_PIN_SET : GPIO_PIN_RESET); // 0.1u
PIN(hv_temp) = r2temp(HV_R(ADC(adc_34_buf[0] >> 16))) * 0.01 + PIN(hv_temp) * 0.99; // 5.5u
PIN(mot_temp) = MOT_R(MOT_REF(ADC(adc_34_buf[3] >> 16))); // 1.4u
HAL_GPIO_WritePin(GPIOA, GPIO_PIN_8, PIN(led) > 0 ? GPIO_PIN_SET : GPIO_PIN_RESET); // 0.1u
}
hal_comp_t io_comp_struct = {
.name = "io",
.nrt = 0,
.rt = rt_func,
.frt = 0,
.nrt_init = nrt_init,
.rt_start = 0,
.frt_start = 0,
.rt_stop = 0,
.frt_stop = 0,
.ctx_size = sizeof(struct io_ctx_t),
.pin_count = sizeof(struct io_pin_ctx_t) / sizeof(struct hal_pin_inst_t),
.name = "io",
.nrt = 0,
.rt = rt_func,
.frt = 0,
.nrt_init = nrt_init,
.rt_start = 0,
.frt_start = 0,
.rt_stop = 0,
.frt_stop = 0,
.ctx_size = sizeof(struct io_ctx_t),
.pin_count = sizeof(struct io_pin_ctx_t) / sizeof(struct hal_pin_inst_t),
};

View File

@@ -10,7 +10,7 @@ extern CRC_HandleTypeDef hcrc;
HAL_COMP(ls);
//process data from LS
//process data from LS
HAL_PIN(d_cmd);
HAL_PIN(q_cmd);
HAL_PIN(pos);
@@ -54,12 +54,12 @@ HAL_PIN(dma_pos);
HAL_PIN(idle);
struct ls_ctx_t{
uint32_t timeout;
uint32_t tx_addr;
uint8_t send;
volatile packet_to_hv_t packet_to_hv;
volatile packet_from_hv_t packet_from_hv;
struct ls_ctx_t {
uint32_t timeout;
uint32_t tx_addr;
uint8_t send;
volatile packet_to_hv_t packet_to_hv;
volatile packet_from_hv_t packet_from_hv;
};
//TODO: move to ctx
@@ -69,217 +69,221 @@ struct ls_ctx_t{
f3_config_data_t config;
f3_state_data_t state;
static void hw_init(volatile void * ctx_ptr, volatile hal_pin_inst_t * pin_ptr){
struct ls_ctx_t * ctx = (struct ls_ctx_t *)ctx_ptr;
// struct ls_pin_ctx_t * pins = (struct ls_pin_ctx_t *)pin_ptr;
GPIO_InitTypeDef GPIO_InitStruct;
/* Peripheral clock enable */
__HAL_RCC_USART3_CLK_ENABLE();
UART_HandleTypeDef huart3;
huart3.Instance = USART3;
huart3.Init.BaudRate = DATABAUD;
huart3.Init.WordLength = UART_WORDLENGTH_8B;
huart3.Init.StopBits = UART_STOPBITS_1;
huart3.Init.Parity = UART_PARITY_NONE;
huart3.Init.Mode = UART_MODE_TX_RX;
huart3.Init.HwFlowCtl = UART_HWCONTROL_NONE;
huart3.Init.OverSampling = UART_OVERSAMPLING_8;
huart3.Init.OneBitSampling = UART_ONE_BIT_SAMPLE_DISABLE;
huart3.AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_NO_INIT;
USART3->CR3 |= USART_CR3_DMAT | USART_CR3_DMAR | USART_CR3_OVRDIS;
HAL_UART_Init(&huart3);
/**USART3 GPIO Configuration
static void hw_init(volatile void *ctx_ptr, volatile hal_pin_inst_t *pin_ptr) {
struct ls_ctx_t *ctx = (struct ls_ctx_t *)ctx_ptr;
// struct ls_pin_ctx_t * pins = (struct ls_pin_ctx_t *)pin_ptr;
GPIO_InitTypeDef GPIO_InitStruct;
/* Peripheral clock enable */
__HAL_RCC_USART3_CLK_ENABLE();
UART_HandleTypeDef huart3;
huart3.Instance = USART3;
huart3.Init.BaudRate = DATABAUD;
huart3.Init.WordLength = UART_WORDLENGTH_8B;
huart3.Init.StopBits = UART_STOPBITS_1;
huart3.Init.Parity = UART_PARITY_NONE;
huart3.Init.Mode = UART_MODE_TX_RX;
huart3.Init.HwFlowCtl = UART_HWCONTROL_NONE;
huart3.Init.OverSampling = UART_OVERSAMPLING_8;
huart3.Init.OneBitSampling = UART_ONE_BIT_SAMPLE_DISABLE;
huart3.AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_NO_INIT;
USART3->CR3 |= USART_CR3_DMAT | USART_CR3_DMAR | USART_CR3_OVRDIS;
HAL_UART_Init(&huart3);
/**USART3 GPIO Configuration
PB10 ------> USART3_TX
PB11 ------> USART3_RX
*/
GPIO_InitStruct.Pin = GPIO_PIN_10|GPIO_PIN_11;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_PULLUP;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF7_USART3;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
__HAL_RCC_DMA1_CLK_ENABLE();
//TX DMA
DMA1_Channel2->CCR &= (uint16_t)(~DMA_CCR_EN);
DMA1_Channel2->CPAR = (uint32_t)&(USART3->TDR);
DMA1_Channel2->CMAR = (uint32_t)&(ctx->packet_from_hv);
DMA1_Channel2->CNDTR = sizeof(packet_from_hv_t);
DMA1_Channel2->CCR = DMA_CCR_MINC | DMA_CCR_DIR;// | DMA_CCR_PL_0 | DMA_CCR_PL_1
DMA1->IFCR = DMA_IFCR_CTCIF2 | DMA_IFCR_CHTIF2 | DMA_IFCR_CGIF2;
//RX DMA
DMA1_Channel3->CCR &= (uint16_t)(~DMA_CCR_EN);
DMA1_Channel3->CPAR = (uint32_t)&(USART3->RDR);
DMA1_Channel3->CMAR = (uint32_t)&(ctx->packet_to_hv);
DMA1_Channel3->CNDTR = sizeof(packet_to_hv_t);
DMA1_Channel3->CCR = DMA_CCR_MINC;// | DMA_CCR_PL_0 | DMA_CCR_PL_1
DMA1->IFCR = DMA_IFCR_CTCIF3 | DMA_IFCR_CHTIF3 | DMA_IFCR_CGIF3;
DMA1_Channel3->CCR |= DMA_CCR_EN;
config.pins.r = 0.0;
config.pins.l = 0.0;
config.pins.psi = 0.0;
config.pins.cur_p = 0.0;
config.pins.cur_i = 0.0;
config.pins.cur_ff = 0.0;
config.pins.cur_ind = 0.0;
config.pins.max_y = 0.0;
config.pins.max_cur = 0.0;
USART3->RTOR = 16; // 16 bits timeout
USART3->CR2 |= USART_CR2_RTOEN; // timeout en
USART3->ICR |= USART_ICR_RTOCF; // timeout clear flag
GPIO_InitStruct.Pin = GPIO_PIN_10 | GPIO_PIN_11;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_PULLUP;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF7_USART3;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
__HAL_RCC_DMA1_CLK_ENABLE();
//TX DMA
DMA1_Channel2->CCR &= (uint16_t)(~DMA_CCR_EN);
DMA1_Channel2->CPAR = (uint32_t) & (USART3->TDR);
DMA1_Channel2->CMAR = (uint32_t) & (ctx->packet_from_hv);
DMA1_Channel2->CNDTR = sizeof(packet_from_hv_t);
DMA1_Channel2->CCR = DMA_CCR_MINC | DMA_CCR_DIR; // | DMA_CCR_PL_0 | DMA_CCR_PL_1
DMA1->IFCR = DMA_IFCR_CTCIF2 | DMA_IFCR_CHTIF2 | DMA_IFCR_CGIF2;
//RX DMA
DMA1_Channel3->CCR &= (uint16_t)(~DMA_CCR_EN);
DMA1_Channel3->CPAR = (uint32_t) & (USART3->RDR);
DMA1_Channel3->CMAR = (uint32_t) & (ctx->packet_to_hv);
DMA1_Channel3->CNDTR = sizeof(packet_to_hv_t);
DMA1_Channel3->CCR = DMA_CCR_MINC; // | DMA_CCR_PL_0 | DMA_CCR_PL_1
DMA1->IFCR = DMA_IFCR_CTCIF3 | DMA_IFCR_CHTIF3 | DMA_IFCR_CGIF3;
DMA1_Channel3->CCR |= DMA_CCR_EN;
config.pins.r = 0.0;
config.pins.l = 0.0;
config.pins.psi = 0.0;
config.pins.cur_p = 0.0;
config.pins.cur_i = 0.0;
config.pins.cur_ff = 0.0;
config.pins.cur_ind = 0.0;
config.pins.max_y = 0.0;
config.pins.max_cur = 0.0;
USART3->RTOR = 16; // 16 bits timeout
USART3->CR2 |= USART_CR2_RTOEN; // timeout en
USART3->ICR |= USART_ICR_RTOCF; // timeout clear flag
}
static void rt_start(volatile void * ctx_ptr, volatile hal_pin_inst_t * pin_ptr){
struct ls_ctx_t * ctx = (struct ls_ctx_t *)ctx_ptr;
struct ls_pin_ctx_t * pins = (struct ls_pin_ctx_t *)pin_ptr;
ctx->timeout = 0;
ctx->tx_addr = 0;
ctx->send = 0;
PIN(crc_error) = 0.0;
PIN(crc_ok) = 0.0;
PIN(timeout) = 0.0;
PIN(idle) = 0.0;
static void rt_start(volatile void *ctx_ptr, volatile hal_pin_inst_t *pin_ptr) {
struct ls_ctx_t *ctx = (struct ls_ctx_t *)ctx_ptr;
struct ls_pin_ctx_t *pins = (struct ls_pin_ctx_t *)pin_ptr;
ctx->timeout = 0;
ctx->tx_addr = 0;
ctx->send = 0;
PIN(crc_error) = 0.0;
PIN(crc_ok) = 0.0;
PIN(timeout) = 0.0;
PIN(idle) = 0.0;
}
static void rt_func(float period, volatile void * ctx_ptr, volatile hal_pin_inst_t * pin_ptr){
struct ls_ctx_t * ctx = (struct ls_ctx_t *)ctx_ptr;
struct ls_pin_ctx_t * pins = (struct ls_pin_ctx_t *)pin_ptr;
static void rt_func(float period, volatile void *ctx_ptr, volatile hal_pin_inst_t *pin_ptr) {
struct ls_ctx_t *ctx = (struct ls_ctx_t *)ctx_ptr;
struct ls_pin_ctx_t *pins = (struct ls_pin_ctx_t *)pin_ptr;
uint32_t dma_pos = sizeof(packet_to_hv_t) - DMA1_Channel3->CNDTR;
uint32_t dma_pos = sizeof(packet_to_hv_t) - DMA1_Channel3->CNDTR;
if(dma_pos == sizeof(packet_to_hv_t)){
uint32_t crc = HAL_CRC_Calculate(&hcrc, (uint32_t *) &(ctx->packet_to_hv), sizeof(packet_to_hv_t) / 4 - 1);
if(crc == ctx->packet_to_hv.crc){
PIN(en) = ctx->packet_to_hv.flags.enable;
PIN(phase_mode) = ctx->packet_to_hv.flags.phase_type;
PIN(cmd_mode) = ctx->packet_to_hv.flags.cmd_type;
PIN(d_cmd) = ctx->packet_to_hv.d_cmd;
PIN(q_cmd) = ctx->packet_to_hv.q_cmd;
PIN(pos) = ctx->packet_to_hv.pos;
PIN(vel) = ctx->packet_to_hv.vel;
uint8_t a = ctx->packet_to_hv.addr;
a = CLAMP(a, 0, sizeof(config) / 4);
config.data[a] = ctx->packet_to_hv.value; // TODO: first enable after complete update
if(dma_pos == sizeof(packet_to_hv_t)) {
uint32_t crc = HAL_CRC_Calculate(&hcrc, (uint32_t *)&(ctx->packet_to_hv), sizeof(packet_to_hv_t) / 4 - 1);
if(crc == ctx->packet_to_hv.crc) {
PIN(en) = ctx->packet_to_hv.flags.enable;
PIN(phase_mode) = ctx->packet_to_hv.flags.phase_type;
PIN(cmd_mode) = ctx->packet_to_hv.flags.cmd_type;
PIN(d_cmd) = ctx->packet_to_hv.d_cmd;
PIN(q_cmd) = ctx->packet_to_hv.q_cmd;
PIN(pos) = ctx->packet_to_hv.pos;
PIN(vel) = ctx->packet_to_hv.vel;
uint8_t a = ctx->packet_to_hv.addr;
a = CLAMP(a, 0, sizeof(config) / 4);
config.data[a] = ctx->packet_to_hv.value; // TODO: first enable after complete update
PIN(r) = config.pins.r;
PIN(l) = config.pins.l;
PIN(psi) = config.pins.psi;
PIN(cur_p) = config.pins.cur_p;
PIN(cur_i) = config.pins.cur_i;
PIN(cur_ff) = config.pins.cur_ff;
PIN(cur_ind) = config.pins.cur_ind;
PIN(max_y) = config.pins.max_y;
PIN(max_cur) = config.pins.max_cur;
ctx->timeout = 0;
PIN(crc_ok)++;
if(ctx->send == 0){
ctx->send = 1;
}
PIN(r) = config.pins.r;
PIN(l) = config.pins.l;
PIN(psi) = config.pins.psi;
PIN(cur_p) = config.pins.cur_p;
PIN(cur_i) = config.pins.cur_i;
PIN(cur_ff) = config.pins.cur_ff;
PIN(cur_ind) = config.pins.cur_ind;
PIN(max_y) = config.pins.max_y;
PIN(max_cur) = config.pins.max_cur;
ctx->timeout = 0;
PIN(crc_ok)
++;
if(ctx->send == 0) {
ctx->send = 1;
}
else{
PIN(crc_error)++;
}
}
if(USART3->ISR & USART_ISR_RTOF){ // idle line
USART3->ICR |= USART_ICR_RTOCF | USART_ICR_FECF | USART_ICR_ORECF; // timeout clear flag
GPIOA->BSRR |= GPIO_PIN_10;
} else {
PIN(crc_error)
++;
}
}
PIN(idle)++;
if(dma_pos != sizeof(packet_to_hv_t)){
PIN(dma_pos) = dma_pos;
}
if(USART3->ISR & USART_ISR_RTOF) { // idle line
USART3->ICR |= USART_ICR_RTOCF | USART_ICR_FECF | USART_ICR_ORECF; // timeout clear flag
GPIOA->BSRR |= GPIO_PIN_10;
// reset rx DMA
DMA1_Channel3->CCR &= (uint16_t)(~DMA_CCR_EN);
DMA1_Channel3->CNDTR = sizeof(packet_to_hv_t);
DMA1_Channel3->CCR |= DMA_CCR_EN;
dma_pos = 0;
GPIOA->BSRR |= GPIO_PIN_10 << 16;
PIN(idle)
++;
if(dma_pos != sizeof(packet_to_hv_t)) {
PIN(dma_pos) = dma_pos;
}
//ctx->send = 1;
}
// reset rx DMA
DMA1_Channel3->CCR &= (uint16_t)(~DMA_CCR_EN);
DMA1_Channel3->CNDTR = sizeof(packet_to_hv_t);
DMA1_Channel3->CCR |= DMA_CCR_EN;
dma_pos = 0;
GPIOA->BSRR |= GPIO_PIN_10 << 16;
if(ctx->send == 2){
ctx->send = 0;
}
if(ctx->send == 1 && dma_pos != 0){
ctx->send = 2;
//packet_to_hv.d_cmd = -99.0;
state.pins.u_fb = PIN(u_fb);
state.pins.v_fb = PIN(v_fb);
state.pins.w_fb = PIN(w_fb);
state.pins.hv_temp = PIN(hv_temp);
state.pins.mot_temp = PIN(mot_temp);
state.pins.core_temp = PIN(core_temp);
state.pins.fault = PIN(fault);
state.pins.y = PIN(y);
//ctx->send = 1;
}
// fill tx struct
ctx->packet_from_hv.dc_volt = PIN(dc_volt);
ctx->packet_from_hv.pwm_volt = PIN(pwm_volt);
ctx->packet_from_hv.d_fb = PIN(d_fb);
ctx->packet_from_hv.q_fb = PIN(q_fb);
ctx->packet_from_hv.addr = ctx->tx_addr;
ctx->packet_from_hv.value = state.data[ctx->tx_addr++];
ctx->tx_addr %= sizeof(state) / 4;
ctx->packet_from_hv.crc = HAL_CRC_Calculate(&hcrc, (uint32_t *) &(ctx->packet_from_hv), sizeof(packet_from_hv_t) / 4 - 1);
if(ctx->send == 2) {
ctx->send = 0;
}
if(ctx->send == 1 && dma_pos != 0) {
ctx->send = 2;
//packet_to_hv.d_cmd = -99.0;
state.pins.u_fb = PIN(u_fb);
state.pins.v_fb = PIN(v_fb);
state.pins.w_fb = PIN(w_fb);
state.pins.hv_temp = PIN(hv_temp);
state.pins.mot_temp = PIN(mot_temp);
state.pins.core_temp = PIN(core_temp);
state.pins.fault = PIN(fault);
state.pins.y = PIN(y);
// start tx DMA
DMA1_Channel2->CCR &= (uint16_t)(~DMA_CCR_EN);
DMA1_Channel2->CNDTR = sizeof(packet_from_hv_t);
DMA1_Channel2->CCR |= DMA_CCR_EN;
//ctx->send = 0;
}
// fill tx struct
ctx->packet_from_hv.dc_volt = PIN(dc_volt);
ctx->packet_from_hv.pwm_volt = PIN(pwm_volt);
ctx->packet_from_hv.d_fb = PIN(d_fb);
ctx->packet_from_hv.q_fb = PIN(q_fb);
ctx->packet_from_hv.addr = ctx->tx_addr;
ctx->packet_from_hv.value = state.data[ctx->tx_addr++];
ctx->tx_addr %= sizeof(state) / 4;
ctx->packet_from_hv.crc = HAL_CRC_Calculate(&hcrc, (uint32_t *)&(ctx->packet_from_hv), sizeof(packet_from_hv_t) / 4 - 1);
if(ctx->timeout > 5){//disable driver
PIN(en) = 0.0;
PIN(timeout)++;
}
ctx->timeout++;
// start tx DMA
DMA1_Channel2->CCR &= (uint16_t)(~DMA_CCR_EN);
DMA1_Channel2->CNDTR = sizeof(packet_from_hv_t);
DMA1_Channel2->CCR |= DMA_CCR_EN;
//ctx->send = 0;
}
// TODO: sin = 0.5
switch((uint16_t)PIN(phase_mode)){
case PHASE_90_3PH: // 90°
PIN(pwm_volt) = PIN(dc_volt) / M_SQRT2 * 0.95;
if(ctx->timeout > 5) { //disable driver
PIN(en) = 0.0;
PIN(timeout)
++;
}
ctx->timeout++;
// TODO: sin = 0.5
switch((uint16_t)PIN(phase_mode)) {
case PHASE_90_3PH: // 90°
PIN(pwm_volt) = PIN(dc_volt) / M_SQRT2 * 0.95;
break;
case PHASE_90_4PH: // 90°
PIN(pwm_volt) = PIN(dc_volt) * 0.95;
case PHASE_90_4PH: // 90°
PIN(pwm_volt) = PIN(dc_volt) * 0.95;
break;
case PHASE_120_3PH: // 120°
PIN(pwm_volt) = PIN(dc_volt) / M_SQRT3 * 0.95;
case PHASE_120_3PH: // 120°
PIN(pwm_volt) = PIN(dc_volt) / M_SQRT3 * 0.95;
break;
case PHASE_180_2PH: // 180°
case PHASE_180_3PH: // 180°
PIN(pwm_volt) = PIN(dc_volt) * 0.95;
case PHASE_180_2PH: // 180°
case PHASE_180_3PH: // 180°
PIN(pwm_volt) = PIN(dc_volt) * 0.95;
break;
default:
PIN(pwm_volt) = 0.0;
}
default:
PIN(pwm_volt) = 0.0;
}
}
hal_comp_t ls_comp_struct = {
.name = "ls",
.nrt = 0,
.rt = rt_func,
.frt = 0,
.hw_init = hw_init,
.rt_start = rt_start,
.frt_start = 0,
.rt_stop = 0,
.frt_stop = 0,
.ctx_size = sizeof(struct ls_ctx_t),
.pin_count = sizeof(struct ls_pin_ctx_t) / sizeof(struct hal_pin_inst_t),
.name = "ls",
.nrt = 0,
.rt = rt_func,
.frt = 0,
.hw_init = hw_init,
.rt_start = rt_start,
.frt_start = 0,
.rt_stop = 0,
.frt_stop = 0,
.ctx_size = sizeof(struct ls_ctx_t),
.pin_count = sizeof(struct ls_pin_ctx_t) / sizeof(struct hal_pin_inst_t),
};

View File

@@ -52,76 +52,65 @@
DAC_HandleTypeDef hdac;
/* DAC init function */
void MX_DAC_Init(void)
{
void MX_DAC_Init(void) {
DAC_ChannelConfTypeDef sConfig;
/**DAC Initialization
/**DAC Initialization
*/
hdac.Instance = DAC;
if (HAL_DAC_Init(&hdac) != HAL_OK)
{
if(HAL_DAC_Init(&hdac) != HAL_OK) {
Error_Handler();
}
/**DAC channel OUT1 config
/**DAC channel OUT1 config
*/
sConfig.DAC_Trigger = DAC_TRIGGER_NONE;
sConfig.DAC_Trigger = DAC_TRIGGER_NONE;
sConfig.DAC_OutputBuffer = DAC_OUTPUTBUFFER_ENABLE;
if (HAL_DAC_ConfigChannel(&hdac, &sConfig, DAC_CHANNEL_1) != HAL_OK)
{
if(HAL_DAC_ConfigChannel(&hdac, &sConfig, DAC_CHANNEL_1) != HAL_OK) {
Error_Handler();
}
}
void HAL_DAC_MspInit(DAC_HandleTypeDef* dacHandle)
{
void HAL_DAC_MspInit(DAC_HandleTypeDef *dacHandle) {
GPIO_InitTypeDef GPIO_InitStruct;
if(dacHandle->Instance==DAC)
{
/* USER CODE BEGIN DAC_MspInit 0 */
if(dacHandle->Instance == DAC) {
/* USER CODE BEGIN DAC_MspInit 0 */
/* USER CODE END DAC_MspInit 0 */
/* USER CODE END DAC_MspInit 0 */
/* Peripheral clock enable */
__HAL_RCC_DAC1_CLK_ENABLE();
/**DAC GPIO Configuration
PA4 ------> DAC_OUT1
*/
GPIO_InitStruct.Pin = GPIO_PIN_4;
GPIO_InitStruct.Pin = GPIO_PIN_4;
GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
/* USER CODE BEGIN DAC_MspInit 1 */
/* USER CODE BEGIN DAC_MspInit 1 */
/* USER CODE END DAC_MspInit 1 */
/* USER CODE END DAC_MspInit 1 */
}
}
void HAL_DAC_MspDeInit(DAC_HandleTypeDef* dacHandle)
{
void HAL_DAC_MspDeInit(DAC_HandleTypeDef *dacHandle) {
if(dacHandle->Instance == DAC) {
/* USER CODE BEGIN DAC_MspDeInit 0 */
if(dacHandle->Instance==DAC)
{
/* USER CODE BEGIN DAC_MspDeInit 0 */
/* USER CODE END DAC_MspDeInit 0 */
/* USER CODE END DAC_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_DAC1_CLK_DISABLE();
/**DAC GPIO Configuration
PA4 ------> DAC_OUT1
*/
HAL_GPIO_DeInit(GPIOA, GPIO_PIN_4);
}
/* USER CODE BEGIN DAC_MspDeInit 1 */
/* USER CODE END DAC_MspDeInit 1 */
}
}
/* USER CODE BEGIN 1 */

View File

@@ -76,16 +76,16 @@ CRC_HandleTypeDef hcrc;
// // TIM_ITConfig(TIM2, TIM_IT_Update, DISABLE);
// }
uint32_t hal_get_systick_value(){
return(SysTick->VAL);
uint32_t hal_get_systick_value() {
return (SysTick->VAL);
}
uint32_t hal_get_systick_reload(){
return(SysTick->LOAD);
uint32_t hal_get_systick_reload() {
return (SysTick->LOAD);
}
uint32_t hal_get_systick_freq(){
return(systick_freq);
uint32_t hal_get_systick_freq() {
return (systick_freq);
}
/* USER CODE END PV */
@@ -102,36 +102,34 @@ void Error_Handler(void);
/* USER CODE BEGIN 0 */
void TIM8_UP_IRQHandler(){
GPIOA->BSRR |= GPIO_PIN_9;
__HAL_TIM_CLEAR_IT(&htim8, TIM_IT_UPDATE);
hal_run_rt();
if(__HAL_TIM_GET_FLAG(&htim8, TIM_IT_UPDATE) == SET){
hal_stop();
hal.hal_state = RT_TOO_LONG;
}
GPIOA->BSRR |= GPIO_PIN_9 << 16;
void TIM8_UP_IRQHandler() {
GPIOA->BSRR |= GPIO_PIN_9;
__HAL_TIM_CLEAR_IT(&htim8, TIM_IT_UPDATE);
hal_run_rt();
if(__HAL_TIM_GET_FLAG(&htim8, TIM_IT_UPDATE) == SET) {
hal_stop();
hal.hal_state = RT_TOO_LONG;
}
GPIOA->BSRR |= GPIO_PIN_9 << 16;
}
void bootloader(char * ptr){
#ifdef USB_DISCONNECT_PIN
void bootloader(char *ptr) {
#ifdef USB_DISCONNECT_PIN
HAL_GPIO_WritePin(USB_DISCONNECT_PORT, USB_DISCONNECT_PIN, GPIO_PIN_SET);
HAL_Delay(100);
#endif
#endif
RTC->BKP0R = 0xDEADBEEF;
NVIC_SystemReset();
}
COMMAND("bootloader", bootloader, "enter bootloader");
void reset(char * ptr){
HAL_NVIC_SystemReset();
void reset(char *ptr) {
HAL_NVIC_SystemReset();
}
COMMAND("reset", reset, "reset STMBL");
int main(void)
{
int main(void) {
/* USER CODE BEGIN 1 */
SCB->VTOR = 0x8004000;
/* USER CODE END 1 */
@@ -149,18 +147,18 @@ int main(void)
__HAL_RCC_GPIOB_CLK_ENABLE();
__HAL_RCC_GPIOC_CLK_ENABLE();
__HAL_RCC_GPIOF_CLK_ENABLE();
GPIO_InitTypeDef GPIO_InitStruct;
#ifdef USB_DISCONNECT_PIN
GPIO_InitStruct.Pin = USB_DISCONNECT_PIN;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
HAL_GPIO_Init(USB_DISCONNECT_PORT, &GPIO_InitStruct);
HAL_GPIO_WritePin(USB_DISCONNECT_PORT, USB_DISCONNECT_PIN, GPIO_PIN_RESET);
#endif
#ifdef USB_DISCONNECT_PIN
GPIO_InitStruct.Pin = USB_DISCONNECT_PIN;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
HAL_GPIO_Init(USB_DISCONNECT_PORT, &GPIO_InitStruct);
HAL_GPIO_WritePin(USB_DISCONNECT_PORT, USB_DISCONNECT_PIN, GPIO_PIN_RESET);
#endif
MX_TIM8_Init();
MX_ADC1_Init();
MX_ADC2_Init();
@@ -172,11 +170,11 @@ int main(void)
MX_OPAMP3_Init();
// MX_USART1_UART_Init();
MX_USB_DEVICE_Init();
#ifdef USB_CONNECT_PIN
GPIO_InitStruct.Pin = USB_CONNECT_PIN;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Pin = USB_CONNECT_PIN;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
HAL_GPIO_Init(USB_CONNECT_PORT, &GPIO_InitStruct);
HAL_GPIO_WritePin(USB_CONNECT_PORT, USB_CONNECT_PIN, GPIO_PIN_SET);
@@ -195,69 +193,68 @@ int main(void)
HAL_OPAMP_SelfCalibrate(&hopamp1);
HAL_OPAMP_SelfCalibrate(&hopamp2);
HAL_OPAMP_SelfCalibrate(&hopamp3);
hcrc.Instance = CRC;
hcrc.Init.DefaultPolynomialUse = DEFAULT_POLYNOMIAL_ENABLE;
hcrc.Init.DefaultInitValueUse = DEFAULT_INIT_VALUE_ENABLE;
hcrc.Init.InputDataInversionMode = CRC_INPUTDATA_INVERSION_NONE;
hcrc.Instance = CRC;
hcrc.Init.DefaultPolynomialUse = DEFAULT_POLYNOMIAL_ENABLE;
hcrc.Init.DefaultInitValueUse = DEFAULT_INIT_VALUE_ENABLE;
hcrc.Init.InputDataInversionMode = CRC_INPUTDATA_INVERSION_NONE;
hcrc.Init.OutputDataInversionMode = CRC_OUTPUTDATA_INVERSION_DISABLE;
hcrc.InputDataFormat = CRC_INPUTDATA_FORMAT_WORDS;
hcrc.InputDataFormat = CRC_INPUTDATA_FORMAT_WORDS;
__HAL_RCC_CRC_CLK_ENABLE();
if (HAL_CRC_Init(&hcrc) != HAL_OK)
{
if(HAL_CRC_Init(&hcrc) != HAL_OK) {
Error_Handler();
}
//IO pins
GPIO_InitStruct.Pin = GPIO_PIN_9 | GPIO_PIN_10;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Pin = GPIO_PIN_9 | GPIO_PIN_10;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
if (HAL_OPAMP_Start(&hopamp1) != HAL_OK){
Error_Handler();
}
if (HAL_OPAMP_Start(&hopamp2) != HAL_OK){
Error_Handler();
}
if (HAL_OPAMP_Start(&hopamp3) != HAL_OK){
Error_Handler();
}
if(HAL_OPAMP_Start(&hopamp1) != HAL_OK) {
Error_Handler();
}
if(HAL_OPAMP_Start(&hopamp2) != HAL_OK) {
Error_Handler();
}
if(HAL_OPAMP_Start(&hopamp3) != HAL_OK) {
Error_Handler();
}
htim8.Instance->CCR1 = 0;
htim8.Instance->CCR2 = 0;
htim8.Instance->CCR3 = 0;
HAL_ADC_Start(&hadc1);
HAL_ADC_Start(&hadc2);
HAL_ADC_Start(&hadc3);
HAL_ADC_Start(&hadc4);
if (HAL_TIM_Base_Start_IT(&htim8) != HAL_OK){
Error_Handler();
if(HAL_TIM_Base_Start_IT(&htim8) != HAL_OK) {
Error_Handler();
}
#ifndef PWM_INVERT
TIM8->RCR = 1;//uptate event foo
TIM8->RCR = 1; //uptate event foo
#endif
if (HAL_TIM_PWM_Start(&htim8, TIM_CHANNEL_1) != HAL_OK){
Error_Handler();
if(HAL_TIM_PWM_Start(&htim8, TIM_CHANNEL_1) != HAL_OK) {
Error_Handler();
}
if (HAL_TIM_PWM_Start(&htim8, TIM_CHANNEL_2) != HAL_OK){
Error_Handler();
if(HAL_TIM_PWM_Start(&htim8, TIM_CHANNEL_2) != HAL_OK) {
Error_Handler();
}
if (HAL_TIM_PWM_Start(&htim8, TIM_CHANNEL_3) != HAL_OK){
Error_Handler();
if(HAL_TIM_PWM_Start(&htim8, TIM_CHANNEL_3) != HAL_OK) {
Error_Handler();
}
if (HAL_TIMEx_PWMN_Start(&htim8, TIM_CHANNEL_1) != HAL_OK){
Error_Handler();
if(HAL_TIMEx_PWMN_Start(&htim8, TIM_CHANNEL_1) != HAL_OK) {
Error_Handler();
}
if (HAL_TIMEx_PWMN_Start(&htim8, TIM_CHANNEL_2) != HAL_OK){
Error_Handler();
if(HAL_TIMEx_PWMN_Start(&htim8, TIM_CHANNEL_2) != HAL_OK) {
Error_Handler();
}
if (HAL_TIMEx_PWMN_Start(&htim8, TIM_CHANNEL_3) != HAL_OK){
Error_Handler();
if(HAL_TIMEx_PWMN_Start(&htim8, TIM_CHANNEL_3) != HAL_OK) {
Error_Handler();
}
hal_init(1.0 / 15000.0, 0.0);
@@ -271,7 +268,7 @@ int main(void)
load_comp(comp_by_name("svm"));
load_comp(comp_by_name("hv"));
load_comp(comp_by_name("curpid"));
hal_parse("term0.rt_prio = 0.1");
hal_parse("ls0.rt_prio = 0.6");
hal_parse("io0.rt_prio = 1.0");
@@ -280,7 +277,7 @@ int main(void)
hal_parse("idq0.rt_prio = 4.0");
hal_parse("svm0.rt_prio = 5.0");
hal_parse("hv0.rt_prio = 6.0");
hal_parse("term0.send_step = 100.0");
hal_parse("term0.gain0 = 10.0");
hal_parse("term0.gain1 = 10.0");
@@ -302,19 +299,19 @@ int main(void)
hal_parse("dq0.pos = ls0.pos");
hal_parse("dq0.mode = ls0.phase_mode");
hal_parse("hv0.en = ls0.en");
//ADC TEST
hal_parse("term0.wave3 = io0.udc");
hal_parse("hv0.udc = io0.udc");
hal_parse("dq0.u = io0.iu");
hal_parse("dq0.v = io0.iv");
hal_parse("dq0.w = io0.iw");
hal_parse("svm0.u = idq0.u");
hal_parse("svm0.v = idq0.v");
hal_parse("svm0.w = idq0.w");
hal_parse("hv0.u = svm0.su");
hal_parse("hv0.v = svm0.sv");
hal_parse("hv0.w = svm0.sw");
hal_parse("svm0.udc = io0.udc");
@@ -352,74 +349,64 @@ int main(void)
// hal_init_nrt();
// error foo
hal_start();
while (1)
{
hal_run_nrt();
cdc_poll();
HAL_Delay(1);
}
while(1) {
hal_run_nrt();
cdc_poll();
HAL_Delay(1);
}
}
/** System Clock Configuration
*/
void SystemClock_Config(void)
{
void SystemClock_Config(void) {
RCC_OscInitTypeDef RCC_OscInitStruct;
RCC_ClkInitTypeDef RCC_ClkInitStruct;
RCC_PeriphCLKInitTypeDef PeriphClkInit;
/**Initializes the CPU, AHB and APB busses clocks
/**Initializes the CPU, AHB and APB busses clocks
*/
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
RCC_OscInitStruct.HSEState = RCC_HSE_ON;
RCC_OscInitStruct.HSEState = RCC_HSE_ON;
RCC_OscInitStruct.HSEPredivValue = RCC_HSE_PREDIV_DIV1;
RCC_OscInitStruct.HSIState = RCC_HSI_ON;
RCC_OscInitStruct.LSIState = RCC_LSI_ON;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
RCC_OscInitStruct.PLL.PLLMUL = RCC_PLL_MUL9;
if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)
{
RCC_OscInitStruct.HSIState = RCC_HSI_ON;
RCC_OscInitStruct.LSIState = RCC_LSI_ON;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
RCC_OscInitStruct.PLL.PLLMUL = RCC_PLL_MUL9;
if(HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) {
Error_Handler();
}
/**Initializes the CPU, AHB and APB busses clocks
/**Initializes the CPU, AHB and APB busses clocks
*/
RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK
|RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2;
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2;
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2;
RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1;
if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2) != HAL_OK)
{
if(HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2) != HAL_OK) {
Error_Handler();
}
PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USB|RCC_PERIPHCLK_USART1
|RCC_PERIPHCLK_USART3|RCC_PERIPHCLK_TIM8
|RCC_PERIPHCLK_ADC12|RCC_PERIPHCLK_ADC34|RCC_PERIPHCLK_RTC;
PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USB | RCC_PERIPHCLK_USART1 | RCC_PERIPHCLK_USART3 | RCC_PERIPHCLK_TIM8 | RCC_PERIPHCLK_ADC12 | RCC_PERIPHCLK_ADC34 | RCC_PERIPHCLK_RTC;
PeriphClkInit.Usart1ClockSelection = RCC_USART1CLKSOURCE_PCLK2;
PeriphClkInit.Usart3ClockSelection = RCC_USART3CLKSOURCE_SYSCLK;
PeriphClkInit.Adc12ClockSelection = RCC_ADC12PLLCLK_DIV1;
PeriphClkInit.Adc34ClockSelection = RCC_ADC34PLLCLK_DIV1;
PeriphClkInit.USBClockSelection = RCC_USBCLKSOURCE_PLL_DIV1_5;
PeriphClkInit.Tim8ClockSelection = RCC_TIM8CLK_PLLCLK;
PeriphClkInit.RTCClockSelection = RCC_RTCCLKSOURCE_LSI;
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK)
{
PeriphClkInit.Adc12ClockSelection = RCC_ADC12PLLCLK_DIV1;
PeriphClkInit.Adc34ClockSelection = RCC_ADC34PLLCLK_DIV1;
PeriphClkInit.USBClockSelection = RCC_USBCLKSOURCE_PLL_DIV1_5;
PeriphClkInit.Tim8ClockSelection = RCC_TIM8CLK_PLLCLK;
PeriphClkInit.RTCClockSelection = RCC_RTCCLKSOURCE_LSI;
if(HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK) {
Error_Handler();
}
/**Configure the Systick interrupt time
/**Configure the Systick interrupt time
*/
HAL_SYSTICK_Config(HAL_RCC_GetHCLKFreq()/1000);
HAL_SYSTICK_Config(HAL_RCC_GetHCLKFreq() / 1000);
/**Configure the Systick
/**Configure the Systick
*/
HAL_SYSTICK_CLKSourceConfig(SYSTICK_CLKSOURCE_HCLK);
@@ -430,8 +417,8 @@ void SystemClock_Config(void)
/* USER CODE BEGIN 4 */
//Delay implementation for hal_term.c
void Wait(uint32_t ms){
HAL_Delay(ms);
void Wait(uint32_t ms) {
HAL_Delay(ms);
}
/* USER CODE END 4 */
@@ -441,15 +428,13 @@ void Wait(uint32_t ms){
* @param None
* @retval None
*/
void Error_Handler(void)
{
void Error_Handler(void) {
/* USER CODE BEGIN Error_Handler */
/* User can add his own implementation to report the HAL error return state */
while(1)
{
HAL_GPIO_WritePin(GPIOA, GPIO_PIN_8, GPIO_PIN_SET);
while(1) {
HAL_GPIO_WritePin(GPIOA, GPIO_PIN_8, GPIO_PIN_SET);
}
/* USER CODE END Error_Handler */
/* USER CODE END Error_Handler */
}
#ifdef USE_FULL_ASSERT
@@ -461,23 +446,21 @@ void Error_Handler(void)
* @param line: assert_param error line source number
* @retval None
*/
void assert_failed(uint8_t* file, uint32_t line)
{
void assert_failed(uint8_t *file, uint32_t line) {
/* USER CODE BEGIN 6 */
/* User can add his own implementation to report the file name and line number,
ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
/* USER CODE END 6 */
}
#endif
/**
* @}
*/
*/
/**
* @}
*/
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -54,172 +54,146 @@ OPAMP_HandleTypeDef hopamp2;
OPAMP_HandleTypeDef hopamp3;
/* OPAMP1 init function */
void MX_OPAMP1_Init(void)
{
hopamp1.Instance = OPAMP1;
hopamp1.Init.Mode = OPAMP_PGA_MODE;
hopamp1.Init.NonInvertingInput = OPAMP_NONINVERTINGINPUT_IO0;
void MX_OPAMP1_Init(void) {
hopamp1.Instance = OPAMP1;
hopamp1.Init.Mode = OPAMP_PGA_MODE;
hopamp1.Init.NonInvertingInput = OPAMP_NONINVERTINGINPUT_IO0;
hopamp1.Init.TimerControlledMuxmode = OPAMP_TIMERCONTROLLEDMUXMODE_DISABLE;
hopamp1.Init.PgaConnect = OPAMP_PGA_CONNECT_INVERTINGINPUT_NO;
hopamp1.Init.PgaGain = OPAMP_PGA_GAIN_16;
hopamp1.Init.UserTrimming = OPAMP_TRIMMING_FACTORY;
if (HAL_OPAMP_Init(&hopamp1) != HAL_OK)
{
hopamp1.Init.PgaConnect = OPAMP_PGA_CONNECT_INVERTINGINPUT_NO;
hopamp1.Init.PgaGain = OPAMP_PGA_GAIN_16;
hopamp1.Init.UserTrimming = OPAMP_TRIMMING_FACTORY;
if(HAL_OPAMP_Init(&hopamp1) != HAL_OK) {
Error_Handler();
}
}
/* OPAMP2 init function */
void MX_OPAMP2_Init(void)
{
hopamp2.Instance = OPAMP2;
hopamp2.Init.Mode = OPAMP_PGA_MODE;
hopamp2.Init.NonInvertingInput = OPAMP_NONINVERTINGINPUT_IO0;
void MX_OPAMP2_Init(void) {
hopamp2.Instance = OPAMP2;
hopamp2.Init.Mode = OPAMP_PGA_MODE;
hopamp2.Init.NonInvertingInput = OPAMP_NONINVERTINGINPUT_IO0;
hopamp2.Init.TimerControlledMuxmode = OPAMP_TIMERCONTROLLEDMUXMODE_DISABLE;
hopamp2.Init.PgaConnect = OPAMP_PGA_CONNECT_INVERTINGINPUT_NO;
hopamp2.Init.PgaGain = OPAMP_PGA_GAIN_16;
hopamp2.Init.UserTrimming = OPAMP_TRIMMING_FACTORY;
if (HAL_OPAMP_Init(&hopamp2) != HAL_OK)
{
hopamp2.Init.PgaConnect = OPAMP_PGA_CONNECT_INVERTINGINPUT_NO;
hopamp2.Init.PgaGain = OPAMP_PGA_GAIN_16;
hopamp2.Init.UserTrimming = OPAMP_TRIMMING_FACTORY;
if(HAL_OPAMP_Init(&hopamp2) != HAL_OK) {
Error_Handler();
}
}
/* OPAMP3 init function */
void MX_OPAMP3_Init(void)
{
hopamp3.Instance = OPAMP3;
hopamp3.Init.Mode = OPAMP_PGA_MODE;
hopamp3.Init.NonInvertingInput = OPAMP_NONINVERTINGINPUT_IO0;
void MX_OPAMP3_Init(void) {
hopamp3.Instance = OPAMP3;
hopamp3.Init.Mode = OPAMP_PGA_MODE;
hopamp3.Init.NonInvertingInput = OPAMP_NONINVERTINGINPUT_IO0;
hopamp3.Init.TimerControlledMuxmode = OPAMP_TIMERCONTROLLEDMUXMODE_DISABLE;
hopamp3.Init.PgaConnect = OPAMP_PGA_CONNECT_INVERTINGINPUT_NO;
hopamp3.Init.PgaGain = OPAMP_PGA_GAIN_16;
hopamp3.Init.UserTrimming = OPAMP_TRIMMING_FACTORY;
if (HAL_OPAMP_Init(&hopamp3) != HAL_OK)
{
hopamp3.Init.PgaConnect = OPAMP_PGA_CONNECT_INVERTINGINPUT_NO;
hopamp3.Init.PgaGain = OPAMP_PGA_GAIN_16;
hopamp3.Init.UserTrimming = OPAMP_TRIMMING_FACTORY;
if(HAL_OPAMP_Init(&hopamp3) != HAL_OK) {
Error_Handler();
}
}
void HAL_OPAMP_MspInit(OPAMP_HandleTypeDef* opampHandle)
{
void HAL_OPAMP_MspInit(OPAMP_HandleTypeDef *opampHandle) {
GPIO_InitTypeDef GPIO_InitStruct;
if(opampHandle->Instance==OPAMP1)
{
/* USER CODE BEGIN OPAMP1_MspInit 0 */
if(opampHandle->Instance == OPAMP1) {
/* USER CODE BEGIN OPAMP1_MspInit 0 */
/* USER CODE END OPAMP1_MspInit 0 */
/* USER CODE END OPAMP1_MspInit 0 */
/**OPAMP1 GPIO Configuration
PA1 ------> OPAMP1_VINP
PA2 ------> OPAMP1_VOUT
*/
GPIO_InitStruct.Pin = GPIO_PIN_1 | GPIO_PIN_2;
GPIO_InitStruct.Pin = GPIO_PIN_1 | GPIO_PIN_2;
GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
/* USER CODE BEGIN OPAMP1_MspInit 1 */
/* USER CODE BEGIN OPAMP1_MspInit 1 */
/* USER CODE END OPAMP1_MspInit 1 */
}
else if(opampHandle->Instance==OPAMP2)
{
/* USER CODE BEGIN OPAMP2_MspInit 0 */
/* USER CODE END OPAMP1_MspInit 1 */
} else if(opampHandle->Instance == OPAMP2) {
/* USER CODE BEGIN OPAMP2_MspInit 0 */
/* USER CODE END OPAMP2_MspInit 0 */
/* USER CODE END OPAMP2_MspInit 0 */
/**OPAMP2 GPIO Configuration
PA6 ------> OPAMP2_VOUT
PA7 ------> OPAMP2_VINP
*/
GPIO_InitStruct.Pin = GPIO_PIN_6 | GPIO_PIN_7;
GPIO_InitStruct.Pin = GPIO_PIN_6 | GPIO_PIN_7;
GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
/* USER CODE BEGIN OPAMP2_MspInit 1 */
/* USER CODE BEGIN OPAMP2_MspInit 1 */
/* USER CODE END OPAMP2_MspInit 1 */
}
else if(opampHandle->Instance==OPAMP3)
{
/* USER CODE BEGIN OPAMP3_MspInit 0 */
/* USER CODE END OPAMP2_MspInit 1 */
} else if(opampHandle->Instance == OPAMP3) {
/* USER CODE BEGIN OPAMP3_MspInit 0 */
/* USER CODE END OPAMP3_MspInit 0 */
/* USER CODE END OPAMP3_MspInit 0 */
/**OPAMP3 GPIO Configuration
PB0 ------> OPAMP3_VINP
PB1 ------> OPAMP3_VOUT
*/
GPIO_InitStruct.Pin = GPIO_PIN_0 | GPIO_PIN_1;
GPIO_InitStruct.Pin = GPIO_PIN_0 | GPIO_PIN_1;
GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
/* USER CODE BEGIN OPAMP3_MspInit 1 */
/* USER CODE BEGIN OPAMP3_MspInit 1 */
/* USER CODE END OPAMP3_MspInit 1 */
/* USER CODE END OPAMP3_MspInit 1 */
}
}
void HAL_OPAMP_MspDeInit(OPAMP_HandleTypeDef* opampHandle)
{
void HAL_OPAMP_MspDeInit(OPAMP_HandleTypeDef *opampHandle) {
if(opampHandle->Instance == OPAMP1) {
/* USER CODE BEGIN OPAMP1_MspDeInit 0 */
if(opampHandle->Instance==OPAMP1)
{
/* USER CODE BEGIN OPAMP1_MspDeInit 0 */
/* USER CODE END OPAMP1_MspDeInit 0 */
/* USER CODE END OPAMP1_MspDeInit 0 */
/**OPAMP1 GPIO Configuration
PA1 ------> OPAMP1_VINP
PA2 ------> OPAMP1_VOUT
*/
HAL_GPIO_DeInit(GPIOA, GPIO_PIN_1 | GPIO_PIN_2);
/* USER CODE BEGIN OPAMP1_MspDeInit 1 */
/* USER CODE BEGIN OPAMP1_MspDeInit 1 */
/* USER CODE END OPAMP1_MspDeInit 1 */
}
else if(opampHandle->Instance==OPAMP2)
{
/* USER CODE BEGIN OPAMP2_MspDeInit 0 */
/* USER CODE END OPAMP1_MspDeInit 1 */
} else if(opampHandle->Instance == OPAMP2) {
/* USER CODE BEGIN OPAMP2_MspDeInit 0 */
/* USER CODE END OPAMP2_MspDeInit 0 */
/* USER CODE END OPAMP2_MspDeInit 0 */
/**OPAMP2 GPIO Configuration
PA6 ------> OPAMP2_VOUT
PA7 ------> OPAMP2_VINP
*/
HAL_GPIO_DeInit(GPIOA, GPIO_PIN_6 | GPIO_PIN_7);
/* USER CODE BEGIN OPAMP2_MspDeInit 1 */
/* USER CODE BEGIN OPAMP2_MspDeInit 1 */
/* USER CODE END OPAMP2_MspDeInit 1 */
}
else if(opampHandle->Instance==OPAMP3)
{
/* USER CODE BEGIN OPAMP3_MspDeInit 0 */
/* USER CODE END OPAMP2_MspDeInit 1 */
} else if(opampHandle->Instance == OPAMP3) {
/* USER CODE BEGIN OPAMP3_MspDeInit 0 */
/* USER CODE END OPAMP3_MspDeInit 0 */
/* USER CODE END OPAMP3_MspDeInit 0 */
/**OPAMP3 GPIO Configuration
PB0 ------> OPAMP3_VINP
PB1 ------> OPAMP3_VOUT
*/
HAL_GPIO_DeInit(GPIOB, GPIO_PIN_0 | GPIO_PIN_1);
/* USER CODE BEGIN OPAMP3_MspDeInit 1 */
/* USER CODE BEGIN OPAMP3_MspDeInit 1 */
/* USER CODE END OPAMP3_MspDeInit 1 */
/* USER CODE END OPAMP3_MspDeInit 1 */
}
}
}
/* USER CODE BEGIN 1 */

View File

@@ -51,8 +51,7 @@ extern void Error_Handler(void);
/**
* Initializes the Global MSP.
*/
void HAL_MspInit(void)
{
void HAL_MspInit(void) {
/* USER CODE BEGIN MspInit 0 */
/* USER CODE END MspInit 0 */

View File

@@ -43,14 +43,13 @@
/* External variables --------------------------------------------------------*/
extern PCD_HandleTypeDef hpcd_USB_FS;
/******************************************************************************/
/* Cortex-M4 Processor Interruption and Exception Handlers */
/* Cortex-M4 Processor Interruption and Exception Handlers */
/******************************************************************************/
/**
* @brief This function handles Non maskable interrupt.
*/
void NMI_Handler(void)
{
void NMI_Handler(void) {
/* USER CODE BEGIN NonMaskableInt_IRQn 0 */
hal_error(NMI);
/* USER CODE END NonMaskableInt_IRQn 0 */
@@ -62,8 +61,7 @@ void NMI_Handler(void)
/**
* @brief This function handles Hard fault interrupt.
*/
void HardFault_Handler(void)
{
void HardFault_Handler(void) {
/* USER CODE BEGIN HardFault_IRQn 0 */
/* USER CODE END HardFault_IRQn 0 */
@@ -76,8 +74,7 @@ void HardFault_Handler(void)
/**
* @brief This function handles Memory management fault.
*/
void MemManage_Handler(void)
{
void MemManage_Handler(void) {
/* USER CODE BEGIN MemoryManagement_IRQn 0 */
/* USER CODE END MemoryManagement_IRQn 0 */
@@ -90,8 +87,7 @@ void MemManage_Handler(void)
/**
* @brief This function handles Pre-fetch fault, memory access fault.
*/
void BusFault_Handler(void)
{
void BusFault_Handler(void) {
/* USER CODE BEGIN BusFault_IRQn 0 */
/* USER CODE END BusFault_IRQn 0 */
@@ -104,8 +100,7 @@ void BusFault_Handler(void)
/**
* @brief This function handles Undefined instruction or illegal state.
*/
void UsageFault_Handler(void)
{
void UsageFault_Handler(void) {
/* USER CODE BEGIN UsageFault_IRQn 0 */
/* USER CODE END UsageFault_IRQn 0 */
@@ -118,8 +113,7 @@ void UsageFault_Handler(void)
/**
* @brief This function handles Debug monitor.
*/
void DebugMon_Handler(void)
{
void DebugMon_Handler(void) {
/* USER CODE BEGIN DebugMonitor_IRQn 0 */
/* USER CODE END DebugMonitor_IRQn 0 */
@@ -131,8 +125,7 @@ void DebugMon_Handler(void)
/**
* @brief This function handles System tick timer.
*/
void SysTick_Handler(void)
{
void SysTick_Handler(void) {
/* USER CODE BEGIN SysTick_IRQn 0 */
/* USER CODE END SysTick_IRQn 0 */
@@ -153,15 +146,14 @@ void SysTick_Handler(void)
/**
* @brief This function handles USB low priority or CAN_RX0 interrupts.
*/
void USB_LP_CAN_RX0_IRQHandler(void)
{
void USB_LP_CAN_RX0_IRQHandler(void) {
/* USER CODE BEGIN USB_LP_CAN_RX0_IRQn 0 */
//GPIOA->BSRR |= GPIO_PIN_10;
//GPIOA->BSRR |= GPIO_PIN_10;
/* USER CODE END USB_LP_CAN_RX0_IRQn 0 */
HAL_PCD_IRQHandler(&hpcd_USB_FS);
/* USER CODE BEGIN USB_LP_CAN_RX0_IRQn 1 */
//GPIOA->BSRR |= GPIO_PIN_10 << 16;
//GPIOA->BSRR |= GPIO_PIN_10 << 16;
/* USER CODE END USB_LP_CAN_RX0_IRQn 1 */
}

View File

@@ -53,116 +53,100 @@
TIM_HandleTypeDef htim8;
/* TIM8 init function */
void MX_TIM8_Init(void)
{
void MX_TIM8_Init(void) {
TIM_ClockConfigTypeDef sClockSourceConfig;
TIM_MasterConfigTypeDef sMasterConfig;
TIM_OC_InitTypeDef sConfigOC;
TIM_BreakDeadTimeConfigTypeDef sBreakDeadTimeConfig;
htim8.Instance = TIM8;
htim8.Init.Prescaler = 0;
htim8.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3;
htim8.Init.Period = 4800;
htim8.Instance = TIM8;
htim8.Init.Prescaler = 0;
htim8.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3;
htim8.Init.Period = 4800;
htim8.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
#ifdef PWM_INVERT
htim8.Init.RepetitionCounter = 1;
#else
htim8.Init.RepetitionCounter = 0;
#endif
if (HAL_TIM_Base_Init(&htim8) != HAL_OK)
{
if(HAL_TIM_Base_Init(&htim8) != HAL_OK) {
Error_Handler();
}
sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL;
if (HAL_TIM_ConfigClockSource(&htim8, &sClockSourceConfig) != HAL_OK)
{
if(HAL_TIM_ConfigClockSource(&htim8, &sClockSourceConfig) != HAL_OK) {
Error_Handler();
}
if (HAL_TIM_PWM_Init(&htim8) != HAL_OK)
{
if(HAL_TIM_PWM_Init(&htim8) != HAL_OK) {
Error_Handler();
}
sMasterConfig.MasterOutputTrigger = TIM_TRGO_UPDATE;
sMasterConfig.MasterOutputTrigger = TIM_TRGO_UPDATE;
sMasterConfig.MasterOutputTrigger2 = TIM_TRGO2_RESET;
sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
if (HAL_TIMEx_MasterConfigSynchronization(&htim8, &sMasterConfig) != HAL_OK)
{
sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
if(HAL_TIMEx_MasterConfigSynchronization(&htim8, &sMasterConfig) != HAL_OK) {
Error_Handler();
}
sConfigOC.OCMode = TIM_OCMODE_PWM1;
sConfigOC.Pulse = 0;
sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH;
sConfigOC.OCNPolarity = TIM_OCNPOLARITY_HIGH;
sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
sConfigOC.OCIdleState = TIM_OCIDLESTATE_RESET;
sConfigOC.OCMode = TIM_OCMODE_PWM1;
sConfigOC.Pulse = 0;
sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH;
sConfigOC.OCNPolarity = TIM_OCNPOLARITY_HIGH;
sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
sConfigOC.OCIdleState = TIM_OCIDLESTATE_RESET;
sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_RESET;
if (HAL_TIM_PWM_ConfigChannel(&htim8, &sConfigOC, TIM_CHANNEL_1) != HAL_OK)
{
if(HAL_TIM_PWM_ConfigChannel(&htim8, &sConfigOC, TIM_CHANNEL_1) != HAL_OK) {
Error_Handler();
}
if (HAL_TIM_PWM_ConfigChannel(&htim8, &sConfigOC, TIM_CHANNEL_2) != HAL_OK)
{
if(HAL_TIM_PWM_ConfigChannel(&htim8, &sConfigOC, TIM_CHANNEL_2) != HAL_OK) {
Error_Handler();
}
if (HAL_TIM_PWM_ConfigChannel(&htim8, &sConfigOC, TIM_CHANNEL_3) != HAL_OK)
{
if(HAL_TIM_PWM_ConfigChannel(&htim8, &sConfigOC, TIM_CHANNEL_3) != HAL_OK) {
Error_Handler();
}
sBreakDeadTimeConfig.OffStateRunMode = TIM_OSSR_DISABLE;
sBreakDeadTimeConfig.OffStateRunMode = TIM_OSSR_DISABLE;
sBreakDeadTimeConfig.OffStateIDLEMode = TIM_OSSI_DISABLE;
sBreakDeadTimeConfig.LockLevel = TIM_LOCKLEVEL_OFF;
sBreakDeadTimeConfig.DeadTime = PWM_DEADTIME;
sBreakDeadTimeConfig.BreakState = TIM_BREAK_DISABLE;
sBreakDeadTimeConfig.BreakPolarity = TIM_BREAKPOLARITY_HIGH;
sBreakDeadTimeConfig.BreakFilter = 0;
sBreakDeadTimeConfig.Break2State = TIM_BREAK2_DISABLE;
sBreakDeadTimeConfig.Break2Polarity = TIM_BREAK2POLARITY_HIGH;
sBreakDeadTimeConfig.Break2Filter = 0;
sBreakDeadTimeConfig.AutomaticOutput = TIM_AUTOMATICOUTPUT_DISABLE;
if (HAL_TIMEx_ConfigBreakDeadTime(&htim8, &sBreakDeadTimeConfig) != HAL_OK)
{
sBreakDeadTimeConfig.LockLevel = TIM_LOCKLEVEL_OFF;
sBreakDeadTimeConfig.DeadTime = PWM_DEADTIME;
sBreakDeadTimeConfig.BreakState = TIM_BREAK_DISABLE;
sBreakDeadTimeConfig.BreakPolarity = TIM_BREAKPOLARITY_HIGH;
sBreakDeadTimeConfig.BreakFilter = 0;
sBreakDeadTimeConfig.Break2State = TIM_BREAK2_DISABLE;
sBreakDeadTimeConfig.Break2Polarity = TIM_BREAK2POLARITY_HIGH;
sBreakDeadTimeConfig.Break2Filter = 0;
sBreakDeadTimeConfig.AutomaticOutput = TIM_AUTOMATICOUTPUT_DISABLE;
if(HAL_TIMEx_ConfigBreakDeadTime(&htim8, &sBreakDeadTimeConfig) != HAL_OK) {
Error_Handler();
}
HAL_TIM_MspPostInit(&htim8);
}
void HAL_TIM_Base_MspInit(TIM_HandleTypeDef* tim_baseHandle)
{
void HAL_TIM_Base_MspInit(TIM_HandleTypeDef *tim_baseHandle) {
if(tim_baseHandle->Instance == TIM8) {
/* USER CODE BEGIN TIM8_MspInit 0 */
if(tim_baseHandle->Instance==TIM8)
{
/* USER CODE BEGIN TIM8_MspInit 0 */
/* USER CODE END TIM8_MspInit 0 */
/* USER CODE END TIM8_MspInit 0 */
/* Peripheral clock enable */
__HAL_RCC_TIM8_CLK_ENABLE();
HAL_NVIC_SetPriority(TIM8_UP_IRQn, 0, 0);
HAL_NVIC_EnableIRQ(TIM8_UP_IRQn);
/* USER CODE BEGIN TIM8_MspInit 1 */
/* USER CODE BEGIN TIM8_MspInit 1 */
/* USER CODE END TIM8_MspInit 1 */
/* USER CODE END TIM8_MspInit 1 */
}
}
void HAL_TIM_MspPostInit(TIM_HandleTypeDef* timHandle)
{
void HAL_TIM_MspPostInit(TIM_HandleTypeDef *timHandle) {
GPIO_InitTypeDef GPIO_InitStruct;
if(timHandle->Instance==TIM8)
{
/* USER CODE BEGIN TIM8_MspPostInit 0 */
if(timHandle->Instance == TIM8) {
/* USER CODE BEGIN TIM8_MspPostInit 0 */
/* USER CODE END TIM8_MspPostInit 0 */
/* USER CODE END TIM8_MspPostInit 0 */
/**TIM8 GPIO Configuration
PB3 ------> TIM8_CH1N
PB4 ------> TIM8_CH2N
@@ -171,56 +155,52 @@ void HAL_TIM_MspPostInit(TIM_HandleTypeDef* timHandle)
PB8 ------> TIM8_CH2
PB9 ------> TIM8_CH3
*/
GPIO_InitStruct.Pin = GPIO_PIN_3|GPIO_PIN_4;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Pin = GPIO_PIN_3 | GPIO_PIN_4;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Alternate = GPIO_AF4_TIM8;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
GPIO_InitStruct.Pin = GPIO_PIN_5;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Pin = GPIO_PIN_5;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Alternate = GPIO_AF3_TIM8;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
GPIO_InitStruct.Pin = GPIO_PIN_6;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Pin = GPIO_PIN_6;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Alternate = GPIO_AF5_TIM8;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
GPIO_InitStruct.Pin = GPIO_PIN_8|GPIO_PIN_9;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Pin = GPIO_PIN_8 | GPIO_PIN_9;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Alternate = GPIO_AF10_TIM8;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
/* USER CODE BEGIN TIM8_MspPostInit 1 */
/* USER CODE BEGIN TIM8_MspPostInit 1 */
/* USER CODE END TIM8_MspPostInit 1 */
/* USER CODE END TIM8_MspPostInit 1 */
}
}
void HAL_TIM_Base_MspDeInit(TIM_HandleTypeDef* tim_baseHandle)
{
void HAL_TIM_Base_MspDeInit(TIM_HandleTypeDef *tim_baseHandle) {
if(tim_baseHandle->Instance == TIM8) {
/* USER CODE BEGIN TIM8_MspDeInit 0 */
if(tim_baseHandle->Instance==TIM8)
{
/* USER CODE BEGIN TIM8_MspDeInit 0 */
/* USER CODE END TIM8_MspDeInit 0 */
/* USER CODE END TIM8_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_TIM8_CLK_DISABLE();
}
/* USER CODE BEGIN TIM8_MspDeInit 1 */
/* USER CODE END TIM8_MspDeInit 1 */
}
}
/* USER CODE BEGIN 1 */

View File

@@ -53,9 +53,8 @@
/* USB Device Core handle declaration */
USBD_HandleTypeDef hUsbDeviceFS;
/* init function */
void MX_USB_DEVICE_Init(void)
{
/* init function */
void MX_USB_DEVICE_Init(void) {
/* Init Device Library,Add Supported Class and Start the library*/
USBD_Init(&hUsbDeviceFS, &FS_Desc, DEVICE_FS);
@@ -64,7 +63,6 @@ void MX_USB_DEVICE_Init(void)
USBD_CDC_RegisterInterface(&hUsbDeviceFS, &USBD_Interface_fops_FS);
USBD_Start(&hUsbDeviceFS);
}
/**
* @}

View File

@@ -45,8 +45,8 @@
#include "usbd_cdc_if.h"
/* USER CODE BEGIN INCLUDE */
#include "ringbuf.h"
#define RX_QUEUE_SIZE 1024
#define TX_QUEUE_SIZE 4096
#define RX_QUEUE_SIZE 1024
#define TX_QUEUE_SIZE 4096
/* USER CODE END INCLUDE */
/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
@@ -56,42 +56,42 @@
/** @defgroup USBD_CDC
* @brief usbd core module
* @{
*/
*/
/** @defgroup USBD_CDC_Private_TypesDefinitions
* @{
*/
*/
/* USER CODE BEGIN PRIVATE_TYPES */
struct ringbuf rx_buf = RINGBUF(RX_QUEUE_SIZE);
struct ringbuf tx_buf = RINGBUF(TX_QUEUE_SIZE);
/* USER CODE END PRIVATE_TYPES */
/* USER CODE END PRIVATE_TYPES */
/**
* @}
*/
*/
/** @defgroup USBD_CDC_Private_Defines
* @{
*/
*/
/* USER CODE BEGIN PRIVATE_DEFINES */
/* Define size for the receive and transmit buffer over CDC */
/* It's up to user to redefine and/or remove those define */
#define APP_RX_DATA_SIZE 64 //TODO: more for FS transfers
#define APP_TX_DATA_SIZE 64
#define APP_RX_DATA_SIZE 64 //TODO: more for FS transfers
#define APP_TX_DATA_SIZE 64
/* USER CODE END PRIVATE_DEFINES */
/**
* @}
*/
*/
/** @defgroup USBD_CDC_Private_Macros
* @{
*/
*/
/* USER CODE BEGIN PRIVATE_MACRO */
/* USER CODE END PRIVATE_MACRO */
/**
* @}
*/
*/
/** @defgroup USBD_CDC_Private_Variables
* @{
*/
@@ -108,41 +108,40 @@ uint8_t UserTxBufferFS[APP_TX_DATA_SIZE];
/**
* @}
*/
*/
/** @defgroup USBD_CDC_IF_Exported_Variables
* @{
*/
extern USBD_HandleTypeDef hUsbDeviceFS;
*/
extern USBD_HandleTypeDef hUsbDeviceFS;
/* USER CODE BEGIN EXPORTED_VARIABLES */
/* USER CODE END EXPORTED_VARIABLES */
/**
* @}
*/
*/
/** @defgroup USBD_CDC_Private_FunctionPrototypes
* @{
*/
static int8_t CDC_Init_FS (void);
static int8_t CDC_DeInit_FS (void);
static int8_t CDC_Control_FS (uint8_t cmd, uint8_t* pbuf, uint16_t length);
static int8_t CDC_Receive_FS (uint8_t* pbuf, uint32_t *Len);
static int8_t CDC_Init_FS(void);
static int8_t CDC_DeInit_FS(void);
static int8_t CDC_Control_FS(uint8_t cmd, uint8_t *pbuf, uint16_t length);
static int8_t CDC_Receive_FS(uint8_t *pbuf, uint32_t *Len);
/* USER CODE BEGIN PRIVATE_FUNCTIONS_DECLARATION */
/* USER CODE END PRIVATE_FUNCTIONS_DECLARATION */
/**
* @}
*/
USBD_CDC_ItfTypeDef USBD_Interface_fops_FS =
{
CDC_Init_FS,
CDC_DeInit_FS,
CDC_Control_FS,
CDC_Receive_FS
};
*/
USBD_CDC_ItfTypeDef USBD_Interface_fops_FS =
{
CDC_Init_FS,
CDC_DeInit_FS,
CDC_Control_FS,
CDC_Receive_FS};
/* Private functions ---------------------------------------------------------*/
/**
@@ -151,14 +150,13 @@ USBD_CDC_ItfTypeDef USBD_Interface_fops_FS =
* @param None
* @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
*/
static int8_t CDC_Init_FS(void)
{
/* USER CODE BEGIN 3 */
static int8_t CDC_Init_FS(void) {
/* USER CODE BEGIN 3 */
/* Set Application Buffers */
USBD_CDC_SetTxBuffer(&hUsbDeviceFS, UserTxBufferFS, 0);
USBD_CDC_SetRxBuffer(&hUsbDeviceFS, UserRxBufferFS);
return (USBD_OK);
/* USER CODE END 3 */
/* USER CODE END 3 */
}
/**
@@ -167,11 +165,10 @@ static int8_t CDC_Init_FS(void)
* @param None
* @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
*/
static int8_t CDC_DeInit_FS(void)
{
/* USER CODE BEGIN 4 */
static int8_t CDC_DeInit_FS(void) {
/* USER CODE BEGIN 4 */
return (USBD_OK);
/* USER CODE END 4 */
/* USER CODE END 4 */
}
/**
@@ -182,66 +179,64 @@ static int8_t CDC_DeInit_FS(void)
* @param length: Number of data to be sent (in bytes)
* @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
*/
static int8_t CDC_Control_FS (uint8_t cmd, uint8_t* pbuf, uint16_t length)
{
static int8_t CDC_Control_FS(uint8_t cmd, uint8_t *pbuf, uint16_t length) {
/* USER CODE BEGIN 5 */
switch (cmd)
{
case CDC_SEND_ENCAPSULATED_COMMAND:
break;
switch(cmd) {
case CDC_SEND_ENCAPSULATED_COMMAND:
case CDC_GET_ENCAPSULATED_RESPONSE:
break;
break;
case CDC_SET_COMM_FEATURE:
break;
case CDC_GET_ENCAPSULATED_RESPONSE:
case CDC_GET_COMM_FEATURE:
break;
break;
case CDC_SET_COMM_FEATURE:
case CDC_CLEAR_COMM_FEATURE:
break;
break;
case CDC_GET_COMM_FEATURE:
/*******************************************************************************/
/* Line Coding Structure */
/*-----------------------------------------------------------------------------*/
/* Offset | Field | Size | Value | Description */
/* 0 | dwDTERate | 4 | Number |Data terminal rate, in bits per second*/
/* 4 | bCharFormat | 1 | Number | Stop bits */
/* 0 - 1 Stop bit */
/* 1 - 1.5 Stop bits */
/* 2 - 2 Stop bits */
/* 5 | bParityType | 1 | Number | Parity */
/* 0 - None */
/* 1 - Odd */
/* 2 - Even */
/* 3 - Mark */
/* 4 - Space */
/* 6 | bDataBits | 1 | Number Data bits (5, 6, 7, 8 or 16). */
/*******************************************************************************/
case CDC_SET_LINE_CODING:
break;
break;
case CDC_GET_LINE_CODING:
case CDC_CLEAR_COMM_FEATURE:
break;
break;
case CDC_SET_CONTROL_LINE_STATE:
/*******************************************************************************/
/* Line Coding Structure */
/*-----------------------------------------------------------------------------*/
/* Offset | Field | Size | Value | Description */
/* 0 | dwDTERate | 4 | Number |Data terminal rate, in bits per second*/
/* 4 | bCharFormat | 1 | Number | Stop bits */
/* 0 - 1 Stop bit */
/* 1 - 1.5 Stop bits */
/* 2 - 2 Stop bits */
/* 5 | bParityType | 1 | Number | Parity */
/* 0 - None */
/* 1 - Odd */
/* 2 - Even */
/* 3 - Mark */
/* 4 - Space */
/* 6 | bDataBits | 1 | Number Data bits (5, 6, 7, 8 or 16). */
/*******************************************************************************/
case CDC_SET_LINE_CODING:
break;
break;
case CDC_SEND_BREAK:
break;
default:
break;
case CDC_GET_LINE_CODING:
break;
case CDC_SET_CONTROL_LINE_STATE:
break;
case CDC_SEND_BREAK:
break;
default:
break;
}
return (USBD_OK);
@@ -263,14 +258,13 @@ static int8_t CDC_Control_FS (uint8_t cmd, uint8_t* pbuf, uint16_t length)
* @param Len: Number of data received (in bytes)
* @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
*/
static int8_t CDC_Receive_FS (uint8_t* Buf, uint32_t *Len)
{
static int8_t CDC_Receive_FS(uint8_t *Buf, uint32_t *Len) {
/* USER CODE BEGIN 6 */
rb_write(&rx_buf, Buf, *Len);
USBD_CDC_SetRxBuffer(&hUsbDeviceFS, &Buf[0]);
USBD_CDC_ReceivePacket(&hUsbDeviceFS);
return (USBD_OK);
/* USER CODE END 6 */
/* USER CODE END 6 */
}
/**
@@ -284,72 +278,70 @@ static int8_t CDC_Receive_FS (uint8_t* Buf, uint32_t *Len)
* @param Len: Number of data to be send (in bytes)
* @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL or USBD_BUSY
*/
uint8_t CDC_Transmit_FS(uint8_t* Buf, uint16_t Len)
{
uint8_t CDC_Transmit_FS(uint8_t *Buf, uint16_t Len) {
uint8_t result = USBD_OK;
/* USER CODE BEGIN 7 */
USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*)hUsbDeviceFS.pClassData;
if (hcdc->TxState != 0){
/* USER CODE BEGIN 7 */
USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef *)hUsbDeviceFS.pClassData;
if(hcdc->TxState != 0) {
return USBD_BUSY;
}
USBD_CDC_SetTxBuffer(&hUsbDeviceFS, Buf, Len);
result = USBD_CDC_TransmitPacket(&hUsbDeviceFS);
/* USER CODE END 7 */
/* USER CODE END 7 */
return result;
}
/* USER CODE BEGIN PRIVATE_FUNCTIONS_IMPLEMENTATION */
void cdc_usbtx(){
USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*)hUsbDeviceFS.pClassData;
if (hcdc->TxState != 0){
return; //busy
}
int len = rb_read(&tx_buf,UserTxBufferFS,sizeof(UserTxBufferFS));
USBD_CDC_SetTxBuffer(&hUsbDeviceFS, UserTxBufferFS, len);
USBD_CDC_TransmitPacket(&hUsbDeviceFS);
void cdc_usbtx() {
USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef *)hUsbDeviceFS.pClassData;
if(hcdc->TxState != 0) {
return; //busy
}
int len = rb_read(&tx_buf, UserTxBufferFS, sizeof(UserTxBufferFS));
USBD_CDC_SetTxBuffer(&hUsbDeviceFS, UserTxBufferFS, len);
USBD_CDC_TransmitPacket(&hUsbDeviceFS);
}
int cdc_tx(void* data, uint32_t len){
if(cdc_is_connected()){
int ret;
ret = rb_write(&tx_buf, data, len);
cdc_usbtx();
return ret;
}else{
return 0;
}
int cdc_tx(void *data, uint32_t len) {
if(cdc_is_connected()) {
int ret;
ret = rb_write(&tx_buf, data, len);
cdc_usbtx();
return ret;
} else {
return 0;
}
}
void cdc_poll(){
if(cdc_is_connected()){
cdc_usbtx();
}
void cdc_poll() {
if(cdc_is_connected()) {
cdc_usbtx();
}
}
int cdc_is_connected(){
if(hUsbDeviceFS.dev_state != USBD_STATE_CONFIGURED){
return 0;
}else{
return 1;
}
int cdc_is_connected() {
if(hUsbDeviceFS.dev_state != USBD_STATE_CONFIGURED) {
return 0;
} else {
return 1;
}
}
int cdc_getline(char *ptr, int len){
return rb_getline(&rx_buf, ptr, len);
int cdc_getline(char *ptr, int len) {
return rb_getline(&rx_buf, ptr, len);
}
int _write(int file, char *ptr, int len){
return cdc_tx(ptr, len);
int _write(int file, char *ptr, int len) {
return cdc_tx(ptr, len);
}
/* USER CODE END PRIVATE_FUNCTIONS_IMPLEMENTATION */
/**
* @}
*/
*/
/**
* @}
*/
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

File diff suppressed because it is too large Load Diff

View File

@@ -54,125 +54,125 @@
/** @defgroup USBD_DESC
* @brief USBD descriptors module
* @{
*/
*/
/** @defgroup USBD_DESC_Private_TypesDefinitions
* @{
*/
*/
/**
* @}
*/
*/
/** @defgroup USBD_DESC_Private_Defines
* @{
*/
#define USBD_VID 1155
#define USBD_LANGID_STRING 1033
#define USBD_MANUFACTURER_STRING "STMicroelectronics"
#define USBD_PID_FS 22336
#define USBD_PRODUCT_STRING_FS "STM32 Virtual ComPort"
#define USBD_SERIALNUMBER_STRING_FS "00000000001A"
#define USBD_CONFIGURATION_STRING_FS "CDC Config"
#define USBD_INTERFACE_STRING_FS "CDC Interface"
*/
#define USBD_VID 1155
#define USBD_LANGID_STRING 1033
#define USBD_MANUFACTURER_STRING "STMicroelectronics"
#define USBD_PID_FS 22336
#define USBD_PRODUCT_STRING_FS "STM32 Virtual ComPort"
#define USBD_SERIALNUMBER_STRING_FS "00000000001A"
#define USBD_CONFIGURATION_STRING_FS "CDC Config"
#define USBD_INTERFACE_STRING_FS "CDC Interface"
/* USER CODE BEGIN 0 */
/* USER CODE END 0*/
/**
* @}
*/
*/
/** @defgroup USBD_DESC_Private_Macros
* @{
*/
*/
/**
* @}
*/
*/
/** @defgroup USBD_DESC_Private_Variables
* @{
*/
uint8_t * USBD_FS_DeviceDescriptor( USBD_SpeedTypeDef speed , uint16_t *length);
uint8_t * USBD_FS_LangIDStrDescriptor( USBD_SpeedTypeDef speed , uint16_t *length);
uint8_t * USBD_FS_ManufacturerStrDescriptor ( USBD_SpeedTypeDef speed , uint16_t *length);
uint8_t * USBD_FS_ProductStrDescriptor ( USBD_SpeedTypeDef speed , uint16_t *length);
uint8_t * USBD_FS_SerialStrDescriptor( USBD_SpeedTypeDef speed , uint16_t *length);
uint8_t * USBD_FS_ConfigStrDescriptor( USBD_SpeedTypeDef speed , uint16_t *length);
uint8_t * USBD_FS_InterfaceStrDescriptor( USBD_SpeedTypeDef speed , uint16_t *length);
*/
uint8_t *USBD_FS_DeviceDescriptor(USBD_SpeedTypeDef speed, uint16_t *length);
uint8_t *USBD_FS_LangIDStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length);
uint8_t *USBD_FS_ManufacturerStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length);
uint8_t *USBD_FS_ProductStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length);
uint8_t *USBD_FS_SerialStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length);
uint8_t *USBD_FS_ConfigStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length);
uint8_t *USBD_FS_InterfaceStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length);
#ifdef USB_SUPPORT_USER_STRING_DESC
uint8_t * USBD_FS_USRStringDesc (USBD_SpeedTypeDef speed, uint8_t idx , uint16_t *length);
#endif /* USB_SUPPORT_USER_STRING_DESC */
uint8_t *USBD_FS_USRStringDesc(USBD_SpeedTypeDef speed, uint8_t idx, uint16_t *length);
#endif /* USB_SUPPORT_USER_STRING_DESC */
USBD_DescriptorsTypeDef FS_Desc =
{
USBD_FS_DeviceDescriptor,
USBD_FS_LangIDStrDescriptor,
USBD_FS_ManufacturerStrDescriptor,
USBD_FS_ProductStrDescriptor,
USBD_FS_SerialStrDescriptor,
USBD_FS_ConfigStrDescriptor,
USBD_FS_InterfaceStrDescriptor,
{
USBD_FS_DeviceDescriptor,
USBD_FS_LangIDStrDescriptor,
USBD_FS_ManufacturerStrDescriptor,
USBD_FS_ProductStrDescriptor,
USBD_FS_SerialStrDescriptor,
USBD_FS_ConfigStrDescriptor,
USBD_FS_InterfaceStrDescriptor,
};
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#if defined(__ICCARM__) /*!< IAR Compiler */
#pragma data_alignment = 4
#endif
/* USB Standard Device Descriptor */
__ALIGN_BEGIN uint8_t USBD_FS_DeviceDesc[USB_LEN_DEV_DESC] __ALIGN_END =
{
0x12, /*bLength */
USB_DESC_TYPE_DEVICE, /*bDescriptorType*/
0x00, /* bcdUSB */
0x02,
0x02, /*bDeviceClass*/
0x02, /*bDeviceSubClass*/
0x00, /*bDeviceProtocol*/
USB_MAX_EP0_SIZE, /*bMaxPacketSize*/
LOBYTE(USBD_VID), /*idVendor*/
HIBYTE(USBD_VID), /*idVendor*/
LOBYTE(USBD_PID_FS), /*idVendor*/
HIBYTE(USBD_PID_FS), /*idVendor*/
0x00, /*bcdDevice rel. 2.00*/
0x02,
USBD_IDX_MFC_STR, /*Index of manufacturer string*/
USBD_IDX_PRODUCT_STR, /*Index of product string*/
USBD_IDX_SERIAL_STR, /*Index of serial number string*/
USBD_MAX_NUM_CONFIGURATION /*bNumConfigurations*/
} ;
{
0x12, /*bLength */
USB_DESC_TYPE_DEVICE, /*bDescriptorType*/
0x00, /* bcdUSB */
0x02,
0x02, /*bDeviceClass*/
0x02, /*bDeviceSubClass*/
0x00, /*bDeviceProtocol*/
USB_MAX_EP0_SIZE, /*bMaxPacketSize*/
LOBYTE(USBD_VID), /*idVendor*/
HIBYTE(USBD_VID), /*idVendor*/
LOBYTE(USBD_PID_FS), /*idVendor*/
HIBYTE(USBD_PID_FS), /*idVendor*/
0x00, /*bcdDevice rel. 2.00*/
0x02,
USBD_IDX_MFC_STR, /*Index of manufacturer string*/
USBD_IDX_PRODUCT_STR, /*Index of product string*/
USBD_IDX_SERIAL_STR, /*Index of serial number string*/
USBD_MAX_NUM_CONFIGURATION /*bNumConfigurations*/
};
/* USB_DeviceDescriptor */
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#if defined(__ICCARM__) /*!< IAR Compiler */
#pragma data_alignment = 4
#endif
/* USB Standard Device Descriptor */
__ALIGN_BEGIN uint8_t USBD_LangIDDesc[USB_LEN_LANGID_STR_DESC] __ALIGN_END =
{
USB_LEN_LANGID_STR_DESC,
USB_DESC_TYPE_STRING,
LOBYTE(USBD_LANGID_STRING),
HIBYTE(USBD_LANGID_STRING),
{
USB_LEN_LANGID_STR_DESC,
USB_DESC_TYPE_STRING,
LOBYTE(USBD_LANGID_STRING),
HIBYTE(USBD_LANGID_STRING),
};
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#if defined(__ICCARM__) /*!< IAR Compiler */
#pragma data_alignment = 4
#endif
__ALIGN_BEGIN uint8_t USBD_StrDesc[USBD_MAX_STR_DESC_SIZ] __ALIGN_END;
/**
* @}
*/
*/
/** @defgroup USBD_DESC_Private_FunctionPrototypes
* @{
*/
*/
/**
* @}
*/
*/
/** @defgroup USBD_DESC_Private_Functions
* @{
*/
*/
/**
* @brief USBD_FS_DeviceDescriptor
@@ -181,8 +181,7 @@ __ALIGN_BEGIN uint8_t USBD_StrDesc[USBD_MAX_STR_DESC_SIZ] __ALIGN_END;
* @param length : pointer to data length variable
* @retval pointer to descriptor buffer
*/
uint8_t * USBD_FS_DeviceDescriptor( USBD_SpeedTypeDef speed , uint16_t *length)
{
uint8_t *USBD_FS_DeviceDescriptor(USBD_SpeedTypeDef speed, uint16_t *length) {
*length = sizeof(USBD_FS_DeviceDesc);
return USBD_FS_DeviceDesc;
}
@@ -194,9 +193,8 @@ uint8_t * USBD_FS_DeviceDescriptor( USBD_SpeedTypeDef speed , uint16_t *length)
* @param length : pointer to data length variable
* @retval pointer to descriptor buffer
*/
uint8_t * USBD_FS_LangIDStrDescriptor( USBD_SpeedTypeDef speed , uint16_t *length)
{
*length = sizeof(USBD_LangIDDesc);
uint8_t *USBD_FS_LangIDStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length) {
*length = sizeof(USBD_LangIDDesc);
return USBD_LangIDDesc;
}
@@ -207,15 +205,11 @@ uint8_t * USBD_FS_LangIDStrDescriptor( USBD_SpeedTypeDef speed , uint16_t *leng
* @param length : pointer to data length variable
* @retval pointer to descriptor buffer
*/
uint8_t * USBD_FS_ProductStrDescriptor( USBD_SpeedTypeDef speed , uint16_t *length)
{
if(speed == 0)
{
USBD_GetString (USBD_PRODUCT_STRING_FS, USBD_StrDesc, length);
}
else
{
USBD_GetString (USBD_PRODUCT_STRING_FS, USBD_StrDesc, length);
uint8_t *USBD_FS_ProductStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length) {
if(speed == 0) {
USBD_GetString(USBD_PRODUCT_STRING_FS, USBD_StrDesc, length);
} else {
USBD_GetString(USBD_PRODUCT_STRING_FS, USBD_StrDesc, length);
}
return USBD_StrDesc;
}
@@ -227,9 +221,8 @@ uint8_t * USBD_FS_ProductStrDescriptor( USBD_SpeedTypeDef speed , uint16_t *len
* @param length : pointer to data length variable
* @retval pointer to descriptor buffer
*/
uint8_t * USBD_FS_ManufacturerStrDescriptor( USBD_SpeedTypeDef speed , uint16_t *length)
{
USBD_GetString (USBD_MANUFACTURER_STRING, USBD_StrDesc, length);
uint8_t *USBD_FS_ManufacturerStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length) {
USBD_GetString(USBD_MANUFACTURER_STRING, USBD_StrDesc, length);
return USBD_StrDesc;
}
@@ -240,15 +233,11 @@ uint8_t * USBD_FS_ManufacturerStrDescriptor( USBD_SpeedTypeDef speed , uint16_t
* @param length : pointer to data length variable
* @retval pointer to descriptor buffer
*/
uint8_t * USBD_FS_SerialStrDescriptor( USBD_SpeedTypeDef speed , uint16_t *length)
{
if(speed == USBD_SPEED_HIGH)
{
USBD_GetString (USBD_SERIALNUMBER_STRING_FS, USBD_StrDesc, length);
}
else
{
USBD_GetString (USBD_SERIALNUMBER_STRING_FS, USBD_StrDesc, length);
uint8_t *USBD_FS_SerialStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length) {
if(speed == USBD_SPEED_HIGH) {
USBD_GetString(USBD_SERIALNUMBER_STRING_FS, USBD_StrDesc, length);
} else {
USBD_GetString(USBD_SERIALNUMBER_STRING_FS, USBD_StrDesc, length);
}
return USBD_StrDesc;
}
@@ -260,17 +249,13 @@ uint8_t * USBD_FS_SerialStrDescriptor( USBD_SpeedTypeDef speed , uint16_t *leng
* @param length : pointer to data length variable
* @retval pointer to descriptor buffer
*/
uint8_t * USBD_FS_ConfigStrDescriptor( USBD_SpeedTypeDef speed , uint16_t *length)
{
if(speed == USBD_SPEED_HIGH)
{
USBD_GetString (USBD_CONFIGURATION_STRING_FS, USBD_StrDesc, length);
uint8_t *USBD_FS_ConfigStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length) {
if(speed == USBD_SPEED_HIGH) {
USBD_GetString(USBD_CONFIGURATION_STRING_FS, USBD_StrDesc, length);
} else {
USBD_GetString(USBD_CONFIGURATION_STRING_FS, USBD_StrDesc, length);
}
else
{
USBD_GetString (USBD_CONFIGURATION_STRING_FS, USBD_StrDesc, length);
}
return USBD_StrDesc;
return USBD_StrDesc;
}
/**
@@ -280,28 +265,24 @@ uint8_t * USBD_FS_ConfigStrDescriptor( USBD_SpeedTypeDef speed , uint16_t *leng
* @param length : pointer to data length variable
* @retval pointer to descriptor buffer
*/
uint8_t * USBD_FS_InterfaceStrDescriptor( USBD_SpeedTypeDef speed , uint16_t *length)
{
if(speed == 0)
{
USBD_GetString (USBD_INTERFACE_STRING_FS, USBD_StrDesc, length);
uint8_t *USBD_FS_InterfaceStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length) {
if(speed == 0) {
USBD_GetString(USBD_INTERFACE_STRING_FS, USBD_StrDesc, length);
} else {
USBD_GetString(USBD_INTERFACE_STRING_FS, USBD_StrDesc, length);
}
else
{
USBD_GetString (USBD_INTERFACE_STRING_FS, USBD_StrDesc, length);
}
return USBD_StrDesc;
return USBD_StrDesc;
}
/**
* @}
*/
*/
/**
* @}
*/
*/
/**
* @}
*/
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -1,8 +1,7 @@
#include "version.h"
volatile const struct version_info version_info = {
.product_name = "STMBL-hv-f303",
.major = 0,
.minor = 9,
.patch = 0
};
.product_name = "STMBL-hv-f303",
.major = 0,
.minor = 9,
.patch = 0};