1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-03-16 08:29:15 +01:00

OP-21/Bootloader deleted old one, commited new one. Partly functional, but slow due to current packet size.

git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@1378 ebee16cc-31ac-478f-84a7-5cbb03baadba
This commit is contained in:
zedamota 2010-08-22 19:51:55 +00:00 committed by zedamota
parent d899bc3c81
commit 002c746076
38 changed files with 2021 additions and 3295 deletions

View File

@ -26,16 +26,7 @@
# Set developer code and compile options
# Set to YES to compile for debugging
DEBUG ?= YES
# Set to YES to use the Servo output pins for debugging via scope or logic analyser
ENABLE_DEBUG_PINS ?= NO
# Set to Yes to enable the AUX UART which is mapped on the S1 (Tx) and S2 (Rx) servo outputs
ENABLE_AUX_UART ?= NO
#
USE_BOOTLOADER ?= NO
# Set to YES when using Code Sourcery toolchain
CODE_SOURCERY ?= NO
@ -64,29 +55,17 @@ USE_THUMB_MODE = YES
MCU = cortex-m3
CHIP = STM32F103RET
BOARD = STM3210E_OP
ifeq ($(USE_BOOTLOADER), YES)
MODEL = HD_BL
else
MODEL = HD
endif
# Directory for output files (lst, obj, dep, elf, sym, map, hex, bin etc.)
OUTDIR = Build
# Target file name (without extension).
TARGET = OpenPilot2_BL
TARGET = bootloader
# Paths
OPSYSTEM = ./
OPSYSTEMINC = $(OPSYSTEM)/inc
OPUAVTALK = ./UAVTalk
OPUAVTALKINC = $(OPUAVTALK)/inc
OPUAVOBJ = ./UAVObjects
OPUAVOBJINC = $(OPUAVOBJ)/inc
OPTESTS = ./Tests
OPMODULEDIR = ./Modules
HIDSYSTEM = .
HIDSYSTEMINC = ./inc
PIOS = ../../PiOS
PIOSINC = $(PIOS)/inc
PIOSSTM32F10X = $(PIOS)/STM32F10x
@ -100,34 +79,19 @@ STMSPDINCDIR = $(STMSPDDIR)/inc
STMUSBSRCDIR = $(STMUSBDIR)/src
STMUSBINCDIR = $(STMUSBDIR)/inc
CMSISDIR = $(STMLIBDIR)/CMSIS/Core/CM3
DOSFSDIR = $(APPLIBDIR)/dosfs
MSDDIR = $(APPLIBDIR)/msd
RTOSDIR = $(APPLIBDIR)/FreeRTOS
RTOSSRCDIR = $(RTOSDIR)/Source
RTOSINCDIR = $(RTOSSRCDIR)/include
DOXYGENDIR = ../Doc/Doxygen
# List C source files here. (C dependencies are automatically generated.)
# use file-extension c for "c-only"-files
MODNAMES = $(notdir ${MODULES})
DOXYGENDIR = .../Doc/Doxygen
## OPENPILOT CORE:
SRC += $(OPSYSTEM)/dfu_mal.c
SRC += $(OPSYSTEM)/flash_if.c
SRC += $(OPSYSTEM)/stm32f10x_it.c
SRC += $(OPSYSTEM)/fsmc_nor.c
SRC += $(OPSYSTEM)/hw_config.c
SRC += $(OPSYSTEM)/main.c
SRC += $(OPSYSTEM)/nor_if.c
SRC += $(OPSYSTEM)/spi_flash.c
SRC += $(OPSYSTEM)/spi_if.c
SRC += $(OPSYSTEM)/usb_desc.c
#SRC += $(OPSYSTEM)/usb_endp.c
SRC += $(OPSYSTEM)/usb_istr.c
SRC += $(OPSYSTEM)/usb_prop.c
SRC += $(OPSYSTEM)/usb_pwr.c
SRC += $(HIDSYSTEM)/main.c
SRC += $(HIDSYSTEM)/hw_config.c
SRC += $(HIDSYSTEM)/stm32f10x_it.c
SRC += $(HIDSYSTEM)/usb_desc.c
SRC += $(HIDSYSTEM)/usb_endp.c
SRC += $(HIDSYSTEM)/usb_istr.c
SRC += $(HIDSYSTEM)/usb_prop.c
SRC += $(HIDSYSTEM)/usb_pwr.c
SRC += $(HIDSYSTEM)/stm3210e_eval.c
## CMSIS for STM32
@ -135,24 +99,24 @@ SRC += $(CMSISDIR)/core_cm3.c
SRC += $(CMSISDIR)/system_stm32f10x.c
## Used parts of the STM-Library
SRC += $(STMSPDSRCDIR)/stm32f10x_adc.c
SRC += $(STMSPDSRCDIR)/stm32f10x_bkp.c
SRC += $(STMSPDSRCDIR)/stm32f10x_crc.c
SRC += $(STMSPDSRCDIR)/stm32f10x_dac.c
SRC += $(STMSPDSRCDIR)/stm32f10x_dma.c
SRC += $(STMSPDSRCDIR)/stm32f10x_exti.c
#SRC += $(STMSPDSRCDIR)/stm32f10x_adc.c
#SRC += $(STMSPDSRCDIR)/stm32f10x_bkp.c
#SRC += $(STMSPDSRCDIR)/stm32f10x_crc.c
#SRC += $(STMSPDSRCDIR)/stm32f10x_dac.c
#SRC += $(STMSPDSRCDIR)/stm32f10x_dma.c
#SRC += $(STMSPDSRCDIR)/stm32f10x_exti.c
SRC += $(STMSPDSRCDIR)/stm32f10x_flash.c
SRC += $(STMSPDSRCDIR)/stm32f10x_gpio.c
SRC += $(STMSPDSRCDIR)/stm32f10x_i2c.c
SRC += $(STMSPDSRCDIR)/stm32f10x_pwr.c
#SRC += $(STMSPDSRCDIR)/stm32f10x_i2c.c
#SRC += $(STMSPDSRCDIR)/stm32f10x_pwr.c
SRC += $(STMSPDSRCDIR)/stm32f10x_rcc.c
SRC += $(STMSPDSRCDIR)/stm32f10x_rtc.c
SRC += $(STMSPDSRCDIR)/stm32f10x_spi.c
SRC += $(STMSPDSRCDIR)/stm32f10x_tim.c
SRC += $(STMSPDSRCDIR)/stm32f10x_usart.c
SRC += $(STMSPDSRCDIR)/stm32f10x_wwdg.c
SRC += $(STMSPDSRCDIR)/stm32f10x_fsmc.c
#SRC += $(STMSPDSRCDIR)/stm32f10x_rtc.c
#SRC += $(STMSPDSRCDIR)/stm32f10x_spi.c
#SRC += $(STMSPDSRCDIR)/stm32f10x_tim.c
#SRC += $(STMSPDSRCDIR)/stm32f10x_usart.c
#SRC += $(STMSPDSRCDIR)/stm32f10x_wwdg.c
SRC += $(STMSPDSRCDIR)/misc.c
SRC += $(STMSPDSRCDIR)/stm32f10x_sdio.c
## STM32 USB Library
SRC += $(STMUSBSRCDIR)/usb_core.c
@ -191,17 +155,12 @@ ASRCARM =
# List any extra directories to look for include files here.
# Each directory must be seperated by a space.
EXTRAINCDIRS = $(OPSYSTEM)
EXTRAINCDIRS += $(OPSYSTEMINC)
XTRAINCDIRS += $(PIOSSTM32F10X)
EXTRAINCDIRS = $(HIDSYSTEM)
EXTRAINCDIRS = $(HIDSYSTEMINC)
EXTRAINCDIRS += $(STMSPDINCDIR)
EXTRAINCDIRS += $(STMUSBINCDIR)
EXTRAINCDIRS += $(CMSISDIR)
EXTRAINCDIRS += $(APPLIBDIR)
EXTRAINCDIRS += ${foreach MOD, ${MODULES}, Modules/${MOD}/inc} ${OPMODULEDIR}/System/inc
EXTRAINCDIRS += $(CMSISCS)
# List any extra directories to look for library files here.
# Also add directories where the linker should search for
@ -225,7 +184,7 @@ LINKERSCRIPTPATH = $(PIOSSTM32F10X)
# (Note: 3 is not always the best optimization level. See avr-libc FAQ.)
ifeq ($(DEBUG),YES)
OPT = 0
OPT = s
else
OPT = s
endif
@ -246,15 +205,7 @@ CDEFS = -DSTM32F10X_$(MODEL)
CDEFS += -DUSE_STDPERIPH_DRIVER
CDEFS += -DUSE_$(BOARD)
CDEFS += -DUSE_STM3210E_EVAL
ifeq ($(ENABLE_DEBUG_PINS), YES)
CDEFS += -DPIOS_ENABLE_DEBUG_PINS
endif
ifeq ($(ENABLE_AUX_UART), YES)
CDEFS += -DPIOS_ENABLE_AUX_UART
endif
ifeq ($(USE_BOOTLOADER), YES)
CDEFS += -DUSE_BOOTLOADER
endif
# Place project-specific -D and/or -U options for
@ -333,7 +284,6 @@ LDFLAGS +=-T$(LINKERSCRIPTPATH)/link_stm32f10x_$(MODEL).ld
# Options for OpenOCD flash-programming
# see openocd.pdf/openocd.texi for further information
#
#OOCD_LOADFILE+=$(OUTDIR)/x.hex
OOCD_LOADFILE+=$(OUTDIR)/$(TARGET).elf
# if OpenOCD is in the $PATH just set OOCD_EXE=openocd
OOCD_EXE=openocd

View File

@ -15,69 +15,136 @@
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
#include "spi_flash.h"
#include "platform_config.h"
#include "hw_config.h"
#include "dfu_mal.h"
#include "usb_lib.h"
#include "usb_desc.h"
#include "platform_config.h"
#include "usb_pwr.h"
#include "stm32_eval.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
#define ADC1_DR_Address ((uint32_t)0x4001244C)
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
ErrorStatus HSEStartUpStatus;
uint32_t ADC_ConvertedValueX = 0;
uint32_t ADC_ConvertedValueX_1 = 0;
/* Extern variables ----------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
static void IntToUnicode (uint32_t value , uint8_t *pbuf , uint8_t len);
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
* Function Name : Set_System.
* Function Name : Set_System
* Description : Configures Main system clocks & power.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void Set_System(void)
{
#ifndef USE_STM3210C_EVAL
GPIO_InitTypeDef GPIO_InitStructure;
#endif /* USE_STM3210C_EVAL */
/* SYSCLK, HCLK, PCLK2 and PCLK1 configuration -----------------------------*/
/* RCC system reset(for debug purpose) */
RCC_DeInit();
/* Unlock the internal flash */
FLASH_Unlock();
/* Enable HSE */
RCC_HSEConfig(RCC_HSE_ON);
#ifdef STM32F10X_HD
/* Enable the FSMC Clock */
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_FSMC, ENABLE);
#endif /* STM32F10X_HD */
/* Wait till HSE is ready */
HSEStartUpStatus = RCC_WaitForHSEStartUp();
#ifndef USE_STM3210C_EVAL
/* Enable "DISCONNECT" GPIO clock */
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIO_DISCONNECT, ENABLE);
if (HSEStartUpStatus == SUCCESS)
{
/* Enable Prefetch Buffer */
FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
/* Configure USB pull-up */
GPIO_InitStructure.GPIO_Pin = USB_DISCONNECT_PIN;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_OD;
GPIO_Init(USB_DISCONNECT, &GPIO_InitStructure);
USB_Cable_Config(DISABLE);
#endif /* USE_STM3210C_EVAL */
/* Flash 2 wait state */
FLASH_SetLatency(FLASH_Latency_2);
/* HCLK = SYSCLK */
RCC_HCLKConfig(RCC_SYSCLK_Div1);
/* Init the media interface */
MAL_Init();
/* PCLK2 = HCLK */
RCC_PCLK2Config(RCC_HCLK_Div1);
#ifndef USE_STM3210C_EVAL
USB_Cable_Config(ENABLE);
#endif /* USE_STM3210C_EVAL */
/* PCLK1 = HCLK/2 */
RCC_PCLK1Config(RCC_HCLK_Div2);
/* ADCCLK = PCLK2/8 */
RCC_ADCCLKConfig(RCC_PCLK2_Div8);
#ifdef STM32F10X_CL
/* Configure PLLs *********************************************************/
/* PLL2 configuration: PLL2CLK = (HSE / 5) * 8 = 40 MHz */
RCC_PREDIV2Config(RCC_PREDIV2_Div5);
RCC_PLL2Config(RCC_PLL2Mul_8);
/* Enable PLL2 */
RCC_PLL2Cmd(ENABLE);
/* Wait till PLL2 is ready */
while (RCC_GetFlagStatus(RCC_FLAG_PLL2RDY) == RESET)
{}
/* PLL configuration: PLLCLK = (PLL2 / 5) * 9 = 72 MHz */
RCC_PREDIV1Config(RCC_PREDIV1_Source_PLL2, RCC_PREDIV1_Div5);
RCC_PLLConfig(RCC_PLLSource_PREDIV1, RCC_PLLMul_9);
#else
/* PLLCLK = 8MHz * 9 = 72 MHz */
RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
#endif
/* Enable PLL */
RCC_PLLCmd(ENABLE);
/* Wait till PLL is ready */
while (RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
{
}
/* Select PLL as system clock source */
RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
/* Wait till PLL is used as system clock source */
while(RCC_GetSYSCLKSource() != 0x08)
{
}
}
else
{ /* If HSE fails to start-up, the application will have wrong clock configuration.
User can add here some code to deal with this error */
/* Go to infinite loop */
while (1)
{
}
}
/* Configure the used GPIOs*/
GPIO_Configuration();
/* Configure the KEY button in EXTI mode */
//STM_EVAL_PBInit(Button_KEY, Mode_EXTI);
/* Configure the Tamper button in EXTI mode */
//STM_EVAL_PBInit(Button_TAMPER, Mode_EXTI);
/* Additional EXTI configuration (configure both edges) */
//EXTI_Configuration();
/* Configure the LEDs */
STM_EVAL_LEDInit(LED1);
STM_EVAL_LEDInit(LED2);
STM_EVAL_LEDInit(LED3);
STM_EVAL_LEDInit(LED4);
/* Configure the ADC*/
// ADC_Configuration();
}
/*******************************************************************************
* Function Name : Set_USBClock.
* Function Name : Set_USBClock
* Description : Configures USB Clock input (48MHz).
* Input : None.
* Output : None.
@ -91,7 +158,7 @@ void Set_USBClock(void)
/* Enable the USB clock */
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_OTG_FS, ENABLE) ;
#else
#else
/* Select USBCLK source */
RCC_USBCLKConfig(RCC_USBCLKSource_PLLCLK_1Div5);
@ -123,28 +190,73 @@ void Enter_LowPowerMode(void)
void Leave_LowPowerMode(void)
{
DEVICE_INFO *pInfo = &Device_Info;
/* Set the device state to the correct state */
if (pInfo->Current_Configuration != 0)
{
/* Device configured */
bDeviceState = CONFIGURED;
}
else
else
{
bDeviceState = ATTACHED;
}
}
/*******************************************************************************
* Function Name : USB_Interrupts_Config.
* Description : Configures the USB interrupts.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void USB_Interrupts_Config(void)
{
NVIC_InitTypeDef NVIC_InitStructure;
/* 2 bit for pre-emption priority, 2 bits for subpriority */
NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2);
#ifdef STM32F10X_CL
/* Enable the USB Interrupts */
NVIC_InitStructure.NVIC_IRQChannel = OTG_FS_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
#else
NVIC_InitStructure.NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
#endif /* STM32F10X_CL */
/* Enable the EXTI9_5 Interrupt */
NVIC_InitStructure.NVIC_IRQChannel = EXTI9_5_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
NVIC_Init(&NVIC_InitStructure);
/* Enable the EXTI15_10 Interrupt */
NVIC_InitStructure.NVIC_IRQChannel = EXTI15_10_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
NVIC_Init(&NVIC_InitStructure);
/* Enable the DMA1 Channel1 Interrupt */
NVIC_InitStructure.NVIC_IRQChannel = DMA1_Channel1_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 2;
NVIC_Init(&NVIC_InitStructure);
}
/*******************************************************************************
* Function Name : USB_Cable_Config.
* Description : Software Connection/Disconnection of USB Cable.
* Input : NewState: new state.
* Output : None.
* Return : None.
* Return : None
*******************************************************************************/
void USB_Cable_Config (FunctionalState NewState)
{
{
#ifdef USE_STM3210C_EVAL
if (NewState != DISABLE)
{
@ -165,59 +277,6 @@ void USB_Cable_Config (FunctionalState NewState)
}
#endif /* USE_STM3210C_EVAL */
}
/*******************************************************************************
* Function Name : DFU_Button_Config.
* Description : Configures the DFU selector Button to enter DFU Mode.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void DFU_Button_Config(void)
{
/* Configure "DFU enter" button */
// STM_EVAL_PBInit(Button_KEY, Mode_GPIO);
}
/*******************************************************************************
* Function Name : DFU_Button_Read.
* Description : Reads the DFU selector Button to enter DFU Mode.
* Input : None.
* Output : None.
* Return : Status
*******************************************************************************/
uint8_t DFU_Button_Read (void)
{
return 0;//STM_EVAL_PBGetState(Button_KEY);
}
/*******************************************************************************
* Function Name : USB_Interrupts_Config.
* Description : Configures the USB interrupts.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void USB_Interrupts_Config(void)
{
NVIC_InitTypeDef NVIC_InitStructure;
#ifdef STM32F10X_CL
/* Enable the USB Interrupts */
NVIC_InitStructure.NVIC_IRQChannel = OTG_FS_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
#else
NVIC_InitStructure.NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
#endif /* STM32F10X_CL */
}
/*******************************************************************************
* Function Name : Reset_Device.
* Description : Reset the device.
@ -231,6 +290,58 @@ void Reset_Device(void)
NVIC_SystemReset();
}
/*******************************************************************************
* Function Name : GPIO_Configuration
* Description : Configures the different GPIO ports.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void GPIO_Configuration(void)
{
GPIO_InitTypeDef GPIO_InitStructure;
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIO_DISCONNECT |
RCC_APB2Periph_GPIO_IOAIN , ENABLE);
#ifndef USE_STM3210C_EVAL
/* USB_DISCONNECT used as USB pull-up */
GPIO_InitStructure.GPIO_Pin = USB_DISCONNECT_PIN;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_OD;
GPIO_Init(USB_DISCONNECT, &GPIO_InitStructure);
#endif /* USE_STM3210C_EVAL */
/* Configure Potentiometer IO as analog input */
GPIO_InitStructure.GPIO_Pin = GPIO_IOAIN_PIN;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AIN;
GPIO_Init(GPIO_IOAIN, &GPIO_InitStructure);
}
/*******************************************************************************
* Function Name : EXTI_Configuration.
* Description : Configure the EXTI lines for Key and Tamper push buttons.
* Input : None.
* Output : None.
* Return value : The direction value.
*******************************************************************************/
void EXTI_Configuration(void)
{
}
/*******************************************************************************
* Function Name : ADC_Configuration.
* Description : Configure the ADC and DMA.
* Input : None.
* Output : None.
* Return value : The direction value.
*******************************************************************************/
void ADC_Configuration(void)
{
}
/*******************************************************************************
* Function Name : Get_SerialNum.
* Description : Create the serial number string descriptor.
@ -250,8 +361,8 @@ void Get_SerialNum(void)
if (Device_Serial0 != 0)
{
IntToUnicode (Device_Serial0, &DFU_StringSerial[2] , 8);
IntToUnicode (Device_Serial1, &DFU_StringSerial[18], 4);
IntToUnicode (Device_Serial0, &CustomHID_StringSerial[2] , 8);
IntToUnicode (Device_Serial1, &CustomHID_StringSerial[18], 4);
}
}

View File

@ -0,0 +1,70 @@
/*
* common.h
*
* Created on: 2010/08/18
* Author: Programacao
*/
#ifndef COMMON_H_
#define COMMON_H_
/**************************************************/
/* OP_DFU Memory locations */
/**************************************************/
#define StartOfUserCode 0x08006000
/**************************************************/
/* OP_DFU Mem Sizes */
/**************************************************/
#define SizeOfHash 60
#define SizeOfDescription 100
#define SizoOfCode 100
/**************************************************/
/* OP_DFU states */
/**************************************************/
#define DFUidle 0
#define uploading 1
#define wrong_packet_received 2
#define too_many_packets 3
#define too_few_packets 4
#define Last_operation_Success 5
#define downloading 6
#define idle 7
#define Last_operation_failed 8
#define uploadingStarting 9
/**************************************************/
/* OP_DFU commands */
/**************************************************/
#define Reserved 0
#define Req_Capabilities 1
#define Rep_Capabilities 2
#define EnterDFU 3
#define JumpFW 4
#define Reset 5
#define Abort_Operation 6
#define Upload 7
#define Op_END 8
#define Download_Req 9
#define Download 10
#define Status_Request 11
#define Status_Rep 12
/**************************************************/
/* OP_DFU transfer types */
/**************************************************/
#define FW 0
#define Hash 1
#define Descript 2
#define DownloadDelay 100000
#endif /* COMMON_H_ */

View File

@ -12,36 +12,30 @@
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __HW_CONFIG_H
#define __HW_CONFIG_H
/* Includes ------------------------------------------------------------------*/
#include "usb_type.h"
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* Flash memory address from where user application will be loaded */
#define ApplicationAddress 0x08003000
/* Exported macro ------------------------------------------------------------*/
/* Exported define -----------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
void Set_System(void);
void Set_USBClock(void);
void Enter_LowPowerMode(void);
void Leave_LowPowerMode(void);
void USB_Cable_Config (FunctionalState NewState);
void USB_Interrupts_Config(void);
void DFU_Button_Config(void);
uint8_t DFU_Button_Read(void);
void Reset_Device(void);
void SMI_FLASH_Init(void);
void SMI_FLASH_SectorErase(uint32_t Address);
void SMI_FLASH_WordWrite(uint32_t Address, uint32_t Data);
void SMI_FLASH_PageWrite(uint32_t Address, uint32_t* wBuffer);
void USB_Cable_Config (FunctionalState NewState);
void GPIO_Configuration(void);
void EXTI_Configuration(void);
void ADC_Configuration(void);
void Get_SerialNum(void);
/* External variables --------------------------------------------------------*/
void Reset_Device(void);
#endif /*__HW_CONFIG_H*/
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -18,7 +18,6 @@
#define __PLATFORM_CONFIG_H
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
@ -43,15 +42,21 @@
#define RCC_APB2Periph_GPIO_DISCONNECT RCC_APB2Periph_GPIOC
#elif defined (USE_STM3210C_EVAL)
#define USB_DISCONNECT GPIOC
#define USB_DISCONNECT_PIN GPIO_Pin_4
#define RCC_APB2Periph_GPIO_DISCONNECT RCC_APB2Periph_GPIOC
#define USB_DISCONNECT 0
#define USB_DISCONNECT_PIN 0
#define RCC_APB2Periph_GPIO_DISCONNECT 0
#endif /* USE_STM3210B_EVAL */
#define RCC_APB2Periph_GPIO_IOAIN RCC_APB2Periph_GPIOC
#define GPIO_IOAIN GPIOC
#define GPIO_IOAIN_PIN GPIO_Pin_4 /* PC.04 */
#define ADC_AIN_CHANNEL ADC_Channel_14
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
#endif /* __PLATFORM_CONFIG_H */
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -60,7 +60,15 @@
/** @addtogroup STM3210E_EVAL_LOW_LEVEL_LED
* @{
*/
#define LEDn 2
#define LED1_PIN GPIO_Pin_12
#define LED1_GPIO_PORT GPIOC
#define LED1_GPIO_CLK RCC_APB2Periph_GPIOC
#define LED2_PIN GPIO_Pin_13
#define LED2_GPIO_PORT GPIOC
#define LED2_GPIO_CLK RCC_APB2Periph_GPIOC
/**
* @}
@ -276,7 +284,10 @@
/** @defgroup STM3210E_EVAL_LOW_LEVEL_Exported_Functions
* @{
*/
void STM_EVAL_LEDInit(Led_TypeDef Led);
void STM_EVAL_LEDOn(Led_TypeDef Led);
void STM_EVAL_LEDOff(Led_TypeDef Led);
void STM_EVAL_LEDToggle(Led_TypeDef Led);
void STM_EVAL_PBInit(Button_TypeDef Button, ButtonMode_TypeDef Button_Mode);
uint32_t STM_EVAL_PBGetState(Button_TypeDef Button);
void STM_EVAL_COMInit(COM_TypeDef COM, USART_InitTypeDef* USART_InitStruct);

View File

@ -76,6 +76,13 @@
* @{
*/
typedef enum
{
LED1 = 0,
LED2 = 1,
LED3 = 2,
LED4 = 3
} Led_TypeDef;
typedef enum
{

View File

@ -19,24 +19,24 @@
/* Includes ------------------------------------------------------------------*/
/* Uncomment the line below to enable peripheral header file inclusion */
/* #include "stm32f10x_adc.h" */
#include "stm32f10x_adc.h"
/* #include "stm32f10x_bkp.h" */
/* #include "stm32f10x_can.h" */
/* #include "stm32f10x_crc.h" */
/* #include "stm32f10x_dac.h" */
/* #include "stm32f10x_dbgmcu.h" */
/* #include "stm32f10x_dma.h" */
#include "stm32f10x_dma.h"
#include "stm32f10x_exti.h"
#include "stm32f10x_flash.h"
#include "stm32f10x_fsmc.h"
#include "stm32f10x_flash.h"
/* #include "stm32f10x_fsmc.h" */
#include "stm32f10x_gpio.h"
/* #include "stm32f10x_i2c.h" */
#include "stm32f10x_i2c.h"
/* #include "stm32f10x_iwdg.h" */
/* #include "stm32f10x_pwr.h" */
#include "stm32f10x_rcc.h"
/* #include "stm32f10x_rtc.h" */
/* #include "stm32f10x_sdio.h" */
#include "stm32f10x_spi.h"
/* #include "stm32f10x_spi.h" */
/* #include "stm32f10x_tim.h" */
#include "stm32f10x_usart.h"
/* #include "stm32f10x_wwdg.h" */

View File

@ -39,6 +39,10 @@ void SysTick_Handler(void);
void USB_LP_CAN1_RX0_IRQHandler(void);
#endif /* STM32F10X_CL */
void DMA1_Channel1_IRQHandler(void);
void EXTI9_5_IRQHandler(void);
void EXTI15_10_IRQHandler(void);
#ifdef STM32F10X_CL
void OTG_FS_IRQHandler(void);
#endif /* STM32F10X_CL */
@ -46,4 +50,3 @@ void OTG_FS_IRQHandler(void);
#endif /* __STM32F10x_IT_H */
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -3,7 +3,7 @@
* Author : MCD Application Team
* Version : V3.2.1
* Date : 07/05/2010
* Description : Device Firmware Upgrade (DFU) configuration file
* Description : Custom HID demo configuration file
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
@ -27,7 +27,7 @@
/* EP_NUM */
/* defines how many endpoints are used by the device */
/*-------------------------------------------------------------*/
#define EP_NUM (1)
#define EP_NUM (2)
#ifndef STM32F10X_CL
/*-------------------------------------------------------------*/
@ -37,11 +37,15 @@
/* buffer table base address */
#define BTABLE_ADDRESS (0x00)
/* EP0 */
/* EP0 */
/* rx/tx buffer base address */
#define ENDP0_RXADDR (0x10)
#define ENDP0_TXADDR (0x50)
#define ENDP0_RXADDR (0x18)
#define ENDP0_TXADDR (0x58)
/* EP1 */
/* tx buffer base address */
#define ENDP1_TXADDR (0x100)
#define ENDP1_RXADDR (0x124)
/*-------------------------------------------------------------*/
/* ------------------- ISTR events -------------------------*/
@ -49,18 +53,12 @@
/* IMR_MSK */
/* mask defining which events has to be handled */
/* by the device application software */
#define IMR_MSK (CNTR_CTRM | \
CNTR_WKUPM | \
CNTR_SUSPM | \
CNTR_ERRM | \
CNTR_SOFM | \
CNTR_ESOFM | \
CNTR_RESETM \
)
#define IMR_MSK (CNTR_CTRM | CNTR_WKUPM | CNTR_SUSPM | CNTR_ERRM | CNTR_SOFM \
| CNTR_ESOFM | CNTR_RESETM )
#endif /* STM32F10X_CL */
#ifdef STM32F10X_CL
/*******************************************************************************
* FIFO Size Configuration
*
@ -108,7 +106,6 @@
#define TX2_FIFO_SIZE 16
#define TX3_FIFO_SIZE 16
/* OTGD-FS-DEVICE IP interrupts Enable definitions */
/* Uncomment the define to enable the selected interrupt */
//#define INTR_MODEMISMATCH
@ -164,6 +161,7 @@
#endif /* STM32F10X_CL */
/* CTR service routines */
/* associated to defined endpoints */
#define EP1_IN_Callback NOP_Process
@ -174,8 +172,7 @@
#define EP6_IN_Callback NOP_Process
#define EP7_IN_Callback NOP_Process
#define EP1_OUT_Callback NOP_Process
//#define EP1_OUT_Callback NOP_Process
#define EP2_OUT_Callback NOP_Process
#define EP3_OUT_Callback NOP_Process
#define EP4_OUT_Callback NOP_Process
@ -187,6 +184,3 @@
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,56 @@
/******************** (C) COPYRIGHT 2010 STMicroelectronics ********************
* File Name : usb_desc.h
* Author : MCD Application Team
* Version : V3.2.1
* Date : 07/05/2010
* Description : Descriptor Header for Custom HID Demo
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __USB_DESC_H
#define __USB_DESC_H
/* Includes ------------------------------------------------------------------*/
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
/* Exported define -----------------------------------------------------------*/
#define USB_DEVICE_DESCRIPTOR_TYPE 0x01
#define USB_CONFIGURATION_DESCRIPTOR_TYPE 0x02
#define USB_STRING_DESCRIPTOR_TYPE 0x03
#define USB_INTERFACE_DESCRIPTOR_TYPE 0x04
#define USB_ENDPOINT_DESCRIPTOR_TYPE 0x05
#define HID_DESCRIPTOR_TYPE 0x21
#define CUSTOMHID_SIZ_HID_DESC 0x09
#define CUSTOMHID_OFF_HID_DESC 0x12
#define CUSTOMHID_SIZ_DEVICE_DESC 18
#define CUSTOMHID_SIZ_CONFIG_DESC 41
#define CUSTOMHID_SIZ_REPORT_DESC 36//163
#define CUSTOMHID_SIZ_STRING_LANGID 4
#define CUSTOMHID_SIZ_STRING_VENDOR 38
#define CUSTOMHID_SIZ_STRING_PRODUCT 32
#define CUSTOMHID_SIZ_STRING_SERIAL 26
#define STANDARD_ENDPOINT_DESC_SIZE 0x09
/* Exported functions ------------------------------------------------------- */
extern const uint8_t CustomHID_DeviceDescriptor[CUSTOMHID_SIZ_DEVICE_DESC];
extern const uint8_t CustomHID_ConfigDescriptor[CUSTOMHID_SIZ_CONFIG_DESC];
extern const uint8_t CustomHID_ReportDescriptor[CUSTOMHID_SIZ_REPORT_DESC];
extern const uint8_t CustomHID_StringLangID[CUSTOMHID_SIZ_STRING_LANGID];
extern const uint8_t CustomHID_StringVendor[CUSTOMHID_SIZ_STRING_VENDOR];
extern const uint8_t CustomHID_StringProduct[CUSTOMHID_SIZ_STRING_PRODUCT];
extern uint8_t CustomHID_StringSerial[CUSTOMHID_SIZ_STRING_SERIAL];
#endif /* __USB_DESC_H */
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -84,7 +84,7 @@ void SOF_Callback(void);
void ESOF_Callback(void);
#endif
#endif
#else /* STM32F10X_CL */
/* Interrupt subroutines user callbacks prototypes.
These callbacks are called into the respective interrupt sunroutine functinos
@ -113,7 +113,7 @@ void INTR_WKUPINTR_Callback(void);
/* Isochronous data update */
void INTR_RXSTSQLVL_ISODU_Callback(void);
#endif /* STM32F10X_CL */
#endif /*__USB_ISTR_H*/

View File

@ -0,0 +1,70 @@
/******************** (C) COPYRIGHT 2010 STMicroelectronics ********************
* File Name : usb_prop.h
* Author : MCD Application Team
* Version : V3.2.1
* Date : 07/05/2010
* Description : All processings related to Custom HID demo
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __USB_PROP_H
#define __USB_PROP_H
/* Includes ------------------------------------------------------------------*/
/* Exported types ------------------------------------------------------------*/
typedef enum _HID_REQUESTS
{
GET_REPORT = 1,
GET_IDLE,
GET_PROTOCOL,
SET_REPORT = 9,
SET_IDLE,
SET_PROTOCOL
} HID_REQUESTS;
/* Exported constants --------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
void CustomHID_init(void);
void CustomHID_Reset(void);
void CustomHID_SetConfiguration(void);
void CustomHID_SetDeviceAddress (void);
void CustomHID_Status_In (void);
void CustomHID_Status_Out (void);
RESULT CustomHID_Data_Setup(uint8_t);
RESULT CustomHID_NoData_Setup(uint8_t);
RESULT CustomHID_Get_Interface_Setting(uint8_t Interface, uint8_t AlternateSetting);
uint8_t *CustomHID_GetDeviceDescriptor(uint16_t );
uint8_t *CustomHID_GetConfigDescriptor(uint16_t);
uint8_t *CustomHID_GetStringDescriptor(uint16_t);
RESULT CustomHID_SetProtocol(void);
uint8_t *CustomHID_GetProtocolValue(uint16_t Length);
RESULT CustomHID_SetProtocol(void);
uint8_t *CustomHID_GetReportDescriptor(uint16_t Length);
uint8_t *CustomHID_GetHIDDescriptor(uint16_t Length);
/* Exported define -----------------------------------------------------------*/
#define CustomHID_GetConfiguration NOP_Process
//#define CustomHID_SetConfiguration NOP_Process
#define CustomHID_GetInterface NOP_Process
#define CustomHID_SetInterface NOP_Process
#define CustomHID_GetStatus NOP_Process
#define CustomHID_ClearFeature NOP_Process
#define CustomHID_SetEndPointFeature NOP_Process
#define CustomHID_SetDeviceFeature NOP_Process
//#define CustomHID_SetDeviceAddress NOP_Process
#define REPORT_DESCRIPTOR 0x22
#endif /* __USB_PROP_H */
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -12,9 +12,11 @@
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __USB_PWR_H
#define __USB_PWR_H
/* Includes ------------------------------------------------------------------*/
/* Exported types ------------------------------------------------------------*/
typedef enum _RESUME_STATE
@ -38,6 +40,7 @@ typedef enum _DEVICE_STATE
ADDRESSED,
CONFIGURED
} DEVICE_STATE;
/* Exported constants --------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
@ -47,7 +50,7 @@ void Resume(RESUME_STATE eResumeSetVal);
RESULT PowerOn(void);
RESULT PowerOff(void);
/* External variables --------------------------------------------------------*/
extern __IO uint32_t bDeviceState; /* USB device status */
extern __IO uint32_t bDeviceState; /* USB device status */
extern __IO bool fSuspendEnabled; /* true when suspend is possible */
#endif /*__USB_PWR_H*/

View File

@ -3,7 +3,7 @@
* Author : MCD Application Team
* Version : V3.2.1
* Date : 07/05/2010
* Description : Device Firmware Upgrade(DFU) demo main file
* Description : Custom HID demo main file
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
@ -16,26 +16,25 @@
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
#include "usb_lib.h"
#include "usb_conf.h"
#include "usb_prop.h"
#include "usb_pwr.h"
#include "dfu_mal.h"
#include "hw_config.h"
#include "platform_config.h"
#include "stm32_eval.h"
#include "common.h"
extern void FLASH_Download();
/* Private typedef -----------------------------------------------------------*/
typedef void (*pFunction)(void);
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Extern variables ----------------------------------------------------------*/
uint8_t DeviceState;
uint8_t DeviceStatus[6];
pFunction Jump_To_Application;
uint32_t JumpAddress;
/* Extern variables ----------------------------------------------------------*/
uint8_t DeviceState;
uint8_t JumpToApp=0;
/* Private function prototypes -----------------------------------------------*/
void Delay(__IO uint32_t nCount);
void DelayWithDown(__IO uint32_t nCount);
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
@ -47,38 +46,77 @@ uint32_t JumpAddress;
*******************************************************************************/
int main(void)
{
DFU_Button_Config();
/* Check if the Key push-button on STM3210x-EVAL Board is pressed */
if (DFU_Button_Read() != 0x00)
{ /* Test if user code is programmed starting from address 0x8003000 */
if (((*(__IO uint32_t*)ApplicationAddress) & 0x2FFE0000 ) == 0x20000000)
{ /* Jump to user application */
JumpAddress = *(__IO uint32_t*) (ApplicationAddress + 4);
Jump_To_Application = (pFunction) JumpAddress;
/* Initialize user application's Stack Pointer */
__set_MSP(*(__IO uint32_t*) ApplicationAddress);
Jump_To_Application();
}
} /* Otherwise enters DFU mode to allow user to program his application */
/* Enter DFU mode */
DeviceState = STATE_dfuERROR;
DeviceStatus[0] = STATUS_ERRFIRMWARE;
DeviceStatus[4] = DeviceState;
if (((*(__IO uint32_t*)StartOfUserCode) & 0x2FFE0000 ) == 0x20000000)
{ /* Jump to user application */
JumpAddress = *(__IO uint32_t*) (StartOfUserCode + 4);
Jump_To_Application = (pFunction) JumpAddress;
/* Initialize user application's Stack Pointer */
__set_MSP(*(__IO uint32_t*) StartOfUserCode);
Jump_To_Application();
}
Set_System();
USB_Interrupts_Config();
Set_USBClock();
USB_Init();
/* Main loop */
while (1)
{}
DeviceState=idle;
while (JumpToApp==0)
{
STM_EVAL_LEDToggle(LED1);
DelayWithDown(10);//1000000);
}
if (((*(__IO uint32_t*)StartOfUserCode) & 0x2FFE0000 ) == 0x20000000)
{ /* Jump to user application */
JumpAddress = *(__IO uint32_t*) (StartOfUserCode + 4);
Jump_To_Application = (pFunction) JumpAddress;
/* Initialize user application's Stack Pointer */
__set_MSP(*(__IO uint32_t*) StartOfUserCode);
Jump_To_Application();
}
while(1)
{
STM_EVAL_LEDToggle(LED1);
STM_EVAL_LEDToggle(LED2);
Delay(1000000);
}
}
/*******************************************************************************
* Function Name : Delay
* Description : Inserts a delay time.
* Input : nCount: specifies the delay time length.
* Output : None
* Return : None
*******************************************************************************/
void Delay(__IO uint32_t nCount)
{
for(; nCount!= 0;nCount--)
{
#ifdef USE_FULL_ASSERT
}
}
/*******************************************************************************
* Function Name : Delay
* Description : Inserts a delay time.
* Input : nCount: specifies the delay time length.
* Output : None
* Return : None
*******************************************************************************/
void DelayWithDown(__IO uint32_t nCount)
{
for(; nCount!= 0;nCount--)
{
for(__IO uint32_t delay=DownloadDelay ; delay!=0 ; delay--){}
FLASH_Download();
}
}
#ifdef USE_FULL_ASSERT
/*******************************************************************************
* Function Name : assert_failed
* Description : Reports the name of the source file and the source line number
@ -89,13 +127,15 @@ int main(void)
* Return : None
*******************************************************************************/
void assert_failed(uint8_t* file, uint32_t line)
{
{
/* 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) */
/* Infinite loop */
while (1)
{}
while(1)
{
}
}
#endif
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,391 @@
/**
******************************************************************************
* @file stm3210e_eval.c
* @author MCD Application Team
* @version V4.2.0
* @date 04/16/2010
* @brief This file provides
* - set of firmware functions to manage Leds, push-button and COM ports
* - low level initialization functions for SD card (on SDIO), SPI serial
* flash (sFLASH) and temperature sensor (LM75)
* available on STM3210E-EVAL evaluation board from STMicroelectronics.
******************************************************************************
* @copy
*
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* <h2><center>&copy; COPYRIGHT 2010 STMicroelectronics</center></h2>
*/
/* Includes ------------------------------------------------------------------*/
#include "stm3210e_eval.h"
#include "stm32f10x_spi.h"
#include "stm32f10x_i2c.h"
#include "stm32f10x_sdio.h"
#include "stm32f10x_dma.h"
/** @addtogroup Utilities
* @{
*/
/** @addtogroup STM32_EVAL
* @{
*/
/** @addtogroup STM3210E_EVAL
* @{
*/
/** @defgroup STM3210E_EVAL_LOW_LEVEL
* @brief This file provides firmware functions to manage Leds, push-buttons,
* COM ports, SD card on SDIO, serial flash (sFLASH), serial EEPROM (sEE)
* and temperature sensor (LM75) available on STM3210E-EVAL evaluation
* board from STMicroelectronics.
* @{
*/
/** @defgroup STM3210E_EVAL_LOW_LEVEL_Private_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @defgroup STM3210E_EVAL_LOW_LEVEL_Private_Defines
* @{
*/
/**
* @}
*/
/** @defgroup STM3210E_EVAL_LOW_LEVEL_Private_Macros
* @{
*/
/**
* @}
*/
/** @defgroup STM3210E_EVAL_LOW_LEVEL_Private_Variables
* @{
*/
GPIO_TypeDef* GPIO_PORT[LEDn] = {LED1_GPIO_PORT, LED2_GPIO_PORT};
const uint16_t GPIO_PIN[LEDn] = {LED1_PIN, LED2_PIN};
const uint32_t GPIO_CLK[LEDn] = {LED1_GPIO_CLK, LED2_GPIO_CLK};
GPIO_TypeDef* BUTTON_PORT[BUTTONn] = {WAKEUP_BUTTON_GPIO_PORT, TAMPER_BUTTON_GPIO_PORT,
KEY_BUTTON_GPIO_PORT, RIGHT_BUTTON_GPIO_PORT,
LEFT_BUTTON_GPIO_PORT, UP_BUTTON_GPIO_PORT,
DOWN_BUTTON_GPIO_PORT, SEL_BUTTON_GPIO_PORT};
const uint16_t BUTTON_PIN[BUTTONn] = {WAKEUP_BUTTON_PIN, TAMPER_BUTTON_PIN,
KEY_BUTTON_PIN, RIGHT_BUTTON_PIN,
LEFT_BUTTON_PIN, UP_BUTTON_PIN,
DOWN_BUTTON_PIN, SEL_BUTTON_PIN};
const uint32_t BUTTON_CLK[BUTTONn] = {WAKEUP_BUTTON_GPIO_CLK, TAMPER_BUTTON_GPIO_CLK,
KEY_BUTTON_GPIO_CLK, RIGHT_BUTTON_GPIO_CLK,
LEFT_BUTTON_GPIO_CLK, UP_BUTTON_GPIO_CLK,
DOWN_BUTTON_GPIO_CLK, SEL_BUTTON_GPIO_CLK};
const uint16_t BUTTON_EXTI_LINE[BUTTONn] = {WAKEUP_BUTTON_EXTI_LINE,
TAMPER_BUTTON_EXTI_LINE,
KEY_BUTTON_EXTI_LINE,
RIGHT_BUTTON_EXTI_LINE,
LEFT_BUTTON_EXTI_LINE,
UP_BUTTON_EXTI_LINE,
DOWN_BUTTON_EXTI_LINE,
SEL_BUTTON_EXTI_LINE};
const uint16_t BUTTON_PORT_SOURCE[BUTTONn] = {WAKEUP_BUTTON_EXTI_PORT_SOURCE,
TAMPER_BUTTON_EXTI_PORT_SOURCE,
KEY_BUTTON_EXTI_PORT_SOURCE,
RIGHT_BUTTON_EXTI_PORT_SOURCE,
LEFT_BUTTON_EXTI_PORT_SOURCE,
UP_BUTTON_EXTI_PORT_SOURCE,
DOWN_BUTTON_EXTI_PORT_SOURCE,
SEL_BUTTON_EXTI_PORT_SOURCE};
const uint16_t BUTTON_PIN_SOURCE[BUTTONn] = {WAKEUP_BUTTON_EXTI_PIN_SOURCE,
TAMPER_BUTTON_EXTI_PIN_SOURCE,
KEY_BUTTON_EXTI_PIN_SOURCE,
RIGHT_BUTTON_EXTI_PIN_SOURCE,
LEFT_BUTTON_EXTI_PIN_SOURCE,
UP_BUTTON_EXTI_PIN_SOURCE,
DOWN_BUTTON_EXTI_PIN_SOURCE,
SEL_BUTTON_EXTI_PIN_SOURCE};
const uint16_t BUTTON_IRQn[BUTTONn] = {WAKEUP_BUTTON_EXTI_IRQn, TAMPER_BUTTON_EXTI_IRQn,
KEY_BUTTON_EXTI_IRQn, RIGHT_BUTTON_EXTI_IRQn,
LEFT_BUTTON_EXTI_IRQn, UP_BUTTON_EXTI_IRQn,
DOWN_BUTTON_EXTI_IRQn, SEL_BUTTON_EXTI_IRQn};
USART_TypeDef* COM_USART[COMn] = {EVAL_COM1, EVAL_COM2};
GPIO_TypeDef* COM_TX_PORT[COMn] = {EVAL_COM1_TX_GPIO_PORT, EVAL_COM2_TX_GPIO_PORT};
GPIO_TypeDef* COM_RX_PORT[COMn] = {EVAL_COM1_RX_GPIO_PORT, EVAL_COM2_RX_GPIO_PORT};
const uint32_t COM_USART_CLK[COMn] = {EVAL_COM1_CLK, EVAL_COM2_CLK};
const uint32_t COM_TX_PORT_CLK[COMn] = {EVAL_COM1_TX_GPIO_CLK, EVAL_COM2_TX_GPIO_CLK};
const uint32_t COM_RX_PORT_CLK[COMn] = {EVAL_COM1_RX_GPIO_CLK, EVAL_COM2_RX_GPIO_CLK};
const uint16_t COM_TX_PIN[COMn] = {EVAL_COM1_TX_PIN, EVAL_COM2_TX_PIN};
const uint16_t COM_RX_PIN[COMn] = {EVAL_COM1_RX_PIN, EVAL_COM2_RX_PIN};
/**
* @}
*/
/** @defgroup STM3210E_EVAL_LOW_LEVEL_Private_FunctionPrototypes
* @{
*/
/**
* @}
*/
/** @defgroup STM3210E_EVAL_LOW_LEVEL_Private_Functions
* @{
*/
/**
* @brief Configures LED GPIO.
* @param Led: Specifies the Led to be configured.
* This parameter can be one of following parameters:
* @arg LED1
* @arg LED2
* @arg LED3
* @arg LED4
* @retval None
*/
void STM_EVAL_LEDInit(Led_TypeDef Led)
{
GPIO_InitTypeDef GPIO_InitStructure;
/* Enable the GPIO_LED Clock */
RCC_APB2PeriphClockCmd(GPIO_CLK[Led], ENABLE);
/* Configure the GPIO_LED pin */
GPIO_InitStructure.GPIO_Pin = GPIO_PIN[Led];
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_Init(GPIO_PORT[Led], &GPIO_InitStructure);
GPIO_PORT[Led]->BSRR = GPIO_PIN[Led];
}
/**
* @brief Turns selected LED On.
* @param Led: Specifies the Led to be set on.
* This parameter can be one of following parameters:
* @arg LED1
* @arg LED2
* @arg LED3
* @arg LED4
* @retval None
*/
void STM_EVAL_LEDOn(Led_TypeDef Led)
{
GPIO_PORT[Led]->BRR = GPIO_PIN[Led];
}
/**
* @brief Turns selected LED Off.
* @param Led: Specifies the Led to be set off.
* This parameter can be one of following parameters:
* @arg LED1
* @arg LED2
* @arg LED3
* @arg LED4
* @retval None
*/
void STM_EVAL_LEDOff(Led_TypeDef Led)
{
GPIO_PORT[Led]->BSRR = GPIO_PIN[Led];
}
/**
* @brief Toggles the selected LED.
* @param Led: Specifies the Led to be toggled.
* This parameter can be one of following parameters:
* @arg LED1
* @arg LED2
* @arg LED3
* @arg LED4
* @retval None
*/
void STM_EVAL_LEDToggle(Led_TypeDef Led)
{
GPIO_PORT[Led]->ODR ^= GPIO_PIN[Led];
}
/**
* @brief Configures Button GPIO and EXTI Line.
* @param Button: Specifies the Button to be configured.
* This parameter can be one of following parameters:
* @arg BUTTON_WAKEUP: Wakeup Push Button
* @arg BUTTON_TAMPER: Tamper Push Button
* @arg BUTTON_KEY: Key Push Button
* @arg BUTTON_RIGHT: Joystick Right Push Button
* @arg BUTTON_LEFT: Joystick Left Push Button
* @arg BUTTON_UP: Joystick Up Push Button
* @arg BUTTON_DOWN: Joystick Down Push Button
* @arg BUTTON_SEL: Joystick Sel Push Button
* @param Button_Mode: Specifies Button mode.
* This parameter can be one of following parameters:
* @arg BUTTON_MODE_GPIO: Button will be used as simple IO
* @arg BUTTON_MODE_EXTI: Button will be connected to EXTI line with interrupt
* generation capability
* @retval None
*/
void STM_EVAL_PBInit(Button_TypeDef Button, ButtonMode_TypeDef Button_Mode)
{
}
/**
* @brief Returns the selected Button state.
* @param Button: Specifies the Button to be checked.
* This parameter can be one of following parameters:
* @arg BUTTON_WAKEUP: Wakeup Push Button
* @arg BUTTON_TAMPER: Tamper Push Button
* @arg BUTTON_KEY: Key Push Button
* @arg BUTTON_RIGHT: Joystick Right Push Button
* @arg BUTTON_LEFT: Joystick Left Push Button
* @arg BUTTON_UP: Joystick Up Push Button
* @arg BUTTON_DOWN: Joystick Down Push Button
* @arg BUTTON_SEL: Joystick Sel Push Button
* @retval The Button GPIO pin value.
*/
uint32_t STM_EVAL_PBGetState(Button_TypeDef Button)
{
return GPIO_ReadInputDataBit(BUTTON_PORT[Button], BUTTON_PIN[Button]);
}
/**
* @brief Configures COM port.
* @param COM: Specifies the COM port to be configured.
* This parameter can be one of following parameters:
* @arg COM1
* @arg COM2
* @param USART_InitStruct: pointer to a USART_InitTypeDef structure that
* contains the configuration information for the specified USART peripheral.
* @retval None
*/
/**
* @brief DeInitializes the SDIO interface.
* @param None
* @retval None
*/
void SD_LowLevel_DeInit(void)
{
GPIO_InitTypeDef GPIO_InitStructure;
/*!< Disable SDIO Clock */
SDIO_ClockCmd(DISABLE);
/*!< Set Power State to OFF */
SDIO_SetPowerState(SDIO_PowerState_OFF);
/*!< DeInitializes the SDIO peripheral */
SDIO_DeInit();
/*!< Disable the SDIO AHB Clock */
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_SDIO, DISABLE);
/*!< Configure PC.08, PC.09, PC.10, PC.11, PC.12 pin: D0, D1, D2, D3, CLK pin */
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_8 | GPIO_Pin_9 | GPIO_Pin_10 | GPIO_Pin_11 | GPIO_Pin_12;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
GPIO_Init(GPIOC, &GPIO_InitStructure);
/*!< Configure PD.02 CMD line */
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_2;
GPIO_Init(GPIOD, &GPIO_InitStructure);
}
/**
* @brief Initializes the SD Card and put it into StandBy State (Ready for
* data transfer).
* @param None
* @retval None
*/
void SD_LowLevel_Init(void)
{
GPIO_InitTypeDef GPIO_InitStructure;
/*!< GPIOC and GPIOD Periph clock enable */
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC | RCC_APB2Periph_GPIOD | SD_DETECT_GPIO_CLK, ENABLE);
/*!< Configure PC.08, PC.09, PC.10, PC.11, PC.12 pin: D0, D1, D2, D3, CLK pin */
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_8 | GPIO_Pin_9 | GPIO_Pin_10 | GPIO_Pin_11 | GPIO_Pin_12;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
GPIO_Init(GPIOC, &GPIO_InitStructure);
/*!< Configure PD.02 CMD line */
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_2;
GPIO_Init(GPIOD, &GPIO_InitStructure);
/*!< Configure SD_SPI_DETECT_PIN pin: SD Card detect pin */
GPIO_InitStructure.GPIO_Pin = SD_DETECT_PIN;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPU;
GPIO_Init(SD_DETECT_GPIO_PORT, &GPIO_InitStructure);
/*!< Enable the SDIO AHB Clock */
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_SDIO, ENABLE);
/*!< Enable the DMA2 Clock */
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA2, ENABLE);
}
/**
* @brief Configures the DMA2 Channel4 for SDIO Tx request.
* @param BufferSRC: pointer to the source buffer
* @param BufferSize: buffer size
* @retval None
*/
/**
* @brief DeInitializes the LM75_I2C.
* @param None
* @retval None
*/
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -16,16 +16,21 @@
*******************************************************************************/
/* Includes ------------------------------------------------------------------*/
#include "platform_config.h"
#include "stm32f10x_it.h"
#include "usb_lib.h"
#include "usb_istr.h"
#include "usb_prop.h"
#include "usb_pwr.h"
#include "stm32_eval.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
__IO uint8_t Send_Buffer[2];
extern uint32_t ADC_ConvertedValueX;
extern uint32_t ADC_ConvertedValueX_1;
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
@ -167,6 +172,114 @@ void USB_LP_CAN1_RX0_IRQHandler(void)
}
#endif /* STM32F10X_CL */
/*******************************************************************************
* Function Name : DMA1_Channel1_IRQHandler
* Description : This function handles DMA1 Channel 1 interrupt request.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void DMA1_Channel1_IRQHandler(void)
{
while (1)
{
}
//TODO CLEAN
Send_Buffer[0] = 0x07;
if((ADC_ConvertedValueX >>4) - (ADC_ConvertedValueX_1 >>4) > 4)
{
Send_Buffer[1] = (uint8_t)(ADC_ConvertedValueX >>4);
/* Write the descriptor through the endpoint */
USB_SIL_Write(EP1_IN, (uint8_t*) Send_Buffer, 2);
#ifndef STM32F10X_CL
SetEPTxValid(ENDP1);
#endif /* STM32F10X_CL */
ADC_ConvertedValueX_1 = ADC_ConvertedValueX;
}
DMA_ClearFlag(DMA1_FLAG_TC1);
}
/*******************************************************************************
* Function Name : EXTI9_5_IRQHandler
* Description : This function handles External lines 9 to 5 interrupt request.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void EXTI9_5_IRQHandler(void)
{
while (1)
{
}
//TODO CLEAN
if(EXTI_GetITStatus(KEY_BUTTON_EXTI_LINE) != RESET)
{
Send_Buffer[0] = 0x05;
if (STM_EVAL_PBGetState(Button_KEY) == Bit_RESET)
{
Send_Buffer[1] = 0x01;
}
else
{
Send_Buffer[1] = 0x00;
}
/* Write the descriptor through the endpoint */
USB_SIL_Write(EP1_IN, (uint8_t*) Send_Buffer, 2);
#ifndef STM32F10X_CL
SetEPTxValid(ENDP1);
#endif /* STM32F10X_CL */
/* Clear the EXTI line pending bit */
EXTI_ClearITPendingBit(KEY_BUTTON_EXTI_LINE);
}
}
/*******************************************************************************
* Function Name : EXTI15_10_IRQHandler
* Description : This function handles External lines 15 to 10 interrupt request.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void EXTI15_10_IRQHandler(void)
{
while (1)
{
}
//TODO CLEAN
if(EXTI_GetITStatus(TAMPER_BUTTON_EXTI_LINE) != RESET)
{
Send_Buffer[0] = 0x06;
if (STM_EVAL_PBGetState(Button_TAMPER) == Bit_RESET)
{
Send_Buffer[1] = 0x01;
}
else
{
Send_Buffer[1] = 0x00;
}
/* Write the descriptor through the endpoint */
USB_SIL_Write(EP1_IN, (uint8_t*) Send_Buffer, 2);
#ifndef STM32F10X_CL
SetEPTxValid(ENDP1);
#endif /* STM32F10X_CL */
/* Clear the EXTI line 13 pending bit */
EXTI_ClearITPendingBit(TAMPER_BUTTON_EXTI_LINE);
}
}
#ifdef STM32F10X_CL
/*******************************************************************************
* Function Name : OTG_FS_IRQHandler

View File

@ -0,0 +1,188 @@
/******************** (C) COPYRIGHT 2010 STMicroelectronics ********************
* File Name : usb_desc.c
* Author : MCD Application Team
* Version : V3.2.1
* Date : 07/05/2010
* Description : Descriptors for Custom HID Demo
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Includes ------------------------------------------------------------------*/
#include "usb_lib.h"
#include "usb_desc.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Extern variables ----------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/* USB Standard Device Descriptor */
#define VENDOR_ID 0x20A0
#define USB_PRODUCT_ID 0x4117
#define USB_VERSION_ID 0x0200
const uint8_t CustomHID_DeviceDescriptor[CUSTOMHID_SIZ_DEVICE_DESC] =
{
0x12, /*bLength */
USB_DEVICE_DESCRIPTOR_TYPE, /*bDescriptorType*/
0x00, /*bcdUSB */
0x02,
0x00, /*bDeviceClass*/
0x00, /*bDeviceSubClass*/
0x00, /*bDeviceProtocol*/
0x40, /*bMaxPacketSize40*/
(uint8_t)((VENDOR_ID) & 0xff), /*idVendor */
(uint8_t)((VENDOR_ID) >> 8),
(uint8_t)((USB_PRODUCT_ID) & 0xff), /*idProduct */
(uint8_t)((USB_PRODUCT_ID) >> 8),
(uint8_t)((USB_VERSION_ID) & 0xff), /*bcdDevice */
(uint8_t)((USB_VERSION_ID) >> 8),
1, /*Index of string descriptor describing
manufacturer */
2, /*Index of string descriptor describing
product*/
3, /*Index of string descriptor describing the
device serial number */
0x01 /*bNumConfigurations*/
}
; /* CustomHID_DeviceDescriptor */
/* USB Configuration Descriptor */
/* All Descriptors (Configuration, Interface, Endpoint, Class, Vendor */
const uint8_t CustomHID_ConfigDescriptor[CUSTOMHID_SIZ_CONFIG_DESC] =
{
0x09, /* bLength: Configuation Descriptor size */
USB_CONFIGURATION_DESCRIPTOR_TYPE, /* bDescriptorType: Configuration */
CUSTOMHID_SIZ_CONFIG_DESC,
/* wTotalLength: Bytes returned */
0x00,
0x01, /* bNumInterfaces: 1 interface */
0x01, /* bConfigurationValue: Configuration value */
0x00, /* iConfiguration: Index of string descriptor describing
the configuration*/
0xC0, /* bmAttributes: Bus powered */
0x32, /* MaxPower 100 mA: this current is used for detecting Vbus */
/************** Descriptor of Custom HID interface ****************/
/* 09 */
0x09, /* bLength: Interface Descriptor size */
USB_INTERFACE_DESCRIPTOR_TYPE,/* bDescriptorType: Interface descriptor type */
0x00, /* bInterfaceNumber: Number of Interface */
0x00, /* bAlternateSetting: Alternate setting */
0x02, /* bNumEndpoints */
0x03, /* bInterfaceClass: HID */
0x00, /* bInterfaceSubClass : 1=BOOT, 0=no boot */
0x00, /* nInterfaceProtocol : 0=none, 1=keyboard, 2=mouse */
0, /* iInterface: Index of string descriptor */
/******************** Descriptor of Custom HID HID ********************/
/* 18 */
0x09, /* bLength: HID Descriptor size */
HID_DESCRIPTOR_TYPE, /* bDescriptorType: HID */
0x10, /* bcdHID: HID Class Spec release number */
0x01,
0x00, /* bCountryCode: Hardware target country */
0x01, /* bNumDescriptors: Number of HID class descriptors to follow */
0x22, /* bDescriptorType */
CUSTOMHID_SIZ_REPORT_DESC,/* diff:36 wItemLength: Total length of Report descriptor */
0x00,
/******************** Descriptor of Custom HID endpoints ******************/
/* 27 */
0x07, /* bLength: Endpoint Descriptor size */
USB_ENDPOINT_DESCRIPTOR_TYPE, /* bDescriptorType: */
0x81, /* bEndpointAddress: Endpoint Address (IN) */
0x03, /* bmAttributes: Interrupt endpoint */
0x40, /* diff:0x40 wMaxPacketSize: 2 Bytes max */
0x00,
0x08, /* diff:0x08 bInterval: Polling Interval (32 ms) */
/* 34 */
0x07, /* bLength: Endpoint Descriptor size */
USB_ENDPOINT_DESCRIPTOR_TYPE, /* bDescriptorType: */
/* Endpoint descriptor type */
0x01, /* bEndpointAddress: */
/* Endpoint Address (OUT) */
0x03, /* bmAttributes: Interrupt endpoint */
0x40, /* diff:0x40 wMaxPacketSize: 2 Bytes max */
0x00,
0x08, /* diff:0x08 bInterval: Polling Interval (20 ms) */
/* 41 */
}
; /* diff:lots CustomHID_ConfigDescriptor */
const uint8_t CustomHID_ReportDescriptor[CUSTOMHID_SIZ_REPORT_DESC] =
{
0x06, 0x9c, 0xff, /* diff:0x06, 0x9c, 0xff, USAGE_PAGE (Vendor Page: 0xFF00) */
0x09, 0x01, /* USAGE (Demo Kit) */
0xa1, 0x01, /* COLLECTION (Application) */
/* 6 */
/* DATA 1 */
0x85, 0x01, /* REPORT_ID (1) */
0x09, 0x02, /* USAGE (LED 1) */
0x15, 0x00, /* LOGICAL_MINIMUM (0) */
0x25, 0xff, /* LOGICAL_MAXIMUM (1) */
0x75, 0x08, /* REPORT_SIZE (8) */
0x95, 9, /* REPORT_COUNT (1) */
0x81, 0x83, /* FEATURE (Data,Var,Abs,Vol) */
/* Led 2 */
0x85, 0x02, /* REPORT_ID 2 */
0x09, 0x03, /* USAGE (LED 2) */
0x15, 0x00, /* LOGICAL_MINIMUM (0) */
0x25, 0xff, /* LOGICAL_MAXIMUM (1) */
0x75, 0x08, /* REPORT_SIZE (8) */
0x95, 9, /* REPORT_COUNT (1) */
0x91, 0x82, /* FEATURE (Data,Var,Abs,Vol) */
/* 161 */
0xc0 /* END_COLLECTION */
}; /* CustomHID_ReportDescriptor */
/* USB String Descriptors (optional) */
const uint8_t CustomHID_StringLangID[CUSTOMHID_SIZ_STRING_LANGID] =
{
CUSTOMHID_SIZ_STRING_LANGID,
USB_STRING_DESCRIPTOR_TYPE,
0x09,
0x04
}
; /* LangID = 0x0409: U.S. English */
const uint8_t CustomHID_StringVendor[CUSTOMHID_SIZ_STRING_VENDOR] =
{
CUSTOMHID_SIZ_STRING_VENDOR, /* Size of Vendor string */
USB_STRING_DESCRIPTOR_TYPE, /* bDescriptorType*/
/* Manufacturer: "STMicroelectronics" */
'S', 0, 'T', 0, 'M', 0, 'i', 0, 'c', 0, 'r', 0, 'o', 0, 'e', 0,
'l', 0, 'e', 0, 'c', 0, 't', 0, 'r', 0, 'o', 0, 'n', 0, 'i', 0,
'c', 0, 's', 0
};
const uint8_t CustomHID_StringProduct[CUSTOMHID_SIZ_STRING_PRODUCT] =
{
CUSTOMHID_SIZ_STRING_PRODUCT, /* bLength */
USB_STRING_DESCRIPTOR_TYPE, /* bDescriptorType */
'S', 0, 'T', 0, 'M', 0, '3', 0, '2', 0, ' ', 0, 'C', 0,
'u', 0, 's', 0, 't', 0, 'm', 0, ' ', 0, 'H', 0, 'I', 0,
'D', 0
};
uint8_t CustomHID_StringSerial[CUSTOMHID_SIZ_STRING_SERIAL] =
{
CUSTOMHID_SIZ_STRING_SERIAL, /* bLength */
USB_STRING_DESCRIPTOR_TYPE, /* bDescriptorType */
'S', 0, 'T', 0, 'M', 0,'3', 0,'2', 0, '1', 0, '0', 0
};
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,326 @@
/******************** (C) COPYRIGHT 2010 STMicroelectronics ********************
* File Name : usb_endp.c
* Author : MCD Application Team
* Version : V3.2.1
* Date : 07/05/2010
* Description : Endpoint routines
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Includes ------------------------------------------------------------------*/
#include "platform_config.h"
#include "stm32f10x.h"
#include "usb_lib.h"
#include "usb_istr.h"
#include "stm32_eval.h"
#include "stm32f10x_flash.h"
#include "common.h"
#include "hw_config.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
uint8_t Receive_Buffer[10];
uint8_t Buffer[10];
uint8_t Command=0;
uint8_t EchoReqFlag=0;
uint8_t EchoAnsFlag=0;
uint8_t StartFlag=0;
uint32_t Aditionals=0;
uint32_t SizeOfTransfer=0;
uint32_t Next_Packet=0;
uint8_t TransferType;
uint32_t Count=0;
uint32_t Data;
uint8_t Data0;
uint8_t Data1;
uint8_t Data2;
uint8_t Data3;
//Download vars
volatile uint32_t downPacketCurrent=0;
uint32_t downPacketTotal=0;
uint8_t downType=0;
uint32_t MemLocations[3]=
{
StartOfUserCode, StartOfUserCode-SizeOfHash, StartOfUserCode-SizeOfHash-SizeOfDescription
};
/* Extern variables ----------------------------------------------------------*/
extern uint8_t DeviceState ;
extern uint8_t JumpToApp;
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
uint8_t *FLASH_If_Read (uint32_t SectorAddress, uint32_t DataLength)
{
return (uint8_t*)(SectorAddress);
}
void FLASH_Download() {
if (DeviceState == downloading) {
Buffer[0] = 0x01;
Buffer[1] = Download;
Buffer[2] = downPacketCurrent >> 24;
Buffer[3] = downPacketCurrent >> 16;
Buffer[4] = downPacketCurrent >> 8;
Buffer[5] = downPacketCurrent;
Buffer[6] = *FLASH_If_Read(MemLocations[downType]+downPacketCurrent*4, 0);
Buffer[7] = *FLASH_If_Read(MemLocations[downType] + 1+downPacketCurrent*4, 0);
Buffer[8] = *FLASH_If_Read(MemLocations[downType] + 2+downPacketCurrent*4, 0);
Buffer[9] = *FLASH_If_Read(MemLocations[downType] + 3+downPacketCurrent*4, 0);
USB_SIL_Write(EP1_IN, (uint8_t*) Buffer, 10);
downPacketCurrent=downPacketCurrent+1;
if(downPacketCurrent>downPacketTotal)
{
STM_EVAL_LEDOn(LED2);
DeviceState=Last_operation_Success;
Aditionals=(uint32_t)Download;
}
SetEPTxValid(ENDP1);
}
}
/*******************************************************************************
* Function Name : EP1_OUT_Callback.
* Description : EP1 OUT Callback Routine.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void EP1_OUT_Callback(void)
{
BitAction Led_State;
/* Read received data (2 bytes) */
USB_SIL_Read(EP1_OUT, Receive_Buffer);
Command=Receive_Buffer[1];
EchoReqFlag=(Command>>7);
EchoAnsFlag=(Command>>6) & 0x01;
StartFlag=(Command>>5) & 0x01;
Count=Receive_Buffer[2]<<24;
Count+=Receive_Buffer[3]<<16;
Count+=Receive_Buffer[4]<<8;
Count+=Receive_Buffer[5];
Data=Receive_Buffer[6]<<24;
Data+=Receive_Buffer[7]<<16;
Data+=Receive_Buffer[8]<<8;
Data+=Receive_Buffer[9];
Data0=Receive_Buffer[6];
Data1=Receive_Buffer[7];
Data2=Receive_Buffer[8];
Data3=Receive_Buffer[9];
Command=Command & 0b00011111;
switch(Command)
{
case EnterDFU:
if (DeviceState==idle)
{
DeviceState=DFUidle;
FLASH_Unlock();
}
else
{
DeviceState=Last_operation_failed;
Aditionals=(uint16_t) Command;
}
break;
case Upload:
if((DeviceState==DFUidle) || (DeviceState==uploading))
{
if((StartFlag==1) && (Next_Packet==0))
{
TransferType=Data0;
SizeOfTransfer=Count;
Next_Packet=1;
DeviceState=uploading;
}
else if((StartFlag!=1) && (Next_Packet!=0))
{
// STM_EVAL_LEDOn(LED2);
if(Count==Next_Packet-1)
{
FLASH_ProgramWord(MemLocations[TransferType]+Count*4,Data);
++Next_Packet;
}
else
{
DeviceState=wrong_packet_received;
Aditionals=Count;
}
// FLASH_ProgramWord(MemLocations[TransferType]+4,++Next_Packet);//+Count,Data);
}
else
{
STM_EVAL_LEDOn(LED2);
DeviceState=Last_operation_failed;
Aditionals=(uint32_t) Command;
}
}
break;
case Req_Capabilities:
break;
case Rep_Capabilities:
break;
case JumpFW:
JumpToApp=1;
break;
case Reset:
Reset_Device();
break;
case Abort_Operation:
break;
case Op_END:
if(DeviceState==uploading)
{
if(Next_Packet-1==SizeOfTransfer)
{
DeviceState=Last_operation_Success;
}
if(Next_Packet-1<SizeOfTransfer)
{
DeviceState=too_few_packets;
}
}
break;
case Download_Req:
if(DeviceState==DFUidle)
{
downType=Data0;
downPacketCurrent=0;
downPacketTotal=Count;
DeviceState=downloading;
}
else
{
DeviceState=Last_operation_failed;
Aditionals=(uint32_t) Command;
}
break;
case Status_Request:
Buffer[0]=0x01;
Buffer[1]=Status_Rep;
if(DeviceState==wrong_packet_received)
{
Buffer[2]=Aditionals>>24;
Buffer[3]=Aditionals>>16;
Buffer[4]=Aditionals>>8;
Buffer[4]=Aditionals;
}
else
{
Buffer[2]=0;
Buffer[3]=((uint16_t)Aditionals)>>8;
Buffer[4]=((uint16_t)Aditionals);
Buffer[5]=0;
}
Buffer[6]=DeviceState;
Buffer[7]=0;
Buffer[8]=0;
Buffer[9]=0;
USB_SIL_Write(EP1_IN, (uint8_t*)Buffer,10);
SetEPTxValid(ENDP1);
if(DeviceState==Last_operation_Success)
{
DeviceState=DFUidle;
}
break;
case Status_Rep:
break;
}
SetEPRxStatus(ENDP1, EP_RX_VALID);
//uint8_t Buffer[2];
Buffer[0]=0x07;
Buffer[1]=2;
//USB_SIL_Write(EP1_IN, (uint8_t*)Buffer,2);
//SetEPTxValid(ENDP1);
return;
if (Receive_Buffer[1] == 0)
{
Led_State = Bit_RESET;
}
else
{
Led_State = Bit_SET;
}
switch (Receive_Buffer[0])
{
case 1: /* Led 1 */
if (Led_State != Bit_RESET)
{
STM_EVAL_LEDOn(LED1);
}
else
{
STM_EVAL_LEDOff(LED1);
}
break;
case 2: /* Led 2 */
if (Led_State != Bit_RESET)
{
STM_EVAL_LEDOn(LED2);
}
else
{
STM_EVAL_LEDOff(LED2);
}
break;
case 3: /* Led 3 */
if (Led_State != Bit_RESET)
{
STM_EVAL_LEDOn(LED3);
}
else
{
STM_EVAL_LEDOff(LED3);
}
break;
case 4: /* Led 4 */
if (Led_State != Bit_RESET)
{
STM_EVAL_LEDOn(LED4);
}
else
{
STM_EVAL_LEDOff(LED4);
}
break;
default:
STM_EVAL_LEDOff(LED1);
STM_EVAL_LEDOff(LED2);
STM_EVAL_LEDOff(LED3);
STM_EVAL_LEDOff(LED4);
break;
}
#ifndef STM32F10X_CL
SetEPRxStatus(ENDP1, EP_RX_VALID);
#endif /* STM32F10X_CL */
}
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,425 @@
/******************** (C) COPYRIGHT 2010 STMicroelectronics ********************
* File Name : usb_prop.c
* Author : MCD Application Team
* Version : V3.2.1
* Date : 07/05/2010
* Description : All processings related to Custom HID Demo
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
#include "usb_lib.h"
#include "usb_conf.h"
#include "usb_prop.h"
#include "usb_desc.h"
#include "usb_pwr.h"
#include "hw_config.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
uint32_t ProtocolValue;
__IO uint8_t EXTI_Enable;
/* -------------------------------------------------------------------------- */
/* Structures initializations */
/* -------------------------------------------------------------------------- */
DEVICE Device_Table =
{
EP_NUM,
1
};
DEVICE_PROP Device_Property =
{
CustomHID_init,
CustomHID_Reset,
CustomHID_Status_In,
CustomHID_Status_Out,
CustomHID_Data_Setup,
CustomHID_NoData_Setup,
CustomHID_Get_Interface_Setting,
CustomHID_GetDeviceDescriptor,
CustomHID_GetConfigDescriptor,
CustomHID_GetStringDescriptor,
0,
0x40 /*MAX PACKET SIZE*/
};
USER_STANDARD_REQUESTS User_Standard_Requests =
{
CustomHID_GetConfiguration,
CustomHID_SetConfiguration,
CustomHID_GetInterface,
CustomHID_SetInterface,
CustomHID_GetStatus,
CustomHID_ClearFeature,
CustomHID_SetEndPointFeature,
CustomHID_SetDeviceFeature,
CustomHID_SetDeviceAddress
};
ONE_DESCRIPTOR Device_Descriptor =
{
(uint8_t*)CustomHID_DeviceDescriptor,
CUSTOMHID_SIZ_DEVICE_DESC
};
ONE_DESCRIPTOR Config_Descriptor =
{
(uint8_t*)CustomHID_ConfigDescriptor,
CUSTOMHID_SIZ_CONFIG_DESC
};
ONE_DESCRIPTOR CustomHID_Report_Descriptor =
{
(uint8_t *)CustomHID_ReportDescriptor,
CUSTOMHID_SIZ_REPORT_DESC
};
ONE_DESCRIPTOR CustomHID_Hid_Descriptor =
{
(uint8_t*)CustomHID_ConfigDescriptor + CUSTOMHID_OFF_HID_DESC,
CUSTOMHID_SIZ_HID_DESC
};
ONE_DESCRIPTOR String_Descriptor[4] =
{
{(uint8_t*)CustomHID_StringLangID, CUSTOMHID_SIZ_STRING_LANGID},
{(uint8_t*)CustomHID_StringVendor, CUSTOMHID_SIZ_STRING_VENDOR},
{(uint8_t*)CustomHID_StringProduct, CUSTOMHID_SIZ_STRING_PRODUCT},
{(uint8_t*)CustomHID_StringSerial, CUSTOMHID_SIZ_STRING_SERIAL}
};
/* Extern variables ----------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Extern function prototypes ------------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
* Function Name : CustomHID_init.
* Description : Custom HID init routine.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void CustomHID_init(void)
{
/* Update the serial number string descriptor with the data from the unique
ID*/
Get_SerialNum();
pInformation->Current_Configuration = 0;
/* Connect the device */
PowerOn();
/* Perform basic device initialization operations */
USB_SIL_Init();
bDeviceState = UNCONNECTED;
}
/*******************************************************************************
* Function Name : CustomHID_Reset.
* Description : Custom HID reset routine.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void CustomHID_Reset(void)
{
/* Set Joystick_DEVICE as not configured */
pInformation->Current_Configuration = 0;
pInformation->Current_Interface = 0;/*the default Interface*/
/* Current Feature initialization */
pInformation->Current_Feature = CustomHID_ConfigDescriptor[7];
#ifdef STM32F10X_CL
/* EP0 is already configured in DFU_Init() by USB_SIL_Init() function */
/* Init EP1 IN as Interrupt endpoint */
OTG_DEV_EP_Init(EP1_IN, OTG_DEV_EP_TYPE_INT, 2);
/* Init EP1 OUT as Interrupt endpoint */
OTG_DEV_EP_Init(EP1_OUT, OTG_DEV_EP_TYPE_INT, 2);
#else
SetBTABLE(BTABLE_ADDRESS);
/* Initialize Endpoint 0 */
SetEPType(ENDP0, EP_CONTROL);
SetEPTxStatus(ENDP0, EP_TX_STALL);
SetEPRxAddr(ENDP0, ENDP0_RXADDR);
SetEPTxAddr(ENDP0, ENDP0_TXADDR);
Clear_Status_Out(ENDP0);
SetEPRxCount(ENDP0, Device_Property.MaxPacketSize);
SetEPRxValid(ENDP0);
/* Initialize Endpoint 1 */
SetEPType(ENDP1, EP_INTERRUPT);
SetEPTxAddr(ENDP1, ENDP1_TXADDR);
SetEPRxAddr(ENDP1, ENDP1_RXADDR);
SetEPTxCount(ENDP1, 11);
SetEPRxCount(ENDP1, 11);
SetEPRxStatus(ENDP1, EP_RX_VALID);
SetEPTxStatus(ENDP1, EP_TX_NAK);
/* Set this device to response on default address */
SetDeviceAddress(0);
#endif /* STM32F10X_CL */
bDeviceState = ATTACHED;
}
/*******************************************************************************
* Function Name : CustomHID_SetConfiguration.
* Description : Udpade the device state to configured and command the ADC
* conversion.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void CustomHID_SetConfiguration(void)
{
if (pInformation->Current_Configuration != 0)
{
/* Device configured */
bDeviceState = CONFIGURED;
/* Start ADC1 Software Conversion */
//ADC_SoftwareStartConvCmd(ADC1, ENABLE);
}
}
/*******************************************************************************
* Function Name : CustomHID_SetConfiguration.
* Description : Udpade the device state to addressed.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void CustomHID_SetDeviceAddress (void)
{
bDeviceState = ADDRESSED;
}
/*******************************************************************************
* Function Name : CustomHID_Status_In.
* Description : Joystick status IN routine.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void CustomHID_Status_In(void)
{
}
/*******************************************************************************
* Function Name : CustomHID_Status_Out
* Description : Joystick status OUT routine.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void CustomHID_Status_Out (void)
{
}
/*******************************************************************************
* Function Name : CustomHID_Data_Setup
* Description : Handle the data class specific requests.
* Input : Request Nb.
* Output : None.
* Return : USB_UNSUPPORT or USB_SUCCESS.
*******************************************************************************/
RESULT CustomHID_Data_Setup(uint8_t RequestNo)
{
uint8_t *(*CopyRoutine)(uint16_t);
CopyRoutine = NULL;
if ((RequestNo == GET_DESCRIPTOR)
&& (Type_Recipient == (STANDARD_REQUEST | INTERFACE_RECIPIENT))
&& (pInformation->USBwIndex0 == 0))
{
if (pInformation->USBwValue1 == REPORT_DESCRIPTOR)
{
CopyRoutine = CustomHID_GetReportDescriptor;
}
else if (pInformation->USBwValue1 == HID_DESCRIPTOR_TYPE)
{
CopyRoutine = CustomHID_GetHIDDescriptor;
}
} /* End of GET_DESCRIPTOR */
/*** GET_PROTOCOL ***/
else if ((Type_Recipient == (CLASS_REQUEST | INTERFACE_RECIPIENT))
&& RequestNo == GET_PROTOCOL)
{
CopyRoutine = CustomHID_GetProtocolValue;
}
if (CopyRoutine == NULL)
{
return USB_UNSUPPORT;
}
pInformation->Ctrl_Info.CopyData = CopyRoutine;
pInformation->Ctrl_Info.Usb_wOffset = 0;
(*CopyRoutine)(0);
return USB_SUCCESS;
}
/*******************************************************************************
* Function Name : CustomHID_NoData_Setup
* Description : handle the no data class specific requests
* Input : Request Nb.
* Output : None.
* Return : USB_UNSUPPORT or USB_SUCCESS.
*******************************************************************************/
RESULT CustomHID_NoData_Setup(uint8_t RequestNo)
{
if ((Type_Recipient == (CLASS_REQUEST | INTERFACE_RECIPIENT))
&& (RequestNo == SET_PROTOCOL))
{
return CustomHID_SetProtocol();
}
else
{
return USB_UNSUPPORT;
}
}
/*******************************************************************************
* Function Name : CustomHID_GetDeviceDescriptor.
* Description : Gets the device descriptor.
* Input : Length
* Output : None.
* Return : The address of the device descriptor.
*******************************************************************************/
uint8_t *CustomHID_GetDeviceDescriptor(uint16_t Length)
{
return Standard_GetDescriptorData(Length, &Device_Descriptor);
}
/*******************************************************************************
* Function Name : CustomHID_GetConfigDescriptor.
* Description : Gets the configuration descriptor.
* Input : Length
* Output : None.
* Return : The address of the configuration descriptor.
*******************************************************************************/
uint8_t *CustomHID_GetConfigDescriptor(uint16_t Length)
{
return Standard_GetDescriptorData(Length, &Config_Descriptor);
}
/*******************************************************************************
* Function Name : CustomHID_GetStringDescriptor
* Description : Gets the string descriptors according to the needed index
* Input : Length
* Output : None.
* Return : The address of the string descriptors.
*******************************************************************************/
uint8_t *CustomHID_GetStringDescriptor(uint16_t Length)
{
uint8_t wValue0 = pInformation->USBwValue0;
if (wValue0 > 4)
{
return NULL;
}
else
{
return Standard_GetDescriptorData(Length, &String_Descriptor[wValue0]);
}
}
/*******************************************************************************
* Function Name : CustomHID_GetReportDescriptor.
* Description : Gets the HID report descriptor.
* Input : Length
* Output : None.
* Return : The address of the configuration descriptor.
*******************************************************************************/
uint8_t *CustomHID_GetReportDescriptor(uint16_t Length)
{
return Standard_GetDescriptorData(Length, &CustomHID_Report_Descriptor);
}
/*******************************************************************************
* Function Name : CustomHID_GetHIDDescriptor.
* Description : Gets the HID descriptor.
* Input : Length
* Output : None.
* Return : The address of the configuration descriptor.
*******************************************************************************/
uint8_t *CustomHID_GetHIDDescriptor(uint16_t Length)
{
return Standard_GetDescriptorData(Length, &CustomHID_Hid_Descriptor);
}
/*******************************************************************************
* Function Name : CustomHID_Get_Interface_Setting.
* Description : tests the interface and the alternate setting according to the
* supported one.
* Input : - Interface : interface number.
* - AlternateSetting : Alternate Setting number.
* Output : None.
* Return : USB_SUCCESS or USB_UNSUPPORT.
*******************************************************************************/
RESULT CustomHID_Get_Interface_Setting(uint8_t Interface, uint8_t AlternateSetting)
{
if (AlternateSetting > 0)
{
return USB_UNSUPPORT;
}
else if (Interface > 0)
{
return USB_UNSUPPORT;
}
return USB_SUCCESS;
}
/*******************************************************************************
* Function Name : CustomHID_SetProtocol
* Description : Joystick Set Protocol request routine.
* Input : None.
* Output : None.
* Return : USB SUCCESS.
*******************************************************************************/
RESULT CustomHID_SetProtocol(void)
{
uint8_t wValue0 = pInformation->USBwValue0;
ProtocolValue = wValue0;
return USB_SUCCESS;
}
/*******************************************************************************
* Function Name : CustomHID_GetProtocolValue
* Description : get the protocol value
* Input : Length.
* Output : None.
* Return : address of the protcol value.
*******************************************************************************/
uint8_t *CustomHID_GetProtocolValue(uint16_t Length)
{
if (Length == 0)
{
pInformation->Ctrl_Info.Usb_wLength = 1;
return NULL;
}
else
{
return (uint8_t *)(&ProtocolValue);
}
}
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -1,220 +0,0 @@
/******************** (C) COPYRIGHT 2010 STMicroelectronics ********************
* File Name : dfu_mal.c
* Author : MCD Application Team
* Version : V3.2.1
* Date : 07/05/2010
* Description : Generic media access Layer
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Includes ------------------------------------------------------------------*/
#include "dfu_mal.h"
#include "spi_if.h"
#include "flash_if.h"
#include "nor_if.h"
#include "fsmc_nor.h"
#include "usb_lib.h"
#include "usb_type.h"
#include "usb_desc.h"
#include "platform_config.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
uint16_t (*pMAL_Init) (void);
uint16_t (*pMAL_Erase) (uint32_t SectorAddress);
uint16_t (*pMAL_Write) (uint32_t SectorAddress, uint32_t DataLength);
uint8_t *(*pMAL_Read) (uint32_t SectorAddress, uint32_t DataLength);
uint8_t MAL_Buffer[wTransferSize]; /* RAM Buffer for Downloaded Data */
NOR_IDTypeDef NOR_ID;
extern ONE_DESCRIPTOR DFU_String_Descriptor[7];
static const uint16_t TimingTable[5][2] =
{
{ 3000 , 20 }, /* SPI Flash */
{ 1000 , 25 }, /* NOR Flash M29W128F */
{ 100 , 104 }, /* Internal Flash */
{ 1000 , 25 }, /* NOR Flash M29W128G */
{ 1000 , 45 } /* NOR Flash S29GL128 */
};
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
* Function Name : MAL_Init
* Description : Initializes the Media on the STM32
* Input : None
* Output : None
* Return : None
*******************************************************************************/
uint16_t MAL_Init(void)
{
FLASH_If_Init(); /* Internal Flash */
#if defined(USE_STM3210B_EVAL) || defined(USE_STM3210E_EVAL)
SPI_If_Init(); /* SPI Flash */
#endif /* USE_STM3210B_EVAL or USE_STM3210E_EVAL */
#ifdef USE_STM3210E_EVAL
NOR_If_Init(); /* NOR Flash */
FSMC_NOR_ReadID(&NOR_ID);
FSMC_NOR_ReturnToReadMode();
/* select the alternate descriptor following NOR ID */
if ((NOR_ID.Manufacturer_Code == 0x01)&&(NOR_ID.Device_Code2 == NOR_S29GL128))
{
DFU_String_Descriptor[6].Descriptor = DFU_StringInterface2_3;
}
/* select the alternate descriptor following NOR ID */
if ((NOR_ID.Manufacturer_Code == 0x20)&&(NOR_ID.Device_Code2 == NOR_M29W128G))
{
DFU_String_Descriptor[6].Descriptor = DFU_StringInterface2_2;
}
#endif /* USE_STM3210E_EVAL */
return MAL_OK;
}
/*******************************************************************************
* Function Name : MAL_Erase
* Description : Erase sector
* Input : None
* Output : None
* Return : None
*******************************************************************************/
uint16_t MAL_Erase(uint32_t SectorAddress)
{
switch (SectorAddress & MAL_MASK)
{
case INTERNAL_FLASH_BASE:
pMAL_Erase = FLASH_If_Erase;
break;
#if defined(USE_STM3210B_EVAL) || defined(USE_STM3210E_EVAL)
case SPI_FLASH_BASE:
pMAL_Erase = SPI_If_Erase;
break;
#endif /* USE_STM3210B_EVAL or USE_STM3210E_EVAL */
#ifdef USE_STM3210E_EVAL
case NOR_FLASH_BASE:
pMAL_Erase = NOR_If_Erase;
break;
#endif /* USE_STM3210E_EVAL */
default:
return MAL_FAIL;
}
return pMAL_Erase(SectorAddress);
}
/*******************************************************************************
* Function Name : MAL_Write
* Description : Write sectors
* Input : None
* Output : None
* Return : None
*******************************************************************************/
uint16_t MAL_Write (uint32_t SectorAddress, uint32_t DataLength)
{
switch (SectorAddress & MAL_MASK)
{
case INTERNAL_FLASH_BASE:
pMAL_Write = FLASH_If_Write;
break;
#if defined(USE_STM3210B_EVAL) || defined(USE_STM3210E_EVAL)
case SPI_FLASH_BASE:
pMAL_Write = SPI_If_Write;
break;
#endif /* USE_STM3210B_EVAL || USE_STM3210E_EVAL */
#ifdef USE_STM3210E_EVAL
case NOR_FLASH_BASE:
pMAL_Write = NOR_If_Write;
break;
#endif /* USE_STM3210E_EVAL */
default:
return MAL_FAIL;
}
return pMAL_Write(SectorAddress, DataLength);
}
/*******************************************************************************
* Function Name : MAL_Read
* Description : Read sectors
* Input : None
* Output : None
* Return : Buffer pointer
*******************************************************************************/
uint8_t *MAL_Read (uint32_t SectorAddress, uint32_t DataLength)
{
switch (SectorAddress & MAL_MASK)
{
case INTERNAL_FLASH_BASE:
pMAL_Read = FLASH_If_Read;
break;
#if defined(USE_STM3210B_EVAL) || defined(USE_STM3210E_EVAL)
case SPI_FLASH_BASE:
pMAL_Read = SPI_If_Read;
break;
#endif /* USE_STM3210B_EVAL or USE_STM3210E_EVAL */
#ifdef USE_STM3210E_EVAL
case NOR_FLASH_BASE:
pMAL_Read = NOR_If_Read;
break;
#endif /* USE_STM3210E_EVAL */
default:
return 0;
}
return pMAL_Read (SectorAddress, DataLength);
}
/*******************************************************************************
* Function Name : MAL_GetStatus
* Description : Get status
* Input : None
* Output : None
* Return : Buffer pointer
*******************************************************************************/
uint16_t MAL_GetStatus(uint32_t SectorAddress , uint8_t Cmd, uint8_t *buffer)
{
uint8_t x = (SectorAddress >> 26) & 0x03 ; /* 0x000000000 --> 0 */
/* 0x640000000 --> 1 */
/* 0x080000000 --> 2 */
uint8_t y = Cmd & 0x01;
if ((x == 1) && (NOR_ID.Device_Code2 == NOR_M29W128G)&& (NOR_ID.Manufacturer_Code == 0x20))
{
x = 3 ;
}
else if((x == 1) && (NOR_ID.Device_Code2 == NOR_S29GL128) && (NOR_ID.Manufacturer_Code == 0x01))
{
x = 4 ;
}
SET_POLLING_TIMING(TimingTable[x][y]); /* x: Erase/Write Timing */
/* y: Media */
return MAL_OK;
}
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -1,92 +0,0 @@
/******************** (C) COPYRIGHT 2010 STMicroelectronics ********************
* File Name : flash_if.c
* Author : MCD Application Team
* Version : V3.2.1
* Date : 07/05/2010
* Description : specific media access Layer for internal flash
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Includes ------------------------------------------------------------------*/
#include "flash_if.h"
#include "dfu_mal.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
* Function Name : FLASH_If_Init
* Description : Initializes the Media on the STM32
* Input : None
* Output : None
* Return : None
*******************************************************************************/
uint16_t FLASH_If_Init(void)
{
return MAL_OK;
}
/*******************************************************************************
* Function Name : FLASH_If_Erase
* Description : Erase sector
* Input : None
* Output : None
* Return : None
*******************************************************************************/
uint16_t FLASH_If_Erase(uint32_t SectorAddress)
{
FLASH_ErasePage(SectorAddress);
return MAL_OK;
}
/*******************************************************************************
* Function Name : FLASH_If_Write
* Description : Write sectors
* Input : None
* Output : None
* Return : None
*******************************************************************************/
uint16_t FLASH_If_Write(uint32_t SectorAddress, uint32_t DataLength)
{
uint32_t idx = 0;
if (DataLength & 0x3) /* Not an aligned data */
{
for (idx = DataLength; idx < ((DataLength & 0xFFFC) + 4); idx++)
{
MAL_Buffer[idx] = 0xFF;
}
}
/* Data received are Word multiple */
for (idx = 0; idx < DataLength; idx = idx + 4)
{
FLASH_ProgramWord(SectorAddress, *(uint32_t *)(MAL_Buffer + idx));
SectorAddress += 4;
}
return MAL_OK;
}
/*******************************************************************************
* Function Name : FLASH_If_Read
* Description : Read sectors
* Input : None
* Output : None
* Return : buffer address pointer
*******************************************************************************/
uint8_t *FLASH_If_Read (uint32_t SectorAddress, uint32_t DataLength)
{
return (uint8_t*)(SectorAddress);
}
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -1,415 +0,0 @@
/******************** (C) COPYRIGHT 2010 STMicroelectronics ********************
* File Name : fsmc_nor.c
* Author : MCD Application Team
* Version : V3.2.1
* Date : 07/05/2010
* Description : This file provides a set of functions needed to drive the
* M29W128FL, M29W128GL and S29GL128P NOR memories mounted
* on STM3210E-EVAL board.
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Includes ------------------------------------------------------------------*/
#include "fsmc_nor.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
#define Bank1_NOR2_ADDR ((uint32_t)0x64000000)
/* Delay definition */
#define BlockErase_Timeout ((uint32_t)0x00A00000)
#define ChipErase_Timeout ((uint32_t)0x30000000)
#define Program_Timeout ((uint32_t)0x00001400)
/* Private macro -------------------------------------------------------------*/
#define ADDR_SHIFT(A) (Bank1_NOR2_ADDR + (2 * (A)))
#define NOR_WRITE(Address, Data) (*(__IO uint16_t *)(Address) = (Data))
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
* Function Name : FSMC_NOR_Init
* Description : Configures the FSMC and GPIOs to interface with the NOR memory.
* This function must be called before any write/read operation
* on the NOR.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void FSMC_NOR_Init(void)
{
FSMC_NORSRAMInitTypeDef FSMC_NORSRAMInitStructure;
FSMC_NORSRAMTimingInitTypeDef p;
GPIO_InitTypeDef GPIO_InitStructure;
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOD | RCC_APB2Periph_GPIOE |
RCC_APB2Periph_GPIOF | RCC_APB2Periph_GPIOG, ENABLE);
/*-- GPIO Configuration ------------------------------------------------------*/
/* NOR Data lines configuration */
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_1 | GPIO_Pin_8 | GPIO_Pin_9 |
GPIO_Pin_10 | GPIO_Pin_14 | GPIO_Pin_15;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_Init(GPIOD, &GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_7 | GPIO_Pin_8 | GPIO_Pin_9 | GPIO_Pin_10 |
GPIO_Pin_11 | GPIO_Pin_12 | GPIO_Pin_13 |
GPIO_Pin_14 | GPIO_Pin_15;
GPIO_Init(GPIOE, &GPIO_InitStructure);
/* NOR Address lines configuration */
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_1 | GPIO_Pin_2 | GPIO_Pin_3 |
GPIO_Pin_4 | GPIO_Pin_5 | GPIO_Pin_12 | GPIO_Pin_13 |
GPIO_Pin_14 | GPIO_Pin_15;
GPIO_Init(GPIOF, &GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_1 | GPIO_Pin_2 |
GPIO_Pin_3 | GPIO_Pin_4 | GPIO_Pin_5;
GPIO_Init(GPIOG, &GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_11 | GPIO_Pin_12 | GPIO_Pin_13;
GPIO_Init(GPIOD, &GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_3 | GPIO_Pin_4 | GPIO_Pin_5 | GPIO_Pin_6;
GPIO_Init(GPIOE, &GPIO_InitStructure);
/* NOE and NWE configuration */
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4 | GPIO_Pin_5;
GPIO_Init(GPIOD, &GPIO_InitStructure);
/* NE2 configuration */
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_9;
GPIO_Init(GPIOG, &GPIO_InitStructure);
/*-- FSMC Configuration ----------------------------------------------------*/
p.FSMC_AddressSetupTime = 0x02;
p.FSMC_AddressHoldTime = 0x00;
p.FSMC_DataSetupTime = 0x05;
p.FSMC_BusTurnAroundDuration = 0x00;
p.FSMC_CLKDivision = 0x00;
p.FSMC_DataLatency = 0x00;
p.FSMC_AccessMode = FSMC_AccessMode_B;
FSMC_NORSRAMInitStructure.FSMC_Bank = FSMC_Bank1_NORSRAM2;
FSMC_NORSRAMInitStructure.FSMC_DataAddressMux = FSMC_DataAddressMux_Disable;
FSMC_NORSRAMInitStructure.FSMC_MemoryType = FSMC_MemoryType_NOR;
FSMC_NORSRAMInitStructure.FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_16b;
FSMC_NORSRAMInitStructure.FSMC_BurstAccessMode = FSMC_BurstAccessMode_Disable;
FSMC_NORSRAMInitStructure.FSMC_WaitSignalPolarity = FSMC_WaitSignalPolarity_Low;
FSMC_NORSRAMInitStructure.FSMC_WrapMode = FSMC_WrapMode_Disable;
FSMC_NORSRAMInitStructure.FSMC_WaitSignalActive = FSMC_WaitSignalActive_BeforeWaitState;
FSMC_NORSRAMInitStructure.FSMC_WriteOperation = FSMC_WriteOperation_Enable;
FSMC_NORSRAMInitStructure.FSMC_WaitSignal = FSMC_WaitSignal_Disable;
FSMC_NORSRAMInitStructure.FSMC_ExtendedMode = FSMC_ExtendedMode_Disable;
FSMC_NORSRAMInitStructure.FSMC_WriteBurst = FSMC_WriteBurst_Disable;
FSMC_NORSRAMInitStructure.FSMC_ReadWriteTimingStruct = &p;
FSMC_NORSRAMInitStructure.FSMC_WriteTimingStruct = &p;
FSMC_NORSRAMInit(&FSMC_NORSRAMInitStructure);
/* Enable FSMC Bank1_NOR Bank */
FSMC_NORSRAMCmd(FSMC_Bank1_NORSRAM2, ENABLE);
}
/******************************************************************************
* Function Name : FSMC_NOR_ReadID
* Description : Reads NOR memory's Manufacturer and Device Code.
* Input : - NOR_ID: pointer to a NOR_IDTypeDef structure which will hold
* the Manufacturer and Device Code.
* Output : None
* Return : None
*******************************************************************************/
void FSMC_NOR_ReadID(NOR_IDTypeDef* NOR_ID)
{
NOR_WRITE(ADDR_SHIFT(0x0555), 0x00AA);
NOR_WRITE(ADDR_SHIFT(0x02AA), 0x0055);
NOR_WRITE(ADDR_SHIFT(0x0555), 0x0090);
NOR_ID->Manufacturer_Code = *(__IO uint16_t *) ADDR_SHIFT(0x0000);
NOR_ID->Device_Code1 = *(__IO uint16_t *) ADDR_SHIFT(0x0001);
NOR_ID->Device_Code2 = *(__IO uint16_t *) ADDR_SHIFT(0x000E);
NOR_ID->Device_Code3 = *(__IO uint16_t *) ADDR_SHIFT(0x000F);
}
/*******************************************************************************
* Function Name : FSMC_NOR_EraseBlock
* Description : Erases the specified Nor memory block.
* Input : - BlockAddr: address of the block to erase.
* Output : None
* Return : NOR_Status:The returned value can be: NOR_SUCCESS, NOR_ERROR
* or NOR_TIMEOUT
*******************************************************************************/
NOR_Status FSMC_NOR_EraseBlock(uint32_t BlockAddr)
{
NOR_WRITE(ADDR_SHIFT(0x0555), 0x00AA);
NOR_WRITE(ADDR_SHIFT(0x02AA), 0x0055);
NOR_WRITE(ADDR_SHIFT(0x0555), 0x0080);
NOR_WRITE(ADDR_SHIFT(0x0555), 0x00AA);
NOR_WRITE(ADDR_SHIFT(0x02AA), 0x0055);
NOR_WRITE((Bank1_NOR2_ADDR + BlockAddr), 0x30);
return (FSMC_NOR_GetStatus(BlockErase_Timeout));
}
/*******************************************************************************
* Function Name : FSMC_NOR_EraseChip
* Description : Erases the entire chip.
* Input : None
* Output : None
* Return : NOR_Status:The returned value can be: NOR_SUCCESS, NOR_ERROR
* or NOR_TIMEOUT
*******************************************************************************/
NOR_Status FSMC_NOR_EraseChip(void)
{
NOR_WRITE(ADDR_SHIFT(0x0555), 0x00AA);
NOR_WRITE(ADDR_SHIFT(0x02AA), 0x0055);
NOR_WRITE(ADDR_SHIFT(0x0555), 0x0080);
NOR_WRITE(ADDR_SHIFT(0x0555), 0x00AA);
NOR_WRITE(ADDR_SHIFT(0x02AA), 0x0055);
NOR_WRITE(ADDR_SHIFT(0x0555), 0x0010);
return (FSMC_NOR_GetStatus(ChipErase_Timeout));
}
/******************************************************************************
* Function Name : FSMC_NOR_WriteHalfWord
* Description : Writes a half-word to the NOR memory.
* Input : - WriteAddr : NOR memory internal address to write to.
* - Data : Data to write.
* Output : None
* Return : NOR_Status:The returned value can be: NOR_SUCCESS, NOR_ERROR
* or NOR_TIMEOUT
*******************************************************************************/
NOR_Status FSMC_NOR_WriteHalfWord(uint32_t WriteAddr, uint16_t Data)
{
NOR_WRITE(ADDR_SHIFT(0x0555), 0x00AA);
NOR_WRITE(ADDR_SHIFT(0x02AA), 0x0055);
NOR_WRITE(ADDR_SHIFT(0x0555), 0x00A0);
NOR_WRITE((Bank1_NOR2_ADDR + WriteAddr), Data);
return (FSMC_NOR_GetStatus(Program_Timeout));
}
/*******************************************************************************
* Function Name : FSMC_NOR_WriteBuffer
* Description : Writes a half-word buffer to the FSMC NOR memory.
* Input : - pBuffer : pointer to buffer.
* - WriteAddr : NOR memory internal address from which the data
* will be written.
* - NumHalfwordToWrite : number of Half words to write.
* Output : None
* Return : NOR_Status:The returned value can be: NOR_SUCCESS, NOR_ERROR
* or NOR_TIMEOUT
*******************************************************************************/
NOR_Status FSMC_NOR_WriteBuffer(uint16_t* pBuffer, uint32_t WriteAddr, uint32_t NumHalfwordToWrite)
{
NOR_Status status = NOR_ONGOING;
do
{
/* Transfer data to the memory */
status = FSMC_NOR_WriteHalfWord(WriteAddr, *pBuffer++);
WriteAddr = WriteAddr + 2;
NumHalfwordToWrite--;
}
while((status == NOR_SUCCESS) && (NumHalfwordToWrite != 0));
return (status);
}
/*******************************************************************************
* Function Name : FSMC_NOR_ProgramBuffer
* Description : Writes a half-word buffer to the FSMC NOR memory. This function
* must be used only with S29GL128P NOR memory.
* Input : - pBuffer : pointer to buffer.
* - WriteAddr: NOR memory internal address from which the data
* will be written.
* - NumHalfwordToWrite: number of Half words to write.
* The maximum allowed value is 32 Half words (64 bytes).
* Output : None
* Return : NOR_Status:The returned value can be: NOR_SUCCESS, NOR_ERROR
* or NOR_TIMEOUT
*******************************************************************************/
NOR_Status FSMC_NOR_ProgramBuffer(uint16_t* pBuffer, uint32_t WriteAddr, uint32_t NumHalfwordToWrite)
{
uint32_t lastloadedaddress = 0x00;
uint32_t currentaddress = 0x00;
uint32_t endaddress = 0x00;
/* Initialize variables */
currentaddress = WriteAddr;
endaddress = WriteAddr + NumHalfwordToWrite - 1;
lastloadedaddress = WriteAddr;
/* Issue unlock command sequence */
NOR_WRITE(ADDR_SHIFT(0x00555), 0x00AA);
NOR_WRITE(ADDR_SHIFT(0x02AA), 0x0055);
/* Write Write Buffer Load Command */
NOR_WRITE(ADDR_SHIFT(WriteAddr), 0x0025);
NOR_WRITE(ADDR_SHIFT(WriteAddr), (NumHalfwordToWrite - 1));
/* Load Data into NOR Buffer */
while(currentaddress <= endaddress)
{
/* Store last loaded address & data value (for polling) */
lastloadedaddress = currentaddress;
NOR_WRITE(ADDR_SHIFT(currentaddress), *pBuffer++);
currentaddress += 1;
}
NOR_WRITE(ADDR_SHIFT(lastloadedaddress), 0x29);
return(FSMC_NOR_GetStatus(Program_Timeout));
}
/******************************************************************************
* Function Name : FSMC_NOR_ReadHalfWord
* Description : Reads a half-word from the NOR memory.
* Input : - ReadAddr : NOR memory internal address to read from.
* Output : None
* Return : Half-word read from the NOR memory
*******************************************************************************/
uint16_t FSMC_NOR_ReadHalfWord(uint32_t ReadAddr)
{
NOR_WRITE(ADDR_SHIFT(0x00555), 0x00AA);
NOR_WRITE(ADDR_SHIFT(0x002AA), 0x0055);
NOR_WRITE((Bank1_NOR2_ADDR + ReadAddr), 0x00F0 );
return (*(__IO uint16_t *)((Bank1_NOR2_ADDR + ReadAddr)));
}
/*******************************************************************************
* Function Name : FSMC_NOR_ReadBuffer
* Description : Reads a block of data from the FSMC NOR memory.
* Input : - pBuffer : pointer to the buffer that receives the data read
* from the NOR memory.
* - ReadAddr : NOR memory internal address to read from.
* - NumHalfwordToRead : number of Half word to read.
* Output : None
* Return : None
*******************************************************************************/
void FSMC_NOR_ReadBuffer(uint16_t* pBuffer, uint32_t ReadAddr, uint32_t NumHalfwordToRead)
{
NOR_WRITE(ADDR_SHIFT(0x0555), 0x00AA);
NOR_WRITE(ADDR_SHIFT(0x02AA), 0x0055);
NOR_WRITE((Bank1_NOR2_ADDR + ReadAddr), 0x00F0);
for(; NumHalfwordToRead != 0x00; NumHalfwordToRead--) /* while there is data to read */
{
/* Read a Halfword from the NOR */
*pBuffer++ = *(__IO uint16_t *)((Bank1_NOR2_ADDR + ReadAddr));
ReadAddr = ReadAddr + 2;
}
}
/******************************************************************************
* Function Name : FSMC_NOR_ReturnToReadMode
* Description : Returns the NOR memory to Read mode.
* Input : None
* Output : None
* Return : NOR_SUCCESS
*******************************************************************************/
NOR_Status FSMC_NOR_ReturnToReadMode(void)
{
NOR_WRITE(Bank1_NOR2_ADDR, 0x00F0);
return (NOR_SUCCESS);
}
/******************************************************************************
* Function Name : FSMC_NOR_Reset
* Description : Returns the NOR memory to Read mode and resets the errors in
* the NOR memory Status Register.
* Input : None
* Output : None
* Return : NOR_SUCCESS
*******************************************************************************/
NOR_Status FSMC_NOR_Reset(void)
{
NOR_WRITE(ADDR_SHIFT(0x00555), 0x00AA);
NOR_WRITE(ADDR_SHIFT(0x002AA), 0x0055);
NOR_WRITE(Bank1_NOR2_ADDR, 0x00F0);
return (NOR_SUCCESS);
}
/******************************************************************************
* Function Name : FSMC_NOR_GetStatus
* Description : Returns the NOR operation status.
* Input : - Timeout: NOR progamming Timeout
* Output : None
* Return : NOR_Status:The returned value can be: NOR_SUCCESS, NOR_ERROR
* or NOR_TIMEOUT
*******************************************************************************/
NOR_Status FSMC_NOR_GetStatus(uint32_t Timeout)
{
uint16_t val1 = 0x00, val2 = 0x00;
NOR_Status status = NOR_ONGOING;
uint32_t timeout = Timeout;
/* Poll on NOR memory Ready/Busy signal ------------------------------------*/
while((GPIO_ReadInputDataBit(GPIOD, GPIO_Pin_6) != RESET) && (timeout > 0))
{
timeout--;
}
timeout = Timeout;
while((GPIO_ReadInputDataBit(GPIOD, GPIO_Pin_6) == RESET) && (timeout > 0))
{
timeout--;
}
/* Get the NOR memory operation status -------------------------------------*/
while((Timeout != 0x00) && (status != NOR_SUCCESS))
{
Timeout--;
/* Read DQ6 and DQ5 */
val1 = *(__IO uint16_t *)(Bank1_NOR2_ADDR);
val2 = *(__IO uint16_t *)(Bank1_NOR2_ADDR);
/* If DQ6 did not toggle between the two reads then return NOR_Success */
if((val1 & 0x0040) == (val2 & 0x0040))
{
return NOR_SUCCESS;
}
if((val1 & 0x0020) != 0x0020)
{
status = NOR_ONGOING;
}
val1 = *(__IO uint16_t *)(Bank1_NOR2_ADDR);
val2 = *(__IO uint16_t *)(Bank1_NOR2_ADDR);
if((val1 & 0x0040) == (val2 & 0x0040))
{
return NOR_SUCCESS;
}
else if((val1 & 0x0020) == 0x0020)
{
return NOR_ERROR;
}
}
if(Timeout == 0x00)
{
status = NOR_TIMEOUT;
}
/* Return the operation status */
return (status);
}
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -1,61 +0,0 @@
/******************** (C) COPYRIGHT 2010 STMicroelectronics ********************
* File Name : dfu_mal.h
* Author : MCD Application Team
* Version : V3.2.1
* Date : 07/05/2010
* Description : Header for dfu_mal.c file.
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __DFU_MAL_H
#define __DFU_MAL_H
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
#include "dfu_mal.h"
#include "usb_desc.h"
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
#define MAL_OK 0
#define MAL_FAIL 1
#define MAX_USED_MEDIA 3
#define MAL_MASK 0xFC000000
#define INTERNAL_FLASH_BASE 0x08000000
#define SPI_FLASH_BASE 0x00000000
#define NOR_FLASH_BASE 0x64000000
#define NOR_M29W128F 0x2212
#define NOR_M29W128G 0x2221
#define NOR_S29GL128 0x2221
/* utils macro ---------------------------------------------------------------*/
#define _1st_BYTE(x) (uint8_t)((x)&0xFF) /* 1st addressing cycle */
#define _2nd_BYTE(x) (uint8_t)(((x)&0xFF00)>>8) /* 2nd addressing cycle */
#define _3rd_BYTE(x) (uint8_t)(((x)&0xFF0000)>>16) /* 3rd addressing cycle */
#define _4th_BYTE(x) (uint8_t)(((x)&0xFF000000)>>24) /* 4th addressing cycle */
/* Exported macro ------------------------------------------------------------*/
#define SET_POLLING_TIMING(x) buffer[1] = _1st_BYTE(x);\
buffer[2] = _2nd_BYTE(x);\
buffer[3] = _3rd_BYTE(x);
/* Exported functions ------------------------------------------------------- */
uint16_t MAL_Init (void);
uint16_t MAL_Erase (uint32_t SectorAddress);
uint16_t MAL_Write (uint32_t SectorAddress, uint32_t DataLength);
uint8_t *MAL_Read (uint32_t SectorAddress, uint32_t DataLength);
uint16_t MAL_GetStatus(uint32_t SectorAddress ,uint8_t Cmd, uint8_t *buffer);
extern uint8_t MAL_Buffer[wTransferSize]; /* RAM Buffer for Downloaded Data */
#endif /* __DFU_MAL_H */
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -1,34 +0,0 @@
/******************** (C) COPYRIGHT 2010 STMicroelectronics ********************
* File Name : flash_if.h
* Author : MCD Application Team
* Version : V3.2.1
* Date : 07/05/2010
* Description : Header for flash_if.c file.
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __FLASH_IF_MAL_H
#define __FLASH_IF_MAL_H
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
uint16_t FLASH_If_Init(void);
uint16_t FLASH_If_Erase (uint32_t SectorAddress);
uint16_t FLASH_If_Write (uint32_t SectorAddress, uint32_t DataLength);
uint8_t *FLASH_If_Read (uint32_t SectorAddress, uint32_t DataLength);
#endif /* __FLASH_IF_MAL_H */
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -1,58 +0,0 @@
/******************** (C) COPYRIGHT 2010 STMicroelectronics ********************
* File Name : fsmc_nor.h
* Author : MCD Application Team
* Version : V3.2.1
* Date : 07/05/2010
* Description : Header for fsmc_nor.c file.
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __FSMC_NOR_H
#define __FSMC_NOR_H
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
/* Exported types ------------------------------------------------------------*/
typedef struct
{
uint16_t Manufacturer_Code;
uint16_t Device_Code1;
uint16_t Device_Code2;
uint16_t Device_Code3;
}NOR_IDTypeDef;
/* NOR Status */
typedef enum
{
NOR_SUCCESS = 0,
NOR_ONGOING,
NOR_ERROR,
NOR_TIMEOUT
}NOR_Status;
/* Exported constants --------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
void FSMC_NOR_Init(void);
void FSMC_NOR_ReadID(NOR_IDTypeDef* NOR_ID);
NOR_Status FSMC_NOR_EraseBlock(uint32_t BlockAddr);
NOR_Status FSMC_NOR_EraseChip(void);
NOR_Status FSMC_NOR_WriteHalfWord(uint32_t WriteAddr, uint16_t Data);
NOR_Status FSMC_NOR_WriteBuffer(uint16_t* pBuffer, uint32_t WriteAddr, uint32_t NumHalfwordToWrite);
NOR_Status FSMC_NOR_ProgramBuffer(uint16_t* pBuffer, uint32_t WriteAddr, uint32_t NumHalfwordToWrite);
uint16_t FSMC_NOR_ReadHalfWord(uint32_t ReadAddr);
void FSMC_NOR_ReadBuffer(uint16_t* pBuffer, uint32_t ReadAddr, uint32_t NumHalfwordToRead);
NOR_Status FSMC_NOR_ReturnToReadMode(void);
NOR_Status FSMC_NOR_Reset(void);
NOR_Status FSMC_NOR_GetStatus(uint32_t Timeout);
#endif /* __FSMC_NOR_H */
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -1,34 +0,0 @@
/******************** (C) COPYRIGHT 2010 STMicroelectronics ********************
* File Name : nor_if.h
* Author : MCD Application Team
* Version : V3.2.1
* Date : 07/05/2010
* Description : Header for nor_if.c file.
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __NOR_IF_MAL_H
#define __NOR_IF_MAL_H
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
uint16_t NOR_If_Init(void);
uint16_t NOR_If_Erase(uint32_t Address);
uint16_t NOR_If_Write(uint32_t Address, uint32_t DataLength);
uint8_t *NOR_If_Read(uint32_t Address, uint32_t DataLength);
#endif /* __NOR_IF_MAL_H */
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -1,68 +0,0 @@
/******************** (C) COPYRIGHT 2010 STMicroelectronics ********************
* File Name : spi_flash.h
* Author : MCD Application Team
* Version : V3.2.1
* Date : 07/05/2010
* Description : Header for spi_flash.c file.
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __SPI_FLASH_H
#define __SPI_FLASH_H
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* Uncomment the line corresponding to the STMicroelectronics evaluation board
used to run the example */
#if !defined (USE_STM3210B_EVAL) && !defined (USE_STM3210E_EVAL) && !defined (USE_STM3210C_EVAL)
//#define USE_STM3210B_EVAL
#define USE_STM3210E_EVAL
#endif
#ifdef USE_STM3210B_EVAL
#define GPIO_CS GPIOA
#define RCC_APB2Periph_GPIO_CS RCC_APB2Periph_GPIOA
#define GPIO_Pin_CS GPIO_Pin_4
#else /* USE_STM3210E_EVAL */
#define GPIO_CS GPIOB
#define RCC_APB2Periph_GPIO_CS RCC_APB2Periph_GPIOB
#define GPIO_Pin_CS GPIO_Pin_2
#endif
/* Exported macro ------------------------------------------------------------*/
/* Select SPI FLASH: Chip Select pin low */
#define SPI_FLASH_CS_LOW() GPIO_ResetBits(GPIO_CS, GPIO_Pin_CS)
/* Deselect SPI FLASH: Chip Select pin high */
#define SPI_FLASH_CS_HIGH() GPIO_SetBits(GPIO_CS, GPIO_Pin_CS)
/* Exported functions ------------------------------------------------------- */
/*----- High layer function -----*/
void SPI_FLASH_Init(void);
void SPI_FLASH_SectorErase(uint32_t SectorAddr);
void SPI_FLASH_BulkErase(void);
void SPI_FLASH_PageWrite(uint8_t* pBuffer, uint32_t WriteAddr, uint16_t NumByteToWrite);
void SPI_FLASH_BufferWrite(uint8_t* pBuffer, uint32_t WriteAddr, uint16_t NumByteToWrite);
void SPI_FLASH_BufferRead(uint8_t* pBuffer, uint32_t ReadAddr, uint16_t NumByteToRead);
uint32_t SPI_FLASH_ReadID(void);
void SPI_FLASH_StartReadSequence(uint32_t ReadAddr);
/*----- Low layer function -----*/
uint8_t SPI_FLASH_ReadByte(void);
uint8_t SPI_FLASH_SendByte(uint8_t byte);
uint16_t SPI_FLASH_SendHalfWord(uint16_t HalfWord);
void SPI_FLASH_WriteEnable(void);
void SPI_FLASH_WaitForWriteEnd(void);
#endif /* __SPI_FLASH_H */
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -1,34 +0,0 @@
/******************** (C) COPYRIGHT 2010 STMicroelectronics ********************
* File Name : dfu_mal.h
* Author : MCD Application Team
* Version : V3.2.1
* Date : 07/05/2010
* Description : Header for dfu_mal.c file.
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __SPI_IF_MAL_H
#define __SPI_IF_MAL_H
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
uint16_t SPI_If_Init(void);
uint16_t SPI_If_Erase (uint32_t SectorAddress);
uint16_t SPI_If_Write (uint32_t SectorAddress, uint32_t DataLength);
uint8_t *SPI_If_Read (uint32_t SectorAddress, uint32_t DataLength);
#endif /* __SPI_IF_MAL_H */
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -1,69 +0,0 @@
/******************** (C) COPYRIGHT 2010 STMicroelectronics ********************
* File Name : usb_desc.h
* Author : MCD Application Team
* Version : V3.2.1
* Date : 07/05/2010
* Description : Descriptor Header for Device Firmware Upgrade (DFU)
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __USB_DESC_H
#define __USB_DESC_H
#include "platform_config.h"
/* Includes ------------------------------------------------------------------*/
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
#define DFU_SIZ_DEVICE_DESC 18
#ifdef USE_STM3210B_EVAL
#define DFU_SIZ_CONFIG_DESC 36
#elif defined(USE_STM3210C_EVAL)
#define DFU_SIZ_CONFIG_DESC 27
#elif defined(USE_STM3210E_EVAL)
#define DFU_SIZ_CONFIG_DESC 45
#endif /* USE_STM3210B_EVAL */
#define DFU_SIZ_STRING_LANGID 4
#define DFU_SIZ_STRING_VENDOR 38
#define DFU_SIZ_STRING_PRODUCT 20
#define DFU_SIZ_STRING_SERIAL 26
#define DFU_SIZ_STRING_INTERFACE0 96 /* Flash Bank 0 */
#define DFU_SIZ_STRING_INTERFACE1 98 /* SPI Flash : M25P64*/
#define DFU_SIZ_STRING_INTERFACE2 106 /* NOR Flash : M26M128*/
extern uint8_t DFU_DeviceDescriptor[DFU_SIZ_DEVICE_DESC];
extern uint8_t DFU_ConfigDescriptor[DFU_SIZ_CONFIG_DESC];
extern uint8_t DFU_StringLangId [DFU_SIZ_STRING_LANGID];
extern uint8_t DFU_StringVendor [DFU_SIZ_STRING_VENDOR];
extern uint8_t DFU_StringProduct [DFU_SIZ_STRING_PRODUCT];
extern uint8_t DFU_StringSerial [DFU_SIZ_STRING_SERIAL];
extern uint8_t DFU_StringInterface0 [DFU_SIZ_STRING_INTERFACE0];
extern uint8_t DFU_StringInterface1 [DFU_SIZ_STRING_INTERFACE1];
extern uint8_t DFU_StringInterface2_1 [DFU_SIZ_STRING_INTERFACE2];
extern uint8_t DFU_StringInterface2_2 [DFU_SIZ_STRING_INTERFACE2];
extern uint8_t DFU_StringInterface2_3 [DFU_SIZ_STRING_INTERFACE2];
#define bMaxPacketSize0 0x40 /* bMaxPacketSize0 = 64 bytes */
#define wTransferSize 0x0400 /* wTransferSize = 1024 bytes */
/* bMaxPacketSize0 <= wTransferSize <= 32kbytes */
#define wTransferSizeB0 0x00
#define wTransferSizeB1 0x04
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
/* External variables --------------------------------------------------------*/
#endif /* __USB_DESC_H */
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -1,128 +0,0 @@
/******************** (C) COPYRIGHT 2010 STMicroelectronics ********************
* File Name : usb_prop.h
* Author : MCD Application Team
* Version : V3.2.1
* Date : 07/05/2010
* Description : All processings related to DFU demo
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __USB_PROP_H
#define __USB_PROP_H
/* Includes ------------------------------------------------------------------*/
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
void DFU_init(void);
void DFU_Reset(void);
void DFU_SetConfiguration(void);
void DFU_SetDeviceAddress (void);
void DFU_Status_In (void);
void DFU_Status_Out (void);
RESULT DFU_Data_Setup(uint8_t);
RESULT DFU_NoData_Setup(uint8_t);
RESULT DFU_Get_Interface_Setting(uint8_t Interface, uint8_t AlternateSetting);
uint8_t *DFU_GetDeviceDescriptor(uint16_t );
uint8_t *DFU_GetConfigDescriptor(uint16_t);
uint8_t *DFU_GetStringDescriptor(uint16_t);
uint8_t *UPLOAD(uint16_t Length);
uint8_t *DNLOAD(uint16_t Length);
uint8_t *GETSTATE(uint16_t Length);
uint8_t *GETSTATUS(uint16_t Length);
void DFU_write_crc (void);
/* External variables --------------------------------------------------------*/
#define DFU_GetConfiguration NOP_Process
//#define DFU_SetConfiguration NOP_Process
#define DFU_GetInterface NOP_Process
#define DFU_SetInterface NOP_Process
#define DFU_GetStatus NOP_Process
#define DFU_ClearFeature NOP_Process
#define DFU_SetEndPointFeature NOP_Process
#define DFU_SetDeviceFeature NOP_Process
//#define DFU_SetDeviceAddress NOP_Process
/*---------------------------------------------------------------------*/
/* DFU definitions */
/*---------------------------------------------------------------------*/
/**************************************************/
/* DFU Requests */
/**************************************************/
typedef enum _DFU_REQUESTS {
DFU_DNLOAD = 1,
DFU_UPLOAD,
DFU_GETSTATUS,
DFU_CLRSTATUS,
DFU_GETSTATE,
DFU_ABORT
} DFU_REQUESTS;
/**************************************************/
/* DFU Requests DFU states */
/**************************************************/
#define STATE_appIDLE 0
#define STATE_appDETACH 1
#define STATE_dfuIDLE 2
#define STATE_dfuDNLOAD_SYNC 3
#define STATE_dfuDNBUSY 4
#define STATE_dfuDNLOAD_IDLE 5
#define STATE_dfuMANIFEST_SYNC 6
#define STATE_dfuMANIFEST 7
#define STATE_dfuMANIFEST_WAIT_RESET 8
#define STATE_dfuUPLOAD_IDLE 9
#define STATE_dfuERROR 10
/**************************************************/
/* DFU Requests DFU status */
/**************************************************/
#define STATUS_OK 0x00
#define STATUS_ERRTARGET 0x01
#define STATUS_ERRFILE 0x02
#define STATUS_ERRWRITE 0x03
#define STATUS_ERRERASE 0x04
#define STATUS_ERRCHECK_ERASED 0x05
#define STATUS_ERRPROG 0x06
#define STATUS_ERRVERIFY 0x07
#define STATUS_ERRADDRESS 0x08
#define STATUS_ERRNOTDONE 0x09
#define STATUS_ERRFIRMWARE 0x0A
#define STATUS_ERRVENDOR 0x0B
#define STATUS_ERRUSBR 0x0C
#define STATUS_ERRPOR 0x0D
#define STATUS_ERRUNKNOWN 0x0E
#define STATUS_ERRSTALLEDPKT 0x0F
/**************************************************/
/* DFU Requests DFU states Manifestation State */
/**************************************************/
#define Manifest_complete 0x00
#define Manifest_In_Progress 0x01
/**************************************************/
/* Special Commands with Download Request */
/**************************************************/
#define CMD_GETCOMMANDS 0x00
#define CMD_SETADDRESSPOINTER 0x21
#define CMD_ERASE 0x41
#endif /* __USB_PROP_H */
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -1,101 +0,0 @@
/******************** (C) COPYRIGHT 2010 STMicroelectronics ********************
* File Name : nor_if.c
* Author : MCD Application Team
* Version : V3.2.1
* Date : 07/05/2010
* Description : specific media access Layer for NOR flash
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
#include "platform_config.h"
#ifdef USE_STM3210E_EVAL
/* Includes ------------------------------------------------------------------*/
#include "fsmc_nor.h"
#include "nor_if.h"
#include "dfu_mal.h"
#include "stm32f10x_fsmc.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
extern NOR_IDTypeDef NOR_ID;
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
* Function Name : NOR_If_Init
* Description : Initializes the Media on the STM32
* Input : None
* Output : None
* Return : None
*******************************************************************************/
uint16_t NOR_If_Init(void)
{
/* Configure FSMC Bank1 NOR/SRAM2 */
FSMC_NOR_Init();
/* Enable FSMC Bank1 NOR/SRAM2 */
FSMC_NORSRAMCmd(FSMC_Bank1_NORSRAM2, ENABLE);
return MAL_OK;
}
/*******************************************************************************
* Function Name : NOR_If_Erase
* Description : Erase sector
* Input : None
* Output : None
* Return : None
*******************************************************************************/
uint16_t NOR_If_Erase(uint32_t Address)
{
/* Erase the destination memory */
FSMC_NOR_EraseBlock(Address & 0x00FFFFFF);
return MAL_OK;
}
/*******************************************************************************
* Function Name : NOR_If_Write
* Description : Write sectors
* Input : None
* Output : None
* Return : None
*******************************************************************************/
uint16_t NOR_If_Write(uint32_t Address, uint32_t DataLength)
{
if ((DataLength & 1) == 1) /* Not an aligned data */
{
DataLength += 1;
MAL_Buffer[DataLength-1] = 0xFF;
}
FSMC_NOR_WriteBuffer((uint16_t *)MAL_Buffer, (Address&0x00FFFFFF), DataLength >> 1);
return MAL_OK;
}
/*******************************************************************************
* Function Name : NOR_If_Read
* Description : Read sectors
* Input : None
* Output : None
* Return : buffer address pointer
*******************************************************************************/
uint8_t *NOR_If_Read(uint32_t Address, uint32_t DataLength)
{
return (uint8_t*)(Address);
}
#endif
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -1,482 +0,0 @@
/******************** (C) COPYRIGHT 2010 STMicroelectronics ********************
* File Name : spi_flash.c
* Author : MCD Application Team
* Version : V3.2.1
* Date : 07/05/2010
* Description : This file provides a set of functions needed to manage the
* communication between SPI peripheral and SPI M25P64 FLASH.
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Includes ------------------------------------------------------------------*/
#include "spi_flash.h"
/* Private typedef -----------------------------------------------------------*/
#define SPI_FLASH_PageSize 0x100
/* Private define ------------------------------------------------------------*/
#define WRITE 0x02 /* Write to Memory instruction */
#define WRSR 0x01 /* Write Status Register instruction */
#define WREN 0x06 /* Write enable instruction */
#define READ 0x03 /* Read from Memory instruction */
#define RDSR 0x05 /* Read Status Register instruction */
#define RDID 0x9F /* Read identification */
#define SE 0xD8 /* Sector Erase instruction */
#define BE 0xC7 /* Bulk Erase instruction */
#define WIP_Flag 0x01 /* Write In Progress (WIP) flag */
#define Dummy_Byte 0xA5
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
* Function Name : SPI_FLASH_Init
* Description : Initializes the peripherals used by the SPI FLASH driver.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void SPI_FLASH_Init(void)
{
SPI_InitTypeDef SPI_InitStructure;
GPIO_InitTypeDef GPIO_InitStructure;
/* Enable SPI1 and GPIO clocks */
RCC_APB2PeriphClockCmd(RCC_APB2Periph_SPI1 | RCC_APB2Periph_GPIOA |
RCC_APB2Periph_GPIO_CS, ENABLE);
/* Configure SPI1 pins: SCK, MISO and MOSI */
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_5 | GPIO_Pin_6 | GPIO_Pin_7;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_Init(GPIOA, &GPIO_InitStructure);
/* Configure I/O for Flash Chip select */
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_CS;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
GPIO_Init(GPIO_CS, &GPIO_InitStructure);
/* Deselect the FLASH: Chip Select high */
SPI_FLASH_CS_HIGH();
/* SPI1 configuration */
SPI_InitStructure.SPI_Direction = SPI_Direction_2Lines_FullDuplex;
SPI_InitStructure.SPI_Mode = SPI_Mode_Master;
SPI_InitStructure.SPI_DataSize = SPI_DataSize_8b;
SPI_InitStructure.SPI_CPOL = SPI_CPOL_High;
SPI_InitStructure.SPI_CPHA = SPI_CPHA_2Edge;
SPI_InitStructure.SPI_NSS = SPI_NSS_Soft;
SPI_InitStructure.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_4;
SPI_InitStructure.SPI_FirstBit = SPI_FirstBit_MSB;
SPI_InitStructure.SPI_CRCPolynomial = 7;
SPI_Init(SPI1, &SPI_InitStructure);
/* Enable SPI1 */
SPI_Cmd(SPI1, ENABLE);
}
/*******************************************************************************
* Function Name : SPI_FLASH_SectorErase
* Description : Erases the specified FLASH sector.
* Input : SectorAddr: address of the sector to erase.
* Output : None
* Return : None
*******************************************************************************/
void SPI_FLASH_SectorErase(uint32_t SectorAddr)
{
/* Send write enable instruction */
SPI_FLASH_WriteEnable();
/* Sector Erase */
/* Select the FLASH: Chip Select low */
SPI_FLASH_CS_LOW();
/* Send Sector Erase instruction */
SPI_FLASH_SendByte(SE);
/* Send SectorAddr high nibble address byte */
SPI_FLASH_SendByte((SectorAddr & 0xFF0000) >> 16);
/* Send SectorAddr medium nibble address byte */
SPI_FLASH_SendByte((SectorAddr & 0xFF00) >> 8);
/* Send SectorAddr low nibble address byte */
SPI_FLASH_SendByte(SectorAddr & 0xFF);
/* Deselect the FLASH: Chip Select high */
SPI_FLASH_CS_HIGH();
/* Wait the end of Flash writing */
SPI_FLASH_WaitForWriteEnd();
}
/*******************************************************************************
* Function Name : SPI_FLASH_BulkErase
* Description : Erases the entire FLASH.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void SPI_FLASH_BulkErase(void)
{
/* Send write enable instruction */
SPI_FLASH_WriteEnable();
/* Bulk Erase */
/* Select the FLASH: Chip Select low */
SPI_FLASH_CS_LOW();
/* Send Bulk Erase instruction */
SPI_FLASH_SendByte(BE);
/* Deselect the FLASH: Chip Select high */
SPI_FLASH_CS_HIGH();
/* Wait the end of Flash writing */
SPI_FLASH_WaitForWriteEnd();
}
/*******************************************************************************
* Function Name : SPI_FLASH_PageWrite
* Description : Writes more than one byte to the FLASH with a single WRITE
* cycle(Page WRITE sequence). The number of byte can't exceed
* the FLASH page size.
* Input : - pBuffer : pointer to the buffer containing the data to be
* written to the FLASH.
* - WriteAddr : FLASH's internal address to write to.
* - NumByteToWrite : number of bytes to write to the FLASH,
* must be equal or less than "SPI_FLASH_PageSize" value.
* Output : None
* Return : None
*******************************************************************************/
void SPI_FLASH_PageWrite(uint8_t* pBuffer, uint32_t WriteAddr, uint16_t NumByteToWrite)
{
/* Enable the write access to the FLASH */
SPI_FLASH_WriteEnable();
/* Select the FLASH: Chip Select low */
SPI_FLASH_CS_LOW();
/* Send "Write to Memory " instruction */
SPI_FLASH_SendByte(WRITE);
/* Send WriteAddr high nibble address byte to write to */
SPI_FLASH_SendByte((WriteAddr & 0xFF0000) >> 16);
/* Send WriteAddr medium nibble address byte to write to */
SPI_FLASH_SendByte((WriteAddr & 0xFF00) >> 8);
/* Send WriteAddr low nibble address byte to write to */
SPI_FLASH_SendByte(WriteAddr & 0xFF);
/* while there is data to be written on the FLASH */
while (NumByteToWrite--)
{
/* Send the current byte */
SPI_FLASH_SendByte(*pBuffer);
/* Point on the next byte to be written */
pBuffer++;
}
/* Deselect the FLASH: Chip Select high */
SPI_FLASH_CS_HIGH();
/* Wait the end of Flash writing */
SPI_FLASH_WaitForWriteEnd();
}
/*******************************************************************************
* Function Name : SPI_FLASH_BufferWrite
* Description : Writes block of data to the FLASH. In this function, the
* number of WRITE cycles are reduced, using Page WRITE sequence.
* Input : - pBuffer : pointer to the buffer containing the data to be
* written to the FLASH.
* - WriteAddr : FLASH's internal address to write to.
* - NumByteToWrite : number of bytes to write to the FLASH.
* Output : None
* Return : None
*******************************************************************************/
void SPI_FLASH_BufferWrite(uint8_t* pBuffer, uint32_t WriteAddr, uint16_t NumByteToWrite)
{
uint8_t NumOfPage = 0, NumOfSingle = 0, Addr = 0, count = 0, temp = 0;
Addr = WriteAddr % SPI_FLASH_PageSize;
count = SPI_FLASH_PageSize - Addr;
NumOfPage = NumByteToWrite / SPI_FLASH_PageSize;
NumOfSingle = NumByteToWrite % SPI_FLASH_PageSize;
if (Addr == 0) /* WriteAddr is SPI_FLASH_PageSize aligned */
{
if (NumOfPage == 0) /* NumByteToWrite < SPI_FLASH_PageSize */
{
SPI_FLASH_PageWrite(pBuffer, WriteAddr, NumByteToWrite);
}
else /* NumByteToWrite > SPI_FLASH_PageSize */
{
while (NumOfPage--)
{
SPI_FLASH_PageWrite(pBuffer, WriteAddr, SPI_FLASH_PageSize);
WriteAddr += SPI_FLASH_PageSize;
pBuffer += SPI_FLASH_PageSize;
}
SPI_FLASH_PageWrite(pBuffer, WriteAddr, NumOfSingle);
}
}
else /* WriteAddr is not SPI_FLASH_PageSize aligned */
{
if (NumOfPage == 0) /* NumByteToWrite < SPI_FLASH_PageSize */
{
if (NumOfSingle > count) /* (NumByteToWrite + WriteAddr) > SPI_FLASH_PageSize */
{
temp = NumOfSingle - count;
SPI_FLASH_PageWrite(pBuffer, WriteAddr, count);
WriteAddr += count;
pBuffer += count;
SPI_FLASH_PageWrite(pBuffer, WriteAddr, temp);
}
else
{
SPI_FLASH_PageWrite(pBuffer, WriteAddr, NumByteToWrite);
}
}
else /* NumByteToWrite > SPI_FLASH_PageSize */
{
NumByteToWrite -= count;
NumOfPage = NumByteToWrite / SPI_FLASH_PageSize;
NumOfSingle = NumByteToWrite % SPI_FLASH_PageSize;
SPI_FLASH_PageWrite(pBuffer, WriteAddr, count);
WriteAddr += count;
pBuffer += count;
while (NumOfPage--)
{
SPI_FLASH_PageWrite(pBuffer, WriteAddr, SPI_FLASH_PageSize);
WriteAddr += SPI_FLASH_PageSize;
pBuffer += SPI_FLASH_PageSize;
}
if (NumOfSingle != 0)
{
SPI_FLASH_PageWrite(pBuffer, WriteAddr, NumOfSingle);
}
}
}
}
/*******************************************************************************
* Function Name : SPI_FLASH_BufferRead
* Description : Reads a block of data from the FLASH.
* Input : - pBuffer : pointer to the buffer that receives the data read
* from the FLASH.
* - ReadAddr : FLASH's internal address to read from.
* - NumByteToRead : number of bytes to read from the FLASH.
* Output : None
* Return : None
*******************************************************************************/
void SPI_FLASH_BufferRead(uint8_t* pBuffer, uint32_t ReadAddr, uint16_t NumByteToRead)
{
/* Select the FLASH: Chip Select low */
SPI_FLASH_CS_LOW();
/* Send "Read from Memory " instruction */
SPI_FLASH_SendByte(READ);
/* Send ReadAddr high nibble address byte to read from */
SPI_FLASH_SendByte((ReadAddr & 0xFF0000) >> 16);
/* Send ReadAddr medium nibble address byte to read from */
SPI_FLASH_SendByte((ReadAddr& 0xFF00) >> 8);
/* Send ReadAddr low nibble address byte to read from */
SPI_FLASH_SendByte(ReadAddr & 0xFF);
while (NumByteToRead--) /* while there is data to be read */
{
/* Read a byte from the FLASH */
*pBuffer = SPI_FLASH_SendByte(Dummy_Byte);
/* Point to the next location where the byte read will be saved */
pBuffer++;
}
/* Deselect the FLASH: Chip Select high */
SPI_FLASH_CS_HIGH();
}
/*******************************************************************************
* Function Name : SPI_FLASH_ReadID
* Description : Reads FLASH identification.
* Input : None
* Output : None
* Return : FLASH identification
*******************************************************************************/
uint32_t SPI_FLASH_ReadID(void)
{
uint32_t Temp = 0, Temp0 = 0, Temp1 = 0, Temp2 = 0;
/* Select the FLASH: Chip Select low */
SPI_FLASH_CS_LOW();
/* Send "RDID " instruction */
SPI_FLASH_SendByte(0x9F);
/* Read a byte from the FLASH */
Temp0 = SPI_FLASH_SendByte(Dummy_Byte);
/* Read a byte from the FLASH */
Temp1 = SPI_FLASH_SendByte(Dummy_Byte);
/* Read a byte from the FLASH */
Temp2 = SPI_FLASH_SendByte(Dummy_Byte);
/* Deselect the FLASH: Chip Select high */
SPI_FLASH_CS_HIGH();
Temp = (Temp0 << 16) | (Temp1 << 8) | Temp2;
return Temp;
}
/*******************************************************************************
* Function Name : SPI_FLASH_StartReadSequence
* Description : Initiates a read data byte (READ) sequence from the Flash.
* This is done by driving the /CS line low to select the device,
* then the READ instruction is transmitted followed by 3 bytes
* address. This function exit and keep the /CS line low, so the
* Flash still being selected. With this technique the whole
* content of the Flash is read with a single READ instruction.
* Input : - ReadAddr : FLASH's internal address to read from.
* Output : None
* Return : None
*******************************************************************************/
void SPI_FLASH_StartReadSequence(uint32_t ReadAddr)
{
/* Select the FLASH: Chip Select low */
SPI_FLASH_CS_LOW();
/* Send "Read from Memory " instruction */
SPI_FLASH_SendByte(READ);
/* Send the 24-bit address of the address to read from -----------------------*/
/* Send ReadAddr high nibble address byte */
SPI_FLASH_SendByte((ReadAddr & 0xFF0000) >> 16);
/* Send ReadAddr medium nibble address byte */
SPI_FLASH_SendByte((ReadAddr& 0xFF00) >> 8);
/* Send ReadAddr low nibble address byte */
SPI_FLASH_SendByte(ReadAddr & 0xFF);
}
/*******************************************************************************
* Function Name : SPI_FLASH_ReadByte
* Description : Reads a byte from the SPI Flash.
* This function must be used only if the Start_Read_Sequence
* function has been previously called.
* Input : None
* Output : None
* Return : Byte Read from the SPI Flash.
*******************************************************************************/
uint8_t SPI_FLASH_ReadByte(void)
{
return (SPI_FLASH_SendByte(Dummy_Byte));
}
/*******************************************************************************
* Function Name : SPI_FLASH_SendByte
* Description : Sends a byte through the SPI interface and return the byte
* received from the SPI bus.
* Input : byte : byte to send.
* Output : None
* Return : The value of the received byte.
*******************************************************************************/
uint8_t SPI_FLASH_SendByte(uint8_t byte)
{
/* Loop while DR register in not emplty */
while (SPI_I2S_GetFlagStatus(SPI1, SPI_I2S_FLAG_TXE) == RESET);
/* Send byte through the SPI1 peripheral */
SPI_I2S_SendData(SPI1, byte);
/* Wait to receive a byte */
while (SPI_I2S_GetFlagStatus(SPI1, SPI_I2S_FLAG_RXNE) == RESET);
/* Return the byte read from the SPI bus */
return SPI_I2S_ReceiveData(SPI1);
}
/*******************************************************************************
* Function Name : SPI_FLASH_SendHalfWord
* Description : Sends a Half Word through the SPI interface and return the
* Half Word received from the SPI bus.
* Input : Half Word : Half Word to send.
* Output : None
* Return : The value of the received Half Word.
*******************************************************************************/
uint16_t SPI_FLASH_SendHalfWord(uint16_t HalfWord)
{
/* Loop while DR register in not emplty */
while (SPI_I2S_GetFlagStatus(SPI1, SPI_I2S_FLAG_TXE) == RESET);
/* Send Half Word through the SPI1 peripheral */
SPI_I2S_SendData(SPI1, HalfWord);
/* Wait to receive a Half Word */
while (SPI_I2S_GetFlagStatus(SPI1, SPI_I2S_FLAG_RXNE) == RESET);
/* Return the Half Word read from the SPI bus */
return SPI_I2S_ReceiveData(SPI1);
}
/*******************************************************************************
* Function Name : SPI_FLASH_WriteEnable
* Description : Enables the write access to the FLASH.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void SPI_FLASH_WriteEnable(void)
{
/* Select the FLASH: Chip Select low */
SPI_FLASH_CS_LOW();
/* Send "Write Enable" instruction */
SPI_FLASH_SendByte(WREN);
/* Deselect the FLASH: Chip Select high */
SPI_FLASH_CS_HIGH();
}
/*******************************************************************************
* Function Name : SPI_FLASH_WaitForWriteEnd
* Description : Polls the status of the Write In Progress (WIP) flag in the
* FLASH's status register and loop until write opertaion
* has completed.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void SPI_FLASH_WaitForWriteEnd(void)
{
uint8_t FLASH_Status = 0;
/* Select the FLASH: Chip Select low */
SPI_FLASH_CS_LOW();
/* Send "Read Status Register" instruction */
SPI_FLASH_SendByte(RDSR);
/* Loop as long as the memory is busy with a write cycle */
do
{
/* Send a dummy byte to generate the clock needed by the FLASH
and put the value of the status register in FLASH_Status variable */
FLASH_Status = SPI_FLASH_SendByte(Dummy_Byte);
}
while ((FLASH_Status & WIP_Flag) == SET); /* Write in progress */
/* Deselect the FLASH: Chip Select high */
SPI_FLASH_CS_HIGH();
}
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -1,97 +0,0 @@
/******************** (C) COPYRIGHT 2010 STMicroelectronics ********************
* File Name : spi_if.c
* Author : MCD Application Team
* Version : V3.2.1
* Date : 07/05/2010
* Description : specific media access Layer for SPI flash
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Includes ------------------------------------------------------------------*/
#include "spi_flash.h"
#include "spi_if.h"
#include "dfu_mal.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
* Function Name : SPI_If_Init
* Description : Initializes the Media on the STM32
* Input : None
* Output : None
* Return : None
*******************************************************************************/
uint16_t SPI_If_Init(void)
{
SPI_FLASH_Init();
return MAL_OK;
}
/*******************************************************************************
* Function Name : SPI_If_Erase
* Description : Erase sector
* Input : None
* Output : None
* Return : None
*******************************************************************************/
uint16_t SPI_If_Erase(uint32_t SectorAddress)
{
SPI_FLASH_SectorErase(SectorAddress);
return MAL_OK;
}
/*******************************************************************************
* Function Name : SPI_If_Write
* Description : Write sectors
* Input : None
* Output : None
* Return : None
*******************************************************************************/
uint16_t SPI_If_Write(uint32_t SectorAddress, uint32_t DataLength)
{
uint32_t idx, pages;
pages = (((DataLength & 0xFF00)) >> 8);
if (DataLength & 0xFF) /* Not a 256 aligned data */
{
for ( idx = DataLength; idx < ((DataLength & 0xFF00) + 0x100) ; idx++)
{
MAL_Buffer[idx] = 0xFF;
}
pages = (((DataLength & 0xFF00)) >> 8 ) + 1;
}
for (idx = 0; idx < pages; idx++)
{
SPI_FLASH_PageWrite(&MAL_Buffer[idx*256], SectorAddress, 256);
SectorAddress += 0x100;
}
return MAL_OK;
}
/*******************************************************************************
* Function Name : SPI_If_Read
* Description : Read sectors
* Input : None
* Output : None
* Return : buffer address pointer
*******************************************************************************/
uint8_t *SPI_If_Read(uint32_t SectorAddress, uint32_t DataLength)
{
SPI_FLASH_BufferRead(MAL_Buffer, SectorAddress, (uint16_t)DataLength);
return MAL_Buffer;
}
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -1,400 +0,0 @@
/******************** (C) COPYRIGHT 2010 STMicroelectronics ********************
* File Name : usb_desc.c
* Author : MCD Application Team
* Version : V3.2.1
* Date : 07/05/2010
* Description : Descriptors for Device Firmware Upgrade (DFU)
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Includes ------------------------------------------------------------------*/
#include "usb_desc.h"
#include "platform_config.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Extern variables ----------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
uint8_t DFU_DeviceDescriptor[DFU_SIZ_DEVICE_DESC] =
{
0x12, /* bLength */
0x01, /* bDescriptorType */
0x00, /* bcdUSB, version 1.00 */
0x01,
0x00, /* bDeviceClass : See interface */
0x00, /* bDeviceSubClass : See interface*/
0x00, /* bDeviceProtocol : See interface */
bMaxPacketSize0, /* bMaxPacketSize0 0x40 = 64 */
0x83, /* idVendor (0483) */
0x04,
0x11, /* idProduct (0xDF11) DFU PiD*/
0xDF,
0x00, /* bcdDevice*/
0x02,
0x01, /* iManufacturer : index of string Manufacturer */
0x02, /* iProduct : index of string descriptor of product*/
0x03, /* iSerialNumber : index of string serial number*/
0x01 /*bNumConfigurations */
};
#ifdef USE_STM3210B_EVAL
uint8_t DFU_ConfigDescriptor[DFU_SIZ_CONFIG_DESC] =
{
0x09, /* bLength: Configuation Descriptor size */
0x02, /* bDescriptorType: Configuration */
DFU_SIZ_CONFIG_DESC, /* wTotalLength: Bytes returned */
0x00,
0x01, /* bNumInterfaces: 1 interface */
0x01, /* bConfigurationValue: */
/* Configuration value */
0x00, /* iConfiguration: */
/* Index of string descriptor */
/* describing the configuration */
0xC0, /* bmAttributes: */
/* bus powered */
0x32, /* MaxPower 100 mA */
/* 09 */
/************ Descriptor of DFU interface 0 Alternate setting 0 *********/
0x09, /* bLength: Interface Descriptor size */
0x04, /* bDescriptorType: */
/* Interface descriptor type */
0x00, /* bInterfaceNumber: Number of Interface */
0x00, /* bAlternateSetting: Alternate setting */
0x00, /* bNumEndpoints*/
0xFE, /* bInterfaceClass: Application Specific Class Code */
0x01, /* bInterfaceSubClass : Device Firmware Upgrade Code */
0x02, /* nInterfaceProtocol: DFU mode protocol */
0x04, /* iInterface: */
/* Index of string descriptor */
/* 18 */
/************ Descriptor of DFU interface 0 Alternate setting 1 **********/
0x09, /* bLength: Interface Descriptor size */
0x04, /* bDescriptorType: */
/* Interface descriptor type */
0x00, /* bInterfaceNumber: Number of Interface */
0x01, /* bAlternateSetting: Alternate setting */
0x00, /* bNumEndpoints*/
0xFE, /* bInterfaceClass: Application Specific Class Code */
0x01, /* bInterfaceSubClass : Device Firmware Upgrade Code */
0x02, /* nInterfaceProtocol: DFU mode protocol */
0x05, /* iInterface: */
/* Index of string descriptor */
/* 27 */
/******************** DFU Functional Descriptor********************/
0x09, /*blength = 9 Bytes*/
0x21, /* DFU Functional Descriptor*/
0x0B, /*bmAttribute
bitCanDnload = 1 (bit 0)
bitCanUpload = 1 (bit 1)
bitManifestationTolerant = 0 (bit 2)
bitWillDetach = 1 (bit 3)
Reserved (bit4-6)
bitAcceleratedST = 0 (bit 7)*/
0xFF, /*DetachTimeOut= 255 ms*/
0x00,
wTransferSizeB0,
wTransferSizeB1, /* TransferSize = 1024 Byte*/
0x1A, /* bcdDFUVersion*/
0x01
/***********************************************************/
/*36*/
};
#elif defined (USE_STM3210C_EVAL)
uint8_t DFU_ConfigDescriptor[DFU_SIZ_CONFIG_DESC] =
{
0x09, /* bLength: Configuation Descriptor size */
0x02, /* bDescriptorType: Configuration */
DFU_SIZ_CONFIG_DESC, /* wTotalLength: Bytes returned */
0x00,
0x01, /* bNumInterfaces: 1 interface */
0x01, /* bConfigurationValue: */
/* Configuration value */
0x00, /* iConfiguration: */
/* Index of string descriptor */
/* describing the configuration */
0xC0, /* bmAttributes: */
/* bus powered */
0x32, /* MaxPower 100 mA */
/* 09 */
/************ Descriptor of DFU interface 0 Alternate setting 0 *********/
0x09, /* bLength: Interface Descriptor size */
0x04, /* bDescriptorType: */
/* Interface descriptor type */
0x00, /* bInterfaceNumber: Number of Interface */
0x00, /* bAlternateSetting: Alternate setting */
0x00, /* bNumEndpoints*/
0xFE, /* bInterfaceClass: Application Specific Class Code */
0x01, /* bInterfaceSubClass : Device Firmware Upgrade Code */
0x02, /* nInterfaceProtocol: DFU mode protocol */
0x04, /* iInterface: */
/* Index of string descriptor */
/* 18 */
/******************** DFU Functional Descriptor********************/
0x09, /*blength = 9 Bytes*/
0x21, /* DFU Functional Descriptor*/
0x0B, /*bmAttribute
bitCanDnload = 1 (bit 0)
bitCanUpload = 1 (bit 1)
bitManifestationTolerant = 0 (bit 2)
bitWillDetach = 1 (bit 3)
Reserved (bit4-6)
bitAcceleratedST = 0 (bit 7)*/
0xFF, /*DetachTimeOut= 255 ms*/
0x00,
wTransferSizeB0,
wTransferSizeB1, /* TransferSize = 1024 Byte*/
0x1A, /* bcdDFUVersion*/
0x01
/***********************************************************/
/*27*/
};
#elif defined (USE_STM3210E_EVAL)
uint8_t DFU_ConfigDescriptor[DFU_SIZ_CONFIG_DESC] =
{
0x09, /* bLength: Configuation Descriptor size */
0x02, /* bDescriptorType: Configuration */
DFU_SIZ_CONFIG_DESC, /* wTotalLength: Bytes returned */
0x00,
0x01, /* bNumInterfaces: 1 interface */
0x01, /* bConfigurationValue: */
/* Configuration value */
0x00, /* iConfiguration: */
/* Index of string descriptor */
/* describing the configuration */
0x80, /* bmAttributes: */
/* bus powered */
0x20, /* MaxPower 100 mA: this current is used for detecting Vbus */
/* 09 */
/************ Descriptor of DFU interface 0 Alternate setting 0 *********/
0x09, /* bLength: Interface Descriptor size */
0x04, /* bDescriptorType: */
/* Interface descriptor type */
0x00, /* bInterfaceNumber: Number of Interface */
0x00, /* bAlternateSetting: Alternate setting */
0x00, /* bNumEndpoints*/
0xFE, /* bInterfaceClass: Application Specific Class Code */
0x01, /* bInterfaceSubClass : Device Firmware Upgrade Code */
0x02, /* nInterfaceProtocol: DFU mode protocol */
0x04, /* iInterface: */
/* Index of string descriptor */
/* 18 */
/************ Descriptor of DFU interface 0 Alternate setting 1 **********/
0x09, /* bLength: Interface Descriptor size */
0x04, /* bDescriptorType: */
/* Interface descriptor type */
0x00, /* bInterfaceNumber: Number of Interface */
0x01, /* bAlternateSetting: Alternate setting */
0x00, /* bNumEndpoints*/
0xFE, /* bInterfaceClass: Application Specific Class Code */
0x01, /* bInterfaceSubClass : Device Firmware Upgrade Code */
0x02, /* nInterfaceProtocol: DFU mode protocol */
0x05, /* iInterface: */
/* Index of string descriptor */
/* 27 */
/************ Descriptor of DFU interface 0 Alternate setting 2 **********/
0x09, /* bLength: Interface Descriptor size */
0x04, /* bDescriptorType: */
/* Interface descriptor type */
0x00, /* bInterfaceNumber: Number of Interface */
0x02, /* bAlternateSetting: Alternate setting */
0x00, /* bNumEndpoints*/
0xFE, /* bInterfaceClass: Application Specific Class Code */
0x01, /* bInterfaceSubClass : Device Firmware Upgrade Code */
0x02, /* nInterfaceProtocol: DFU mode protocol */
0x06, /* iInterface: */
/* Index of string descriptor */
/* 36 */
/******************** DFU Functional Descriptor********************/
0x09, /*blength = 9 Bytes*/
0x21, /* DFU Functional Descriptor*/
0x0B, /*bmAttribute
bitCanDnload = 1 (bit 0)
bitCanUpload = 1 (bit 1)
bitManifestationTolerant = 0 (bit 2)
bitWillDetach = 1 (bit 3)
Reserved (bit4-6)
bitAcceleratedST = 0 (bit 7)*/
0xFF, /*DetachTimeOut= 255 ms*/
0x00,
wTransferSizeB0,
wTransferSizeB1, /* TransferSize = 1024 Byte*/
0x1A, /* bcdDFUVersion*/
0x01
/***********************************************************/
/*45*/
};
#endif /* USE_STM3210B_EVAL */
uint8_t DFU_StringLangId[DFU_SIZ_STRING_LANGID] =
{
DFU_SIZ_STRING_LANGID,
0x03,
0x09,
0x04 /* LangID = 0x0409: U.S. English */
};
uint8_t DFU_StringVendor[DFU_SIZ_STRING_VENDOR] =
{
DFU_SIZ_STRING_VENDOR,
0x03,
/* Manufacturer: "STMicroelectronics" */
'S', 0, 'T', 0, 'M', 0, 'i', 0, 'c', 0, 'r', 0, 'o', 0, 'e', 0,
'l', 0, 'e', 0, 'c', 0, 't', 0, 'r', 0, 'o', 0, 'n', 0, 'i', 0,
'c', 0, 's', 0
};
uint8_t DFU_StringProduct[DFU_SIZ_STRING_PRODUCT] =
{
DFU_SIZ_STRING_PRODUCT,
0x03,
/* Product name: "STM32 DFU" */
'S', 0, 'T', 0, 'M', 0, '3', 0, '2', 0, ' ', 0, 'D', 0, 'F', 0, 'U', 0
};
uint8_t DFU_StringSerial[DFU_SIZ_STRING_SERIAL] =
{
DFU_SIZ_STRING_SERIAL,
0x03,
/* Serial number */
'S', 0, 'T', 0, 'M', 0, '3', 0, '2', 0, '1', 0, '0', 0
};
#ifdef USE_STM3210B_EVAL
uint8_t DFU_StringInterface0[DFU_SIZ_STRING_INTERFACE0] =
{
DFU_SIZ_STRING_INTERFACE0,
0x03,
// Interface 0: "@Internal Flash /0x08000000/12*001Ka,116*001Kg"
'@', 0, 'I', 0, 'n', 0, 't', 0, 'e', 0, 'r', 0, 'n', 0, 'a', 0, 'l', 0, /* 18 */
' ', 0, 'F', 0, 'l', 0, 'a', 0, 's', 0, 'h', 0, ' ', 0, ' ', 0, /* 16 */
'/', 0, '0', 0, 'x', 0, '0', 0, '8', 0, '0', 0, '0', 0, '0', 0, '0', 0, '0', 0, '0', 0, /* 22 */
'/', 0, '1', 0, '2', 0, '*', 0, '0', 0, '0', 0, '1', 0, 'K', 0, 'a', 0, /* 18 */
',', 0, '1', 0, '1', 0, '6', 0, '*', 0, '0', 0, '0', 0, '1', 0, 'K', 0, 'g', 0, /* 20 */
};
#elif defined (USE_STM3210C_EVAL)
uint8_t DFU_StringInterface0[DFU_SIZ_STRING_INTERFACE0] =
{
DFU_SIZ_STRING_INTERFACE0,
0x03,
// Interface 0: "@Internal Flash /0x08000000/06*002Ka,122*002Kg"
'@', 0, 'I', 0, 'n', 0, 't', 0, 'e', 0, 'r', 0, 'n', 0, 'a', 0, 'l', 0, /* 18 */
' ', 0, 'F', 0, 'l', 0, 'a', 0, 's', 0, 'h', 0, ' ', 0, ' ', 0, /* 16 */
'/', 0, '0', 0, 'x', 0, '0', 0, '8', 0, '0', 0, '0', 0, '0', 0, '0', 0, '0', 0, '0', 0, /* 22 */
'/', 0, '0', 0, '6', 0, '*', 0, '0', 0, '0', 0, '2', 0, 'K', 0, 'a', 0, /* 18 */
',', 0, '1', 0, '2', 0, '2', 0, '*', 0, '0', 0, '0', 0, '2', 0, 'K', 0, 'g', 0, /* 20 */
};
#elif defined (USE_STM3210E_EVAL)
#ifdef STM32F10X_XL
uint8_t DFU_StringInterface0[DFU_SIZ_STRING_INTERFACE0] =
{
DFU_SIZ_STRING_INTERFACE0,
0x03,
// Interface 0: "@Internal Flash /0x08000000/06*002Ka,506*002Kg"
'@', 0, 'I', 0, 'n', 0, 't', 0, 'e', 0, 'r', 0, 'n', 0, 'a', 0, 'l', 0, /* 18 */
' ', 0, 'F', 0, 'l', 0, 'a', 0, 's', 0, 'h', 0, ' ', 0, ' ', 0, /* 16 */
'/', 0, '0', 0, 'x', 0, '0', 0, '8', 0, '0', 0, '0', 0, '0', 0, '0', 0, '0', 0, '0', 0, /* 22 */
'/', 0, '0', 0, '6', 0, '*', 0, '0', 0, '0', 0, '2', 0, 'K', 0, 'a', 0, /* 18 */
',', 0, '5', 0, '0', 0, '6', 0, '*', 0, '0', 0, '0', 0, '2', 0, 'K', 0, 'g', 0, /* 20 */
};
#else
uint8_t DFU_StringInterface0[DFU_SIZ_STRING_INTERFACE0] =
{
DFU_SIZ_STRING_INTERFACE0,
0x03,
// Interface 0: "@Internal Flash /0x08000000/06*002Ka,250*002Kg"
'@', 0, 'I', 0, 'n', 0, 't', 0, 'e', 0, 'r', 0, 'n', 0, 'a', 0, 'l', 0, /* 18 */
' ', 0, 'F', 0, 'l', 0, 'a', 0, 's', 0, 'h', 0, ' ', 0, ' ', 0, /* 16 */
'/', 0, '0', 0, 'x', 0, '0', 0, '8', 0, '0', 0, '0', 0, '0', 0, '0', 0, '0', 0, '0', 0, /* 22 */
'/', 0, '0', 0, '6', 0, '*', 0, '0', 0, '0', 0, '2', 0, 'K', 0, 'a', 0, /* 18 */
',', 0, '2', 0, '5', 0, '0', 0, '*', 0, '0', 0, '0', 0, '2', 0, 'K', 0, 'g', 0, /* 20 */
};
#endif /* STM32F10X_XL */
#endif /* USE_STM3210B_EVAL */
#if defined(USE_STM3210B_EVAL) || defined(USE_STM3210E_EVAL)
uint8_t DFU_StringInterface1[DFU_SIZ_STRING_INTERFACE1] =
{
DFU_SIZ_STRING_INTERFACE1,
0x03,
// Interface 1: "@ SPI Flash: M25P64 /0x00000000/128*064Kg"
'@', 0, 'S', 0, 'P', 0, 'I', 0, ' ', 0, 'F', 0, 'l', 0, 'a', 0, 's', 0,
'h', 0, ' ', 0, ':', 0, ' ', 0, 'M', 0, '2', 0, '5', 0, 'P', 0, '6', 0, '4', 0,
'/', 0, '0', 0, 'x', 0, '0', 0, '0', 0, '0', 0, '0', 0, '0', 0, '0', 0, '0', 0, '0', 0,
'/', 0, '1', 0, '2', 0, '8', 0, '*', 0, '6', 0, '4', 0, 'K', 0, 'g', 0
};
#endif /* USE_STM3210B_EVAL or USE_STM3210E_EVAL */
#ifdef USE_STM3210E_EVAL
uint8_t DFU_StringInterface2_1[DFU_SIZ_STRING_INTERFACE2] =
{
DFU_SIZ_STRING_INTERFACE2,
0x03,
// Interface 1: "@ NOR Flash: M29W128 /0x64000000/256*064Kg"
'@', 0, 'N', 0, 'O', 0, 'R', 0, ' ', 0, 'F', 0, 'l', 0, 'a', 0, 's', 0,
'h', 0, ' ', 0, ':', 0, ' ', 0, 'M', 0, '2', 0, '9', 0, 'W', 0, '1', 0, '2', 0, '8', 0, 'F', 0,
'/', 0, '0', 0, 'x', 0, '6', 0, '4', 0, '0', 0, '0', 0, '0', 0, '0', 0, '0', 0, '0', 0,
'/', 0, '0', 0, '2', 0, '5', 0, '6', 0, '*', 0, '6', 0, '4', 0, 'K', 0, 'g', 0
};
uint8_t DFU_StringInterface2_2[DFU_SIZ_STRING_INTERFACE2] =
{
DFU_SIZ_STRING_INTERFACE2,
0x03,
// Interface 1: "@ NOR Flash: M29W128 /0x64000000/128*128Kg"
'@', 0, 'N', 0, 'O', 0, 'R', 0, ' ', 0, 'F', 0, 'l', 0, 'a', 0, 's', 0,
'h', 0, ' ', 0, ':', 0, ' ', 0, 'M', 0, '2', 0, '9', 0, 'W', 0, '1', 0, '2', 0, '8', 0, 'G', 0,
'/', 0, '0', 0, 'x', 0, '6', 0, '4', 0, '0', 0, '0', 0, '0', 0, '0', 0, '0', 0, '0', 0,
'/', 0, '1', 0, '2', 0, '8', 0, '*', 0, '1', 0, '2', 0, '8', 0, 'K', 0, 'g', 0
};
uint8_t DFU_StringInterface2_3[DFU_SIZ_STRING_INTERFACE2] =
{
DFU_SIZ_STRING_INTERFACE2,
0x03,
// Interface 1: "@ NOR Flash:S29GL128 /0x64000000/128*128Kg"
'@', 0, 'N', 0, 'O', 0, 'R', 0, ' ', 0, 'F', 0, 'l', 0, 'a', 0, 's', 0,
'h', 0, ' ', 0, ':', 0, ' ', 0, 'S', 0, '2', 0, '9', 0, 'G', 0, 'L', 0 , '1', 0, '2', 0, '8', 0,
'/', 0, '0', 0, 'x', 0, '6', 0, '4', 0, '0', 0, '0', 0, '0', 0, '0', 0, '0', 0, '0', 0,
'/', 0, '1', 0, '2', 0, '8', 0, '*', 0, '1', 0, '2', 0, '8', 0, 'K', 0, 'g', 0
};
#endif /* USE_STM3210E_EVAL */
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -1,738 +0,0 @@
/******************** (C) COPYRIGHT 2010 STMicroelectronics ********************
* File Name : usb_prop.c
* Author : MCD Application Team
* Version : V3.2.1
* Date : 07/05/2010
* Description : All processings related to DFU demo
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Includes ------------------------------------------------------------------*/
#include "spi_flash.h"
#include "usb_lib.h"
#include "hw_config.h"
#include "usb_conf.h"
#include "usb_prop.h"
#include "usb_desc.h"
#include "usb_pwr.h"
#include "dfu_mal.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
uint32_t wBlockNum = 0, wlength = 0;
uint32_t Manifest_State = Manifest_complete;
uint32_t Pointer = ApplicationAddress; /* Base Address to Erase, Program or Read */
DEVICE Device_Table =
{
EP_NUM,
1
};
DEVICE_PROP Device_Property =
{
DFU_init,
DFU_Reset,
DFU_Status_In,
DFU_Status_Out,
DFU_Data_Setup,
DFU_NoData_Setup,
DFU_Get_Interface_Setting,
DFU_GetDeviceDescriptor,
DFU_GetConfigDescriptor,
DFU_GetStringDescriptor,
0, /*DFU_EP0Buffer*/
bMaxPacketSize0 /*Max Packet size*/
};
USER_STANDARD_REQUESTS User_Standard_Requests =
{
DFU_GetConfiguration,
DFU_SetConfiguration,
DFU_GetInterface,
DFU_SetInterface,
DFU_GetStatus,
DFU_ClearFeature,
DFU_SetEndPointFeature,
DFU_SetDeviceFeature,
DFU_SetDeviceAddress
};
ONE_DESCRIPTOR Device_Descriptor =
{
(uint8_t*)DFU_DeviceDescriptor,
DFU_SIZ_DEVICE_DESC
};
ONE_DESCRIPTOR Config_Descriptor =
{
(uint8_t*)DFU_ConfigDescriptor,
DFU_SIZ_CONFIG_DESC
};
#ifdef USE_STM3210E_EVAL
ONE_DESCRIPTOR DFU_String_Descriptor[7] =
#elif defined(USE_STM3210B_EVAL)
ONE_DESCRIPTOR DFU_String_Descriptor[6] =
#elif defined(USE_STM3210C_EVAL)
ONE_DESCRIPTOR DFU_String_Descriptor[5] =
#endif /* USE_STM3210E_EVAL */
{
{ (u8*)DFU_StringLangId, DFU_SIZ_STRING_LANGID },
{ (u8*)DFU_StringVendor, DFU_SIZ_STRING_VENDOR },
{ (u8*)DFU_StringProduct, DFU_SIZ_STRING_PRODUCT },
{ (u8*)DFU_StringSerial, DFU_SIZ_STRING_SERIAL },
{ (u8*)DFU_StringInterface0, DFU_SIZ_STRING_INTERFACE0 }
#ifdef USE_STM3210B_EVAL
,
{ (u8*)DFU_StringInterface1, DFU_SIZ_STRING_INTERFACE1 }
#endif /* USE_STM3210B_EVAL */
#ifdef USE_STM3210E_EVAL
,
{ (u8*)DFU_StringInterface1, DFU_SIZ_STRING_INTERFACE1 },
{ (u8*)DFU_StringInterface2_1, DFU_SIZ_STRING_INTERFACE2 }
#endif /* USE_STM3210E_EVAL */
};
/* Extern variables ----------------------------------------------------------*/
extern uint8_t DeviceState ;
extern uint8_t DeviceStatus[6];
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
* Function Name : DFU_init.
* Description : DFU init routine.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void DFU_init(void)
{
DEVICE_INFO *pInfo = &Device_Info;
/* Update the serial number string descriptor with the data from the unique ID*/
Get_SerialNum();
pInfo->Current_Configuration = 0;
/* Connect the device */
PowerOn();
/* Perform basic device initialization operations */
USB_SIL_Init();
/* Enable USB interrupts */
USB_Interrupts_Config();
bDeviceState = UNCONNECTED;
}
/*******************************************************************************
* Function Name : DFU_Reset.
* Description : DFU reset routine
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void DFU_Reset(void)
{
/* Set DFU_DEVICE as not configured */
Device_Info.Current_Configuration = 0;
/* Current Feature initialization */
pInformation->Current_Feature = DFU_ConfigDescriptor[7];
#ifdef STM32F10X_CL
/* EP0 is already configured in DFU_Init by OTG_DEV_Init() function
No Other endpoints needed for this firmware */
#else
_SetBTABLE(BTABLE_ADDRESS);
/* Initialize Endpoint 0 */
_SetEPType(ENDP0, EP_CONTROL);
_SetEPTxStatus(ENDP0, EP_TX_NAK);
_SetEPRxAddr(ENDP0, ENDP0_RXADDR);
SetEPRxCount(ENDP0, Device_Property.MaxPacketSize);
_SetEPTxAddr(ENDP0, ENDP0_TXADDR);
SetEPTxCount(ENDP0, Device_Property.MaxPacketSize);
Clear_Status_Out(ENDP0);
SetEPRxValid(ENDP0);
/* Set this device to response on default address */
SetDeviceAddress(0);
#endif /* STM32F10X_CL */
/* Set the new control state of the device to Attached */
bDeviceState = ATTACHED;
}
/*******************************************************************************
* Function Name : DFU_SetConfiguration.
* Description : Udpade the device state to configured.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void DFU_SetConfiguration(void)
{
DEVICE_INFO *pInfo = &Device_Info;
if (pInfo->Current_Configuration != 0)
{
/* Device configured */
bDeviceState = CONFIGURED;
}
}
/*******************************************************************************
* Function Name : DFU_SetConfiguration.
* Description : Udpade the device state to addressed.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void DFU_SetDeviceAddress (void)
{
bDeviceState = ADDRESSED;
}
/*******************************************************************************
* Function Name : DFU_Status_In.
* Description : DFU status IN routine.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void DFU_Status_In(void)
{}
/*******************************************************************************
* Function Name : DFU_Status_Out.
* Description : DFU status OUT routine.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void DFU_Status_Out (void)
{
DEVICE_INFO *pInfo = &Device_Info;
uint32_t Addr;
if (pInfo->USBbRequest == DFU_GETSTATUS)
{
if (DeviceState == STATE_dfuDNBUSY)
{
if (wBlockNum == 0) /* Decode the Special Command*/
{
if ((MAL_Buffer[0] == CMD_GETCOMMANDS) && (wlength == 1))
{}
else if (( MAL_Buffer[0] == CMD_SETADDRESSPOINTER ) && (wlength == 5))
{
Pointer = MAL_Buffer[1];
Pointer += MAL_Buffer[2] << 8;
Pointer += MAL_Buffer[3] << 16;
Pointer += MAL_Buffer[4] << 24;
}
else if (( MAL_Buffer[0] == CMD_ERASE ) && (wlength == 5))
{
Pointer = MAL_Buffer[1];
Pointer += MAL_Buffer[2] << 8;
Pointer += MAL_Buffer[3] << 16;
Pointer += MAL_Buffer[4] << 24;
MAL_Erase(Pointer);
}
}
else if (wBlockNum > 1) // Download Command
{
Addr = ((wBlockNum - 2) * wTransferSize) + Pointer;
MAL_Write(Addr, wlength);
}
wlength = 0;
wBlockNum = 0;
DeviceState = STATE_dfuDNLOAD_SYNC;
DeviceStatus[4] = DeviceState;
DeviceStatus[1] = 0;
DeviceStatus[2] = 0;
DeviceStatus[3] = 0;
return;
}
else if (DeviceState == STATE_dfuMANIFEST)/* Manifestation in progress*/
{
DFU_write_crc();
return;
}
}
return;
}
/*******************************************************************************
* Function Name : DFU_Data_Setup.
* Description : Handle the data class specific requests.
* Input : RequestNb.
* Output : None.
* Return : USB_SUCCESS or USB_UNSUPPORT.
*******************************************************************************/
RESULT DFU_Data_Setup(uint8_t RequestNo)
{
uint8_t *(*CopyRoutine)(uint16_t);
CopyRoutine = NULL;
if (Type_Recipient == (CLASS_REQUEST | INTERFACE_RECIPIENT))
{
if (RequestNo == DFU_UPLOAD && (DeviceState == STATE_dfuIDLE
|| DeviceState == STATE_dfuUPLOAD_IDLE ))
{
CopyRoutine = UPLOAD;
}
else if (RequestNo == DFU_DNLOAD && (DeviceState == STATE_dfuIDLE
|| DeviceState == STATE_dfuDNLOAD_IDLE))
{
DeviceState = STATE_dfuDNLOAD_SYNC;
CopyRoutine = DNLOAD;
}
else if (RequestNo == DFU_GETSTATE)
{
CopyRoutine = GETSTATE;
}
else if (RequestNo == DFU_GETSTATUS)
{
CopyRoutine = GETSTATUS;
}
else
{
return USB_UNSUPPORT;
}
}
else
{
return USB_UNSUPPORT;
}
if (CopyRoutine == NULL)
{
return USB_UNSUPPORT;
}
pInformation->Ctrl_Info.CopyData = CopyRoutine;
pInformation->Ctrl_Info.Usb_wOffset = 0;
(*CopyRoutine)(0);
return USB_SUCCESS;
}
/*******************************************************************************
* Function Name : DFU_NoData_Setup.
* Description : Handle the No data class specific requests.
* Input : Request Nb.
* Output : None.
* Return : USB_SUCCESS or USB_UNSUPPORT.
*******************************************************************************/
RESULT DFU_NoData_Setup(uint8_t RequestNo)
{
if (Type_Recipient == (CLASS_REQUEST | INTERFACE_RECIPIENT))
{
/*DFU_NDLOAD*/
if (RequestNo == DFU_DNLOAD)
{
/* End of DNLOAD operation*/
if (DeviceState == STATE_dfuDNLOAD_IDLE || DeviceState == STATE_dfuIDLE )
{
Manifest_State = Manifest_In_Progress;
DeviceState = STATE_dfuMANIFEST_SYNC;
DeviceStatus[1] = 0;
DeviceStatus[2] = 0;
DeviceStatus[3] = 0;
DeviceStatus[4] = DeviceState;
return USB_SUCCESS;
}
}
/*DFU_UPLOAD*/
else if (RequestNo == DFU_UPLOAD)
{
DeviceState = STATE_dfuIDLE;
DeviceStatus[1] = 0;
DeviceStatus[2] = 0;
DeviceStatus[3] = 0;
DeviceStatus[4] = DeviceState;
return USB_SUCCESS;
}
/*DFU_CLRSTATUS*/
else if (RequestNo == DFU_CLRSTATUS)
{
if (DeviceState == STATE_dfuERROR)
{
DeviceState = STATE_dfuIDLE;
DeviceStatus[0] = STATUS_OK;/*bStatus*/
DeviceStatus[1] = 0;
DeviceStatus[2] = 0;
DeviceStatus[3] = 0; /*bwPollTimeout=0ms*/
DeviceStatus[4] = DeviceState;/*bState*/
DeviceStatus[5] = 0;/*iString*/
}
else
{ /*State Error*/
DeviceState = STATE_dfuERROR;
DeviceStatus[0] = STATUS_ERRUNKNOWN;/*bStatus*/
DeviceStatus[1] = 0;
DeviceStatus[2] = 0;
DeviceStatus[3] = 0; /*bwPollTimeout=0ms*/
DeviceStatus[4] = DeviceState;/*bState*/
DeviceStatus[5] = 0;/*iString*/
}
return USB_SUCCESS;
}
/*DFU_ABORT*/
else if (RequestNo == DFU_ABORT)
{
if (DeviceState == STATE_dfuIDLE || DeviceState == STATE_dfuDNLOAD_SYNC
|| DeviceState == STATE_dfuDNLOAD_IDLE || DeviceState == STATE_dfuMANIFEST_SYNC
|| DeviceState == STATE_dfuUPLOAD_IDLE )
{
DeviceState = STATE_dfuIDLE;
DeviceStatus[0] = STATUS_OK;
DeviceStatus[1] = 0;
DeviceStatus[2] = 0;
DeviceStatus[3] = 0; /*bwPollTimeout=0ms*/
DeviceStatus[4] = DeviceState;
DeviceStatus[5] = 0; /*iString*/
wBlockNum = 0;
wlength = 0;
}
return USB_SUCCESS;
}
}
return USB_UNSUPPORT;
} /* End of DFU_NoData_Setup */
/*******************************************************************************
* Function Name : DFU_GetDeviceDescriptor.
* Description : Gets the device descriptor.
* Input : Length.
* Output : None.
* Return : The address of the device descriptor.
*******************************************************************************/
uint8_t *DFU_GetDeviceDescriptor(uint16_t Length)
{
return Standard_GetDescriptorData(Length, &Device_Descriptor);
}
/*******************************************************************************
* Function Name : DFU_GetConfigDescriptor.
* Description : Gets the configuration descriptor.
* Input : Length.
* Output : None.
* Return : The address of the configuration discriptor.
*******************************************************************************/
uint8_t *DFU_GetConfigDescriptor(uint16_t Length)
{
return Standard_GetDescriptorData (Length, &Config_Descriptor);
}
/*******************************************************************************
* Function Name : DFU_GetStringDescriptor.
* Description : Gets the string descriptors according to the needed index.
* Input : Length.
* Output : None.
* Return : The address of the string descriptors.
*******************************************************************************/
uint8_t *DFU_GetStringDescriptor(uint16_t Length)
{
uint8_t wValue0 = pInformation->USBwValue0;
if (wValue0 > 8)
{
return NULL;
}
else
{
return Standard_GetDescriptorData(Length, &DFU_String_Descriptor[wValue0]);
}
}
/*******************************************************************************
* Function Name : DFU_Get_Interface_Setting.
* Description : tests the interface and the alternate setting according to the
* supported one.
* Input : - Interface : interface number.
* - AlternateSetting : Alternate Setting number.
* Output : None.
* Return : USB_SUCCESS or USB_UNSUPPORT.
*******************************************************************************/
RESULT DFU_Get_Interface_Setting(uint8_t Interface, uint8_t AlternateSetting)
{
if (AlternateSetting > 3)
{
return USB_UNSUPPORT; /* In this application we don't have more than 3 AlternateSettings */
}
else if (Interface > 2)
{
return USB_UNSUPPORT; /* In this application we have only 1 interfaces */
}
return USB_SUCCESS;
}
/*******************************************************************************
* Function Name : UPLOAD
* Description : Upload routine.
* Input : Length.
* Output : None.
* Return : Pointer to data.
*******************************************************************************/
uint8_t *UPLOAD(uint16_t Length)
{
DEVICE_INFO *pInfo = &Device_Info;
uint8_t B1, B0;
uint16_t offset, returned;
uint8_t *Phy_Addr = NULL;
uint32_t Addr = 0;
B0 = pInfo->USBwValues.bw.bb0;
B1 = pInfo->USBwValues.bw.bb1;
wBlockNum = (uint16_t)B1;
wBlockNum = wBlockNum * 0x100;
wBlockNum += (uint16_t)B0; /* wBlockNum value updated*/
B0 = pInfo->USBwLengths.bw.bb0;
B1 = pInfo->USBwLengths.bw.bb1;
wlength = (uint16_t)B0;
wlength = wlength * 0x100;
wlength += (uint16_t)B1; /* wlength value updated*/
offset = pInformation->Ctrl_Info.Usb_wOffset;
if (wBlockNum == 0) /* Get Command */
{
if (wlength > 3)
{
DeviceState = STATE_dfuIDLE ;
}
else
{
DeviceState = STATE_dfuUPLOAD_IDLE;
}
DeviceStatus[4] = DeviceState;
DeviceStatus[1] = 0;
DeviceStatus[2] = 0;
DeviceStatus[3] = 0;
MAL_Buffer[0] = CMD_GETCOMMANDS;
MAL_Buffer[1] = CMD_SETADDRESSPOINTER;
MAL_Buffer[2] = CMD_ERASE;
if (Length == 0)
{
pInformation->Ctrl_Info.Usb_wLength = 3 ;
return NULL;
}
return(&MAL_Buffer[0]);
}
else if (wBlockNum > 1)
{
DeviceState = STATE_dfuUPLOAD_IDLE ;
DeviceStatus[4] = DeviceState;
DeviceStatus[1] = 0;
DeviceStatus[2] = 0;
DeviceStatus[3] = 0;
Addr = ((wBlockNum - 2) * wTransferSize) + Pointer; /* Change is Accelerated*/
Phy_Addr = MAL_Read(Addr, wlength);
returned = wlength - offset;
if (Length == 0)
{
pInformation->Ctrl_Info.Usb_wLength = returned ;
return NULL;
}
return(Phy_Addr + offset);
}
else /* unsupported wBlockNum */
{
DeviceState = STATUS_ERRSTALLEDPKT;
DeviceStatus[4] = DeviceState;
DeviceStatus[1] = 0;
DeviceStatus[2] = 0;
DeviceStatus[3] = 0;
return NULL;
}
}
/*******************************************************************************
* Function Name : DNLOAD
* Description : Download routine.
* Input : Length.
* Output : None.
* Return : Pointer to data.
*******************************************************************************/
uint8_t *DNLOAD (uint16_t Length)
{
DEVICE_INFO *pInfo = &Device_Info;
uint8_t B1, B0;
uint16_t offset, returned;
B0 = pInfo->USBwValues.bw.bb0;
B1 = pInfo->USBwValues.bw.bb1;
wBlockNum = (uint16_t)B1;
wBlockNum = wBlockNum * 0x100;
wBlockNum += (uint16_t)B0;
B0 = pInfo->USBwLengths.bw.bb0;
B1 = pInfo->USBwLengths.bw.bb1;
wlength = (uint16_t)B0;
wlength = wlength * 0x100;
wlength += (uint16_t)B1;
offset = pInfo->Ctrl_Info.Usb_wOffset;
DeviceState = STATE_dfuDNLOAD_SYNC;
DeviceStatus[4] = DeviceState;
returned = wlength - offset;
if (Length == 0)
{
pInformation->Ctrl_Info.Usb_wLength = returned ;
return NULL;
}
return((uint8_t*)MAL_Buffer + offset);
}
/*******************************************************************************
* Function Name : GETSTATE.
* Description : Get State request routine.
* Input : Length.
* Output : None.
* Return : Pointer to data.
*******************************************************************************/
uint8_t *GETSTATE(uint16_t Length)
{
if (Length == 0)
{
pInformation->Ctrl_Info.Usb_wLength = 1 ;
return NULL;
}
else
return(&DeviceState);
}
/*******************************************************************************
* Function Name : GETSTATUS.
* Description : Get Status request routine.
* Input : Length.
* Output : None.
* Return : Pointer to data.
*******************************************************************************/
uint8_t *GETSTATUS(uint16_t Length)
{
switch (DeviceState)
{
case STATE_dfuDNLOAD_SYNC:
if (wlength != 0)
{
DeviceState = STATE_dfuDNBUSY;
DeviceStatus[4] = DeviceState;
if ((wBlockNum == 0) && (MAL_Buffer[0] == CMD_ERASE))
{
MAL_GetStatus(Pointer, 0, DeviceStatus);
}
else
{
MAL_GetStatus(Pointer, 1, DeviceStatus);
}
}
else /* (wlength==0)*/
{
DeviceState = STATE_dfuDNLOAD_IDLE;
DeviceStatus[4] = DeviceState;
DeviceStatus[1] = 0;
DeviceStatus[2] = 0;
DeviceStatus[3] = 0;
}
break;
case STATE_dfuMANIFEST_SYNC :
if (Manifest_State == Manifest_In_Progress)
{
DeviceState = STATE_dfuMANIFEST;
DeviceStatus[4] = DeviceState;
DeviceStatus[1] = 1; /*bwPollTimeout = 1ms*/
DeviceStatus[2] = 0;
DeviceStatus[3] = 0;
//break;
}
else if (Manifest_State == Manifest_complete && Config_Descriptor.Descriptor[20]
& 0x04)
{
DeviceState = STATE_dfuIDLE;
DeviceStatus[4] = DeviceState;
DeviceStatus[1] = 0;
DeviceStatus[2] = 0;
DeviceStatus[3] = 0;
//break;
}
break;
default :
break;
}
if (Length == 0)
{
pInformation->Ctrl_Info.Usb_wLength = 6 ;
return NULL;
}
else
return(&(DeviceStatus[0]));
}
/*******************************************************************************
* Function Name : DFU_write_crc.
* Description : DFU Write CRC routine.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void DFU_write_crc(void)
{
Manifest_State = Manifest_complete;
if (Config_Descriptor.Descriptor[20] & 0x04)
{
DeviceState = STATE_dfuMANIFEST_SYNC;
DeviceStatus[4] = DeviceState;
DeviceStatus[1] = 0;
DeviceStatus[2] = 0;
DeviceStatus[3] = 0;
return;
}
else
{
DeviceState = STATE_dfuMANIFEST_WAIT_RESET;
DeviceStatus[4] = DeviceState;
DeviceStatus[1] = 0;
DeviceStatus[2] = 0;
DeviceStatus[3] = 0;
Reset_Device();
return;
}
}
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/