1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-01-17 02:52:12 +01:00

OP-21/Flight Bootloader - Remove deprecated bootloaders

git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@1637 ebee16cc-31ac-478f-84a7-5cbb03baadba
This commit is contained in:
zedamota 2010-09-15 16:58:00 +00:00 committed by zedamota
parent c8ac6eb712
commit df88140f51
38 changed files with 0 additions and 6908 deletions

View File

@ -1,567 +0,0 @@
#####
# Project: OpenPilot HID Bootloader
#
#
# Makefile for OpenPilot project build the HID bootlader.
#
# The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2009.
#
#
# This program is free software; you can redistribute it and/or modify
# it under the terms of the GNU General Public License as published by
# the Free Software Foundation; either version 3 of the License, or
# (at your option) any later version.
#
# This program is distributed in the hope that it will be useful, but
# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
# for more details.
#
# You should have received a copy of the GNU General Public License along
# with this program; if not, write to the Free Software Foundation, Inc.,
# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
#####
# Set developer code and compile options
# Set to YES for debugging
DEBUG = NO
# Set to YES when using Code Sourcery toolchain
CODE_SOURCERY = YES
# Toolchain prefix (i.e arm-elf- -> arm-elf-gcc.exe)
TCHAIN_PREFIX = arm-none-eabi-
ifeq ($(CODE_SOURCERY), YES)
REMOVE_CMD = cs-rm
else
REMOVE_CMD = rm
endif
FLASH_TOOL = OPENOCD
# YES enables -mthumb option to flags for source-files listed
# in SRC and CPPSRC
USE_THUMB_MODE = YES
# MCU name, submodel and board
# - MCU used for compiler-option (-mcpu)
# - MODEL used for linker-script name (-T) and passed as define
# - BOARD just passed as define (optional)
MCU = cortex-m3
CHIP = STM32F103RET
MODEL = HD
BOARD = STM3210E_OP
# Directory for output files (lst, obj, dep, elf, sym, map, hex, bin etc.)
OUTDIR = Build
# Target file name (without extension).
TARGET = OpenPilot_BL
# Paths
OPBLSYSTEM = ./
OPBLSYSTEMINC = $(OPBLSYSTEM)/inc
PIOS = ../../PiOS
PIOSINC = $(PIOS)/inc
PIOSSTM32F10X = $(PIOS)/STM32F10x
PIOSCOMMON = $(PIOS)/Common
APPLIBDIR = $(PIOSSTM32F10X)/Libraries
STMLIBDIR = $(APPLIBDIR)
STMSPDDIR = $(STMLIBDIR)/STM32F10x_StdPeriph_Driver
STMUSBDIR = $(STMLIBDIR)/STM32_USB-FS-Device_Driver
STMSPDSRCDIR = $(STMSPDDIR)/src
STMSPDINCDIR = $(STMSPDDIR)/inc
STMUSBSRCDIR = $(STMUSBDIR)/src
STMUSBINCDIR = $(STMUSBDIR)/inc
CMSISDIR = $(STMLIBDIR)/CMSIS/Core/CM3
DOXYGENDIR = .../Doc/Doxygen
# List C source files here. (C dependencies are automatically generated.)
# use file-extension c for "c-only"-files
## OPENPILOT Bootloader:
SRC = $(OPBLSYSTEM)/openpilot_bl.c
SRC += $(OPBLSYSTEM)/bootloader.c
SRC += $(OPBLSYSTEM)/ymodem.c
## PIOS Hardware (STM32F10x)
SRC += $(PIOSSTM32F10X)/pios_sys.c
SRC += $(PIOSSTM32F10X)/pios_led.c
SRC += $(PIOSSTM32F10X)/pios_usart.c
SRC += $(PIOSSTM32F10X)/pios_delay.c
SRC += $(PIOSSTM32F10X)/pios_irq.c
SRC += $(PIOSSTM32F10X)/pios_usb.c
SRC += $(PIOSSTM32F10X)/pios_usb_hid.c
## PIOS Hardware (Common)
SRC += $(PIOSCOMMON)/pios_com.c
SRC += $(PIOSCOMMON)/printf-stdarg.c
## CMSIS for STM32
SRC += $(CMSISDIR)/core_cm3.c
SRC += $(CMSISDIR)/system_stm32f10x.c
## Used parts of the STM-Library
SRC += $(STMSPDSRCDIR)/stm32f10x_gpio.c
SRC += $(STMSPDSRCDIR)/stm32f10x_rcc.c
SRC += $(STMSPDSRCDIR)/stm32f10x_wwdg.c
SRC += $(STMSPDSRCDIR)/stm32f10x_tim.c
SRC += $(STMSPDSRCDIR)/stm32f10x_flash.c
SRC += $(STMSPDSRCDIR)/stm32f10x_usart.c
SRC += $(STMSPDSRCDIR)/misc.c
## STM32 USB Library
SRC += $(STMUSBSRCDIR)/usb_core.c
SRC += $(STMUSBSRCDIR)/usb_init.c
SRC += $(STMUSBSRCDIR)/usb_int.c
SRC += $(STMUSBSRCDIR)/usb_mem.c
SRC += $(STMUSBSRCDIR)/usb_regs.c
# List C source files here which must be compiled in ARM-Mode (no -mthumb).
# use file-extension c for "c-only"-files
## just for testing, timer.c could be compiled in thumb-mode too
SRCARM =
# List C++ source files here.
# use file-extension .cpp for C++-files (not .C)
CPPSRC =
# List C++ source files here which must be compiled in ARM-Mode.
# use file-extension .cpp for C++-files (not .C)
#CPPSRCARM = $(TARGET).cpp
CPPSRCARM =
# List Assembler source files here.
# Make them always end in a capital .S. Files ending in a lowercase .s
# will not be considered source files but generated files (assembler
# output from the compiler), and will be deleted upon "make clean"!
# Even though the DOS/Win* filesystem matches both .s and .S the same,
# it will preserve the spelling of the filenames, and gcc itself does
# care about how the name is spelled on its command-line.
ASRC = $(PIOSSTM32F10X)/startup_stm32f10x_$(MODEL).S
# List Assembler source files here which must be assembled in ARM-Mode..
ASRCARM =
# List any extra directories to look for include files here.
# Each directory must be seperated by a space.
EXTRAINCDIRS = $(OPBLSYSTEM)
EXTRAINCDIRS += $(OPBLSYSTEMINC)
EXTRAINCDIRS += $(PIOS)
EXTRAINCDIRS += $(PIOSINC)
EXTRAINCDIRS += $(PIOSSTM32F10X)
EXTRAINCDIRS += $(PIOSCOMMON)
EXTRAINCDIRS += $(STMSPDINCDIR)
EXTRAINCDIRS += $(STMUSBINCDIR)
EXTRAINCDIRS += $(CMSISDIR)
EXTRAINCDIRS += $(APPLIBDIR)
# List any extra directories to look for library files here.
# Also add directories where the linker should search for
# includes from linker-script to the list
# Each directory must be seperated by a space.
EXTRA_LIBDIRS =
# Extra Libraries
# Each library-name must be seperated by a space.
# i.e. to link with libxyz.a, libabc.a and libefsl.a:
# EXTRA_LIBS = xyz abc efsl
# for newlib-lpc (file: libnewlibc-lpc.a):
# EXTRA_LIBS = newlib-lpc
EXTRA_LIBS =
# Path to Linker-Scripts
LINKERSCRIPTPATH = $(PIOSSTM32F10X)
# Optimization level, can be [0, 1, 2, 3, s].
# 0 = turn off optimization. s = optimize for size.
# (Note: 3 is not always the best optimization level. See avr-libc FAQ.)
ifeq ($(DEBUG),YES)
OPT = 0
else
OPT = s
endif
# Output format. (can be ihex or binary or both)
# binary to create a load-image in raw-binary format i.e. for SAM-BA,
# ihex to create a load-image in Intel hex format
#LOADFORMAT = ihex
#LOADFORMAT = binary
LOADFORMAT = both
# Debugging format.
DEBUGF = dwarf-2
# Place project-specific -D (define) and/or
# -U options for C here.
CDEFS = -DSTM32F10X_$(MODEL)
CDEFS += -DUSE_STDPERIPH_DRIVER
CDEFS += -DUSE_$(BOARD)
# Place project-specific -D and/or -U options for
# Assembler with preprocessor here.
#ADEFS = -DUSE_IRQ_ASM_WRAPPER
ADEFS = -D__ASSEMBLY__
# Compiler flag to set the C Standard level.
# c89 - "ANSI" C
# gnu89 - c89 plus GCC extensions
# c99 - ISO C99 standard (not yet fully implemented)
# gnu99 - c99 plus GCC extensions
CSTANDARD = -std=gnu99
#-----
# Compiler flags.
# -g*: generate debugging information
# -O*: optimization level
# -f...: tuning, see GCC manual and avr-libc documentation
# -Wall...: warning level
# -Wa,...: tell GCC to pass this to the assembler.
# -adhlns...: create assembler listing
#
# Flags for C and C++ (arm-elf-gcc/arm-elf-g++)
ifeq ($(DEBUG),YES)
CFLAGS = -g$(DEBUGF)
endif
CFLAGS += -O$(OPT)
CFLAGS += -mcpu=$(MCU) -mthumb
CFLAGS += $(CDEFS)
CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I.
CFLAGS += -mapcs-frame
CFLAGS += -fomit-frame-pointer
ifeq ($(CODE_SOURCERY), YES)
CFLAGS += -fpromote-loop-indices
endif
CFLAGS += -Wall
CFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<))))
# Compiler flags to generate dependency files:
CFLAGS += -MD -MP -MF $(OUTDIR)/dep/$(@F).d
# flags only for C
#CONLYFLAGS += -Wnested-externs
CONLYFLAGS += $(CSTANDARD)
# Assembler flags.
# -Wa,...: tell GCC to pass this to the assembler.
# -ahlns: create listing
ASFLAGS = -mcpu=$(MCU) -mthumb -I. -x assembler-with-cpp
ASFLAGS += $(ADEFS)
ASFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<))))
ASFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS))
MATH_LIB = -lm
# Linker flags.
# -Wl,...: tell GCC to pass this to linker.
# -Map: create map file
# --cref: add cross reference to map file
LDFLAGS = -nostartfiles -Wl,-Map=$(OUTDIR)/$(TARGET).map,--cref,--gc-sections
LDFLAGS += $(patsubst %,-L%,$(EXTRA_LIBDIRS))
LDFLAGS += -lc
LDFLAGS += $(patsubst %,-l%,$(EXTRA_LIBS))
LDFLAGS += $(MATH_LIB)
LDFLAGS += -lc -lgcc
# Set linker-script name depending on selected submodel name
LDFLAGS +=-T$(LINKERSCRIPTPATH)/link_stm32f10x_$(MODEL).ld
# ---------------------------------------------------------------------------
# Options for OpenOCD flash-programming
# see openocd.pdf/openocd.texi for further information
#
OOCD_LOADFILE+=$(OUTDIR)/$(TARGET).elf
# if OpenOCD is in the $PATH just set OPENOCDEXE=openocd
OOCD_EXE=openocd
# debug level
OOCD_CL=-d0
# interface and board/target settings (using the OOCD target-library here)
OOCD_CL+=-f ../../project/OpenOCD/floss-jtag.cfg -f ../../project/OpenOCD/stm32.cfg
# initialize
OOCD_CL+=-c init
# show the targets
OOCD_CL+=-c targets
# commands to prepare flash-write
OOCD_CL+= -c "reset halt"
# flash erase
OOCD_CL+=-c "stm32x mass_erase 0"
# flash-write
OOCD_CL+=-c "flash write_image $(OOCD_LOADFILE)"
# Verify
OOCD_CL+=-c "verify_image $(OOCD_LOADFILE)"
# reset target
OOCD_CL+=-c "reset run"
# terminate OOCD after programming
OOCD_CL+=-c shutdown
# ---------------------------------------------------------------------------
# Define programs and commands.
CC = $(TCHAIN_PREFIX)gcc
CPP = $(TCHAIN_PREFIX)g++
AR = $(TCHAIN_PREFIX)ar
OBJCOPY = $(TCHAIN_PREFIX)objcopy
OBJDUMP = $(TCHAIN_PREFIX)objdump
SIZE = $(TCHAIN_PREFIX)size
NM = $(TCHAIN_PREFIX)nm
REMOVE = $(REMOVE_CMD) -f
###SHELL = sh
###COPY = cp
# Define Messages
# English
MSG_ERRORS_NONE = Errors: none
MSG_BEGIN = "-------- begin (mode: $(RUN_MODE)) --------"
MSG_END = -------- end --------
MSG_SIZE_BEFORE = Size before:
MSG_SIZE_AFTER = Size after build:
MSG_LOAD_FILE = Creating load file:
MSG_EXTENDED_LISTING = Creating Extended Listing/Disassembly:
MSG_SYMBOL_TABLE = Creating Symbol Table:
MSG_LINKING = "**** Linking :"
MSG_COMPILING = "**** Compiling C :"
MSG_COMPILING_ARM = "**** Compiling C (ARM-only):"
MSG_COMPILINGCPP = "Compiling C++ :"
MSG_COMPILINGCPP_ARM = "Compiling C++ (ARM-only):"
MSG_ASSEMBLING = "**** Assembling:"
MSG_ASSEMBLING_ARM = "****Assembling (ARM-only):"
MSG_CLEANING = Cleaning project:
MSG_FORMATERROR = Can not handle output-format
MSG_ASMFROMC = "Creating asm-File from C-Source:"
MSG_ASMFROMC_ARM = "Creating asm-File from C-Source (ARM-only):"
# List of all source files.
ALLSRC = $(ASRCARM) $(ASRC) $(SRCARM) $(SRC) $(CPPSRCARM) $(CPPSRC)
# List of all source files without directory and file-extension.
ALLSRCBASE = $(notdir $(basename $(ALLSRC)))
# Define all object files.
ALLOBJ = $(addprefix $(OUTDIR)/, $(addsuffix .o, $(ALLSRCBASE)))
# Define all listing files (used for make clean).
LSTFILES = $(addprefix $(OUTDIR)/, $(addsuffix .lst, $(ALLSRCBASE)))
# Define all depedency-files (used for make clean).
DEPFILES = $(addprefix $(OUTDIR)/dep/, $(addsuffix .o.d, $(ALLSRCBASE)))
elf: $(OUTDIR)/$(TARGET).elf
lss: $(OUTDIR)/$(TARGET).lss
sym: $(OUTDIR)/$(TARGET).sym
hex: $(OUTDIR)/$(TARGET).hex
bin: $(OUTDIR)/$(TARGET).bin
# Default target.
#all: begin gccversion sizebefore build sizeafter finished end
all: begin gccversion build sizeafter finished end
ifeq ($(LOADFORMAT),ihex)
build: elf hex lss sym
else
ifeq ($(LOADFORMAT),binary)
build: elf bin lss sym
else
ifeq ($(LOADFORMAT),both)
build: elf hex bin lss sym
else
$(error "$(MSG_FORMATERROR) $(FORMAT)")
endif
endif
endif
# Eye candy.
begin:
## @echo
@echo $(MSG_BEGIN)
finished:
## @echo $(MSG_ERRORS_NONE)
end:
@echo $(MSG_END)
## @echo
# Display sizes of sections.
ELFSIZE = $(SIZE) -A $(OUTDIR)/$(TARGET).elf
##ELFSIZE = $(SIZE) --format=Berkeley --common $(OUTDIR)/$(TARGET).elf
sizebefore:
# @if [ -f $(OUTDIR)/$(TARGET).elf ]; then echo; echo $(MSG_SIZE_BEFORE); $(ELFSIZE); echo; fi
sizeafter:
# @if [ -f $(OUTDIR)/$(TARGET).elf ]; then echo; echo $(MSG_SIZE_AFTER); $(ELFSIZE); echo; fi
@echo $(MSG_SIZE_AFTER)
$(ELFSIZE)
# Display compiler version information.
gccversion :
@$(CC) --version
# @echo $(ALLOBJ)
# Program the device.
ifeq ($(FLASH_TOOL),OPENOCD)
# Program the device with Dominic Rath's OPENOCD in "batch-mode", needs cfg and "reset-script".
program: $(OUTDIR)/$(TARGET).elf
@echo "Programming with OPENOCD"
$(OOCD_EXE) $(OOCD_CL)
endif
# Create final output file (.hex) from ELF output file.
%.hex: %.elf
## @echo
@echo $(MSG_LOAD_FILE) $@
$(OBJCOPY) -O ihex $< $@
# Create final output file (.bin) from ELF output file.
%.bin: %.elf
## @echo
@echo $(MSG_LOAD_FILE) $@
$(OBJCOPY) -O binary $< $@
# Create extended listing file/disassambly from ELF output file.
# using objdump testing: option -C
%.lss: %.elf
## @echo
@echo $(MSG_EXTENDED_LISTING) $@
$(OBJDUMP) -h -S -C -r $< > $@
# $(OBJDUMP) -x -S $< > $@
# Create a symbol table from ELF output file.
%.sym: %.elf
## @echo
@echo $(MSG_SYMBOL_TABLE) $@
$(NM) -n $< > $@
# Link: create ELF output file from object files.
.SECONDARY : $(TARGET).elf
.PRECIOUS : $(ALLOBJ)
%.elf: $(ALLOBJ)
@echo
@echo $(MSG_LINKING) $@
# use $(CC) for C-only projects or $(CPP) for C++-projects:
$(CC) $(THUMB) $(CFLAGS) $(ALLOBJ) --output $@ $(LDFLAGS)
# $(CPP) $(THUMB) $(CFLAGS) $(ALLOBJ) --output $@ $(LDFLAGS)
# Assemble: create object files from assembler source files.
define ASSEMBLE_TEMPLATE
$(OUTDIR)/$(notdir $(basename $(1))).o : $(1)
## @echo
@echo $(MSG_ASSEMBLING) $$< "->" $$@
$(CC) -c $(THUMB) $$(ASFLAGS) $$< -o $$@
endef
$(foreach src, $(ASRC), $(eval $(call ASSEMBLE_TEMPLATE, $(src))))
# Assemble: create object files from assembler source files. ARM-only
define ASSEMBLE_ARM_TEMPLATE
$(OUTDIR)/$(notdir $(basename $(1))).o : $(1)
## @echo
@echo $(MSG_ASSEMBLING_ARM) $$< "->" $$@
$(CC) -c $$(ASFLAGS) $$< -o $$@
endef
$(foreach src, $(ASRCARM), $(eval $(call ASSEMBLE_ARM_TEMPLATE, $(src))))
# Compile: create object files from C source files.
define COMPILE_C_TEMPLATE
$(OUTDIR)/$(notdir $(basename $(1))).o : $(1)
## @echo
@echo $(MSG_COMPILING) $$< "->" $$@
$(CC) -c $(THUMB) $$(CFLAGS) $$(CONLYFLAGS) $$< -o $$@
endef
$(foreach src, $(SRC), $(eval $(call COMPILE_C_TEMPLATE, $(src))))
# Compile: create object files from C source files. ARM-only
define COMPILE_C_ARM_TEMPLATE
$(OUTDIR)/$(notdir $(basename $(1))).o : $(1)
## @echo
@echo $(MSG_COMPILING_ARM) $$< "->" $$@
$(CC) -c $$(CFLAGS) $$(CONLYFLAGS) $$< -o $$@
endef
$(foreach src, $(SRCARM), $(eval $(call COMPILE_C_ARM_TEMPLATE, $(src))))
# Compile: create object files from C++ source files.
define COMPILE_CPP_TEMPLATE
$(OUTDIR)/$(notdir $(basename $(1))).o : $(1)
## @echo
@echo $(MSG_COMPILINGCPP) $$< "->" $$@
$(CC) -c $(THUMB) $$(CFLAGS) $$(CPPFLAGS) $$< -o $$@
endef
$(foreach src, $(CPPSRC), $(eval $(call COMPILE_CPP_TEMPLATE, $(src))))
# Compile: create object files from C++ source files. ARM-only
define COMPILE_CPP_ARM_TEMPLATE
$(OUTDIR)/$(notdir $(basename $(1))).o : $(1)
## @echo
@echo $(MSG_COMPILINGCPP_ARM) $$< "->" $$@
$(CC) -c $$(CFLAGS) $$(CPPFLAGS) $$< -o $$@
endef
$(foreach src, $(CPPSRCARM), $(eval $(call COMPILE_CPP_ARM_TEMPLATE, $(src))))
# Compile: create assembler files from C source files. ARM/Thumb
$(SRC:.c=.s) : %.s : %.c
@echo $(MSG_ASMFROMC) $< to $@
$(CC) $(THUMB) -S $(CFLAGS) $(CONLYFLAGS) $< -o $@
# Compile: create assembler files from C source files. ARM only
$(SRCARM:.c=.s) : %.s : %.c
@echo $(MSG_ASMFROMC_ARM) $< to $@
$(CC) -S $(CFLAGS) $(CONLYFLAGS) $< -o $@
# Generate Doxygen documents
docs:
doxygen $(DOXYGENDIR)/doxygen.cfg
# Target: clean project.
clean: begin clean_list finished end
clean_list :
## @echo
@echo $(MSG_CLEANING)
$(REMOVE) $(OUTDIR)/$(TARGET).map
$(REMOVE) $(OUTDIR)/$(TARGET).elf
$(REMOVE) $(OUTDIR)/$(TARGET).hex
$(REMOVE) $(OUTDIR)/$(TARGET).bin
$(REMOVE) $(OUTDIR)/$(TARGET).sym
$(REMOVE) $(OUTDIR)/$(TARGET).lss
$(REMOVE) $(ALLOBJ)
$(REMOVE) $(LSTFILES)
$(REMOVE) $(DEPFILES)
$(REMOVE) $(SRC:.c=.s)
$(REMOVE) $(SRCARM:.c=.s)
$(REMOVE) $(CPPSRC:.cpp=.s)
$(REMOVE) $(CPPSRCARM:.cpp=.s)
# Create output files directory
# all known MS Windows OS define the ComSpec environment variable
ifdef ComSpec
$(shell md $(OUTDIR) 2>NUL)
else
$(shell mkdir $(OUTDIR) 2>/dev/null)
endif
# Include the dependency files.
ifdef ComSpec
-include $(shell md $(OUTDIR)\dep 2>NUL) $(wildcard $(OUTDIR)/dep/*)
else
-include $(shell mkdir $(OUTDIR) 2>/dev/null) $(shell mkdir $(OUTDIR)/dep 2>/dev/null) $(wildcard $(OUTDIR)/dep/*)
endif
# Listing of phony targets.
.PHONY : all begin finish end sizebefore sizeafter gccversion \
build elf hex bin lss sym clean clean_list program

View File

@ -1,209 +0,0 @@
/**
******************************************************************************
*
* @file bootloader.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief Bootloader functions header
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
/* Includes */
#include "openpilot_bl.h"
/* Local Functions */
static void Serial_PutString(uint8_t *s);
static void FLASH_DisableWriteProtectionPages(void);
static void SerialDownload(void);
/* Global Variables */
extern uint32_t FlashDestination;
extern uint8_t file_name[FILE_NAME_LENGTH];
/* Local variables */
static uint32_t UserMemoryMask = 0;
/**
* Main bootloader function
*/
void StartBootloader(void)
{
uint8_t key = 0;
uint32_t BlockNbr = 0;
bool FlashProtection = FALSE;
/* Get the number of block (4 or 2 pages) from where the user program will be loaded */
BlockNbr = (FlashDestination - 0x08000000) >> 12;
/* Compute the mask to test if the Flash memory, where the user program will be loaded, is write protected */
if(BlockNbr < 62) {
UserMemoryMask = ((uint32_t) ~((1 << BlockNbr) - 1));
} else {
UserMemoryMask = ((uint32_t) 0x80000000);
}
/* Test if any page of Flash memory where program user will be loaded is write protected */
if((FLASH_GetWriteProtectionOptionByte() & UserMemoryMask) != UserMemoryMask) {
FlashProtection = TRUE;
SerialPutString("Download Image To the STM32F10x Internal Flash ------- 1\r\n");
SerialPutString("Execute The New Program ------------------------------ 2\r\n");
SerialPutString("Disable the write protection ------------------------- 3\r\n");
} else {
FlashProtection = FALSE;
SerialPutString("Download Image To the STM32F10x Internal Flash ------- 1\r\n");
SerialPutString("Execute The New Program ------------------------------ 2\r\n");
}
/* Loop through 1mS check for specified time */
for(int32_t i = 0; i < OPBL_MAGIC_TIMEOUT; i++) {
uint16_t start = PIOS_DELAY_TIMER->CNT;
/* Check for magic character for 1mS */
while((volatile uint16_t)(PIOS_DELAY_TIMER->CNT - start) <= 1000) {
/* Check to see if there is anything on the receiving buffer */
if(PIOS_COM_ReceiveBufferUsed(OPBL_COM_PORT) > 0) {
key = PIOS_COM_ReceiveBuffer(OPBL_COM_PORT);
if(key == 0x31) {
/* Flash unlock */
FLASH_Unlock();
/* Download user application in the Flash */
SerialDownload();
return;
} else if ((key == 0x33) && (FlashProtection == TRUE)) {
/* Disable the write protection of desired pages */
FLASH_DisableWriteProtectionPages();
}
}
}
}
return;
}
/**
* Calculate the number of pages
* \param[in] Size The image size
* \return The number of pages
*/
uint32_t FLASH_PagesMask(__IO uint32_t Size)
{
uint32_t pagenumber = 0x0;
uint32_t size = Size;
if((size % PAGE_SIZE) != 0) {
pagenumber = (size / PAGE_SIZE) + 1;
} else {
pagenumber = size / PAGE_SIZE;
}
return pagenumber;
}
/**
* Print a string on the HyperTerminal
* \param[in] s The string to be printed
*/
static void Serial_PutString(uint8_t *s)
{
while(*s != '\0') {
PIOS_COM_SendChar(OPBL_COM_PORT, *s);
s++;
}
}
/**
* Disable the write protection of desired pages
*/
static void FLASH_DisableWriteProtectionPages(void)
{
uint32_t useroptionbyte = 0, WRPR = 0;
uint16_t var1 = OB_IWDG_SW, var2 = OB_STOP_NoRST, var3 = OB_STDBY_NoRST;
FLASH_Status status = FLASH_BUSY;
WRPR = FLASH_GetWriteProtectionOptionByte();
/* Test if user memory is write protected */
if((WRPR & UserMemoryMask) != UserMemoryMask) {
useroptionbyte = FLASH_GetUserOptionByte();
UserMemoryMask |= WRPR;
status = FLASH_EraseOptionBytes();
if(UserMemoryMask != 0xFFFFFFFF) {
status = FLASH_EnableWriteProtection(
(uint32_t) ~UserMemoryMask);
}
/* Test if user Option Bytes are programmed */
if((useroptionbyte & 0x07) != 0x07) { /* Restore user Option Bytes */
if((useroptionbyte & 0x01) == 0x0) {
var1 = OB_IWDG_HW;
}
if((useroptionbyte & 0x02) == 0x0) {
var2 = OB_STOP_RST;
}
if((useroptionbyte & 0x04) == 0x0) {
var3 = OB_STDBY_RST;
}
FLASH_UserOptionByteConfig(var1, var2, var3);
}
if(status == FLASH_COMPLETE) {
SerialPutString("Write Protection disabled...\r\n");
SerialPutString("...and a System Reset will be generated to re-load the new option bytes\r\n");
/* Enable WWDG clock */
RCC_APB1PeriphClockCmd(RCC_APB1Periph_WWDG, ENABLE);
/* Generate a system Reset to re-load the new option bytes: enable WWDG and set
counter value to 0x4F, as T6 bit is cleared this will generate a WWDG reset */
WWDG_Enable(0x4F);
} else {
SerialPutString("Error: Flash write unprotection failed...\r\n");
}
} else {
SerialPutString("Flash memory not write protected\r\n");
}
}
/**
* Download and program the binary file
*/
static void SerialDownload(void)
{
uint8_t tab_1024[1024] = { 0 };
int32_t Size = 0;
SerialPutString("Waiting for the file to be sent ... (press 'a' to abort)\n\r");
Size = Ymodem_Receive(&tab_1024[0]);
if(Size > 0) {
SerialPutString("\n\n\rProgramming Completed Successfully!\n\r");
} else if(Size == -1) {
SerialPutString("\n\n\rThe image size is higher than the allowed space memory!\n\r");
} else if(Size == -2) {
SerialPutString("\n\n\rVerification failed!\n\r");
} else if(Size == -3) {
SerialPutString("\r\n\nAborted by user.\n\r");
} else {
SerialPutString("\n\rFailed to receive the file!\n\r");
}
}

View File

@ -1,45 +0,0 @@
/**
******************************************************************************
*
* @file bootloader.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief Bootloader functions header
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef BOOTLOADER_H
#define BOOTLOADER_H
/* Global Types */
typedef void (*pFunction)(void);
/* Global Defines */
#define CMD_STRING_SIZE 128
#define ApplicationAddress (0x8006000)
#define PAGE_SIZE (0x800)
#define FLASH_SIZE (0x80000) /* 512K */
/* Global macros */
#define SerialPutString(x) Serial_PutString((uint8_t*)(x))
/* Public Functions */
extern void StartBootloader(void);
extern uint32_t FLASH_PagesMask(volatile uint32_t Size);
#endif /* BOOTLOADER_H */

View File

@ -1,38 +0,0 @@
/**
******************************************************************************
*
* @file openpilot_bl.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief Main OpenPilot Bootloader header.
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef OPENPILOT_BL_H
#define OPENPILOT_BL_H
#define OPBL_MAGIC_TIMEOUT 200
#define OPBL_COM_PORT COM_DEBUG_USART
/* PIOS Includes */
#include <pios.h>
#include "bootloader.h"
#include "ymodem.h"
#endif /* OPENPILOT_BL_H */

View File

@ -1,127 +0,0 @@
/**
******************************************************************************
*
* @file pios_board.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief Defines board hardware for the OpenPilot Version 1.1 hardware.
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef PIOS_BOARD_H
#define PIOS_BOARD_H
//------------------------
// PIOS_LED
//------------------------
#define PIOS_LED_LED1_GPIO_PORT GPIOC
#define PIOS_LED_LED1_GPIO_PIN GPIO_Pin_12
#define PIOS_LED_LED1_GPIO_CLK RCC_APB2Periph_GPIOC
#define PIOS_LED_LED2_GPIO_PORT GPIOC
#define PIOS_LED_LED2_GPIO_PIN GPIO_Pin_13
#define PIOS_LED_LED2_GPIO_CLK RCC_APB2Periph_GPIOC
#define PIOS_LED_NUM 2
#define PIOS_LED_PORTS { PIOS_LED_LED1_GPIO_PORT, PIOS_LED_LED2_GPIO_PORT }
#define PIOS_LED_PINS { PIOS_LED_LED1_GPIO_PIN, PIOS_LED_LED2_GPIO_PIN }
#define PIOS_LED_CLKS { PIOS_LED_LED1_GPIO_CLK, PIOS_LED_LED2_GPIO_CLK }
//-------------------------
// PIOS_USART1 (TELEM)
//-------------------------
#define PIOS_USART1_ENABLED 1
#define PIOS_USART1_USART USART2
#define PIOS_USART1_GPIO_PORT GPIOA
#define PIOS_USART1_RX_PIN GPIO_Pin_3
#define PIOS_USART1_TX_PIN GPIO_Pin_2
#define PIOS_USART1_REMAP_FUNC { }
#define PIOS_USART1_IRQ_CHANNEL USART2_IRQn
#define PIOS_USART1_IRQHANDLER_FUNC void USART2_IRQHandler(void)
#define PIOS_USART1_CLK_FUNC RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE)
#define PIOS_USART1_NVIC_PRIO PIOS_IRQ_PRIO_HIGHEST
#define PIOS_USART1_BAUDRATE 115200
//-------------------------
// PIOS_USART2 (GPS)
//-------------------------
#define PIOS_USART2_ENABLED 0
#define PIOS_USART2_USART USART3
#define PIOS_USART2_GPIO_PORT GPIOC
#define PIOS_USART2_RX_PIN GPIO_Pin_11
#define PIOS_USART2_TX_PIN GPIO_Pin_10
#define PIOS_USART2_REMAP_FUNC { GPIO_PinRemapConfig(GPIO_PartialRemap_USART3, ENABLE); }
#define PIOS_USART2_IRQ_CHANNEL USART3_IRQn
#define PIOS_USART2_IRQHANDLER_FUNC void USART3_IRQHandler(void)
#define PIOS_USART2_CLK_FUNC RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART3, ENABLE)
#define PIOS_USART2_NVIC_PRIO PIOS_IRQ_PRIO_HIGHEST
#define PIOS_USART2_BAUDRATE 57600
//-------------------------
// PIOS_USART3 (AUX) (RX5/RX6)
//-------------------------
#define PIOS_USART3_ENABLED 0
#define PIOS_USART3_USART USART1
#define PIOS_USART3_GPIO_PORT GPIOA
#define PIOS_USART3_RX_PIN GPIO_Pin_10
#define PIOS_USART3_TX_PIN GPIO_Pin_9
#define PIOS_USART3_REMAP_FUNC { }
#define PIOS_USART3_IRQ_CHANNEL USART1_IRQn
#define PIOS_USART3_IRQHANDLER_FUNC void USART1_IRQHandler(void)
#define PIOS_USART3_CLK_FUNC RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE)
#define PIOS_USART3_NVIC_PRIO PIOS_IRQ_PRIO_HIGH
#define PIOS_USART3_BAUDRATE 57600
//-------------------------
// PIOS_USART
//-------------------------
#define PIOS_USART_NUM 1
#define PIOS_USART_RX_BUFFER_SIZE 64
#define PIOS_USART_TX_BUFFER_SIZE 64
#define PIOS_COM_DEBUG_PORT USART_1
//-------------------------
// Delay Timer
//-------------------------
#define PIOS_DELAY_TIMER TIM2
#define PIOS_DELAY_TIMER_RCC_FUNC RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE)
//-------------------------
// System Settings
//-------------------------
#define PIOS_MASTER_CLOCK 72000000
#define PIOS_PERIPHERAL_CLOCK (PIOS_MASTER_CLOCK / 2)
#define PIOS_NVIC_VECTTAB_FLASH ((uint32_t)0x08000000)
//-------------------------
// Interrupt Priorities
//-------------------------
#define PIOS_IRQ_PRIO_LOW 12 // lower than RTOS
#define PIOS_IRQ_PRIO_MID 8 // higher than RTOS
#define PIOS_IRQ_PRIO_HIGH 5 // for SPI, ADC, I2C etc...
#define PIOS_IRQ_PRIO_HIGHEST 4 // for USART etc...
//-------------------------
// USB
//-------------------------
#define PIOS_USB_ENABLED 1
#define PIOS_USB_DETECT_GPIO_PORT GPIOC
#define PIOS_USB_DETECT_GPIO_PIN GPIO_Pin_4
#define PIOS_IRQ_USB_PRIORITY PIOS_IRQ_PRIO_MID
#endif /* PIOS_BOARD_H */

View File

@ -1,49 +0,0 @@
/**
******************************************************************************
*
* @file pios_config.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief PiOS configuration header.
* Central compile time config for the project.
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef PIOS_CONFIG_H
#define PIOS_CONFIG_H
/* Enable/Disable PiOS Modules */
#define PIOS_INCLUDE_DELAY
#define PIOS_INCLUDE_IRQ
#define PIOS_INCLUDE_LED
#define PIOS_INCLUDE_SYS
#define PIOS_INCLUDE_USART
#define PIOS_INCLUDE_USB_HID
#define PIOS_INCLUDE_USB
#define PIOS_INCLUDE_COM
#if !defined(PIOS_INCLUDE_FREERTOS)
#define vSemaphoreCreateBinary(a) a = 0;
#define xSemaphoreHandle int32_t
#define portBASE_TYPE int32_t
#define xSemaphoreGiveFromISR(a, b) a = 1;
#endif
#endif /* PIOS_CONFIG_H */

View File

@ -1,70 +0,0 @@
/**
******************************************************************************
*
* @file ymodem.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief YModem functions header
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef YMODEM_H
#define YMODEM_H
/* Global Defines */
#define PACKET_SEQNO_INDEX (1)
#define PACKET_SEQNO_COMP_INDEX (2)
#define PACKET_HEADER (3)
#define PACKET_TRAILER (2)
#define PACKET_OVERHEAD (PACKET_HEADER + PACKET_TRAILER)
#define PACKET_SIZE (128)
#define PACKET_1K_SIZE (1024)
#define FILE_NAME_LENGTH (256)
#define FILE_SIZE_LENGTH (16)
#define SOH (0x01) /* start of 128-byte data packet */
#define STX (0x02) /* start of 1024-byte data packet */
#define EOT (0x04) /* end of transmission */
#define ACK (0x06) /* acknowledge */
#define NAK (0x15) /* negative acknowledge */
#define CA (0x18) /* two of these in succession aborts transfer */
#define CRC16 (0x43) /* 'C' == 0x43, request 16-bit CRC */
#define ABORT1 (0x41) /* 'A' == 0x41, abort by user */
#define ABORT2 (0x61) /* 'a' == 0x61, abort by user */
#define NAK_TIMEOUT (0x100000)
#define MAX_ERRORS (5)
/* Global Macros */
#define IS_AF(c) ((c >= 'A') && (c <= 'F'))
#define IS_af(c) ((c >= 'a') && (c <= 'f'))
#define IS_09(c) ((c >= '0') && (c <= '9'))
#define ISVALIDHEX(c) IS_AF(c) || IS_af(c) || IS_09(c)
#define ISVALIDDEC(c) IS_09(c)
#define CONVERTDEC(c) (c - '0')
#define CONVERTHEX_alpha(c) (IS_AF(c) ? (c - 'A'+10) : (c - 'a'+10))
#define CONVERTHEX(c) (IS_09(c) ? (c - '0') : CONVERTHEX_alpha(c))
/* Public Functions */
extern int32_t Ymodem_Receive(uint8_t *buf);
#endif /* YMODEM_H */

View File

@ -1,82 +0,0 @@
/**
******************************************************************************
*
* @file openpilot_bl.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief Main OpenPilot Bootloader Function
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
/* OpenPilot Includes */
#include "openpilot_bl.h"
/* Global Variables */
static pFunction Jump_To_Application;
static uint32_t JumpAddress;
/**
* OpenPilot Bootloader Main function
*/
int main()
{
/* Brings up System using CMSIS functions, enables the LEDs. */
PIOS_SYS_Init();
/* Only go into bootloader when the USB cable is connected */
if(PIOS_USB_CableConnected()) {
/* Delay system */
PIOS_DELAY_Init();
if(PIOS_USB_IsInitialized()) {
/* Initialise the USB system */
PIOS_USB_Init(0);
}
/* Initialise COM Ports */
PIOS_COM_Init();
/* Execute the IAP driver in order to re-program the Flash */
StartBootloader();
}
/* Test if user code is programmed starting from address "ApplicationAddress" */
if(((*(volatile uint32_t*) ApplicationAddress) & 0x2FFE0000) == 0x20000000) {
/* Jump to user application */
JumpAddress = *(volatile uint32_t*) (ApplicationAddress + 4);
Jump_To_Application = (pFunction) JumpAddress;
/* Initialise user application's Stack Pointer */
__set_MSP(*(volatile uint32_t*) ApplicationAddress);
Jump_To_Application();
}
/* Loop for ever if no application code is not programmed */
PIOS_LED_Off(LED1);
PIOS_LED_Off(LED2);
for(;;) {
PIOS_LED_Toggle(LED1);
PIOS_LED_Toggle(LED2);
PIOS_DELAY_WaitmS(50);
}
return 0;
}

View File

@ -1,324 +0,0 @@
/**
******************************************************************************
*
* @file ymodem.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief YModem functions
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
/* Includes */
#include "openpilot_bl.h"
/* Local functions */
static int32_t Receive_Byte(uint8_t *c, uint32_t timeout);
static uint32_t Send_Byte(uint8_t c);
static int32_t Receive_Packet(uint8_t *data, int32_t *length, uint32_t timeout);
static uint32_t Str2Int(uint8_t *inputstr, int32_t *intnum);
/* Global variables */
uint32_t FlashDestination = ApplicationAddress; /* Flash user program offset */
/* Local variables */
static uint8_t file_name[FILE_NAME_LENGTH];
static uint16_t PageSize = PAGE_SIZE;
static uint32_t EraseCounter = 0x0;
static uint32_t NbrOfPage = 0;
static FLASH_Status FLASHStatus = FLASH_COMPLETE;
static uint32_t RamSource;
/**
* Receive a file using the ymodem protocol
* \param[in] buf Address of the first byte
* \return The size of the file
*/
int32_t Ymodem_Receive(uint8_t *buf)
{
uint8_t packet_data[PACKET_1K_SIZE + PACKET_OVERHEAD], file_size[FILE_SIZE_LENGTH], *file_ptr, *buf_ptr;
int32_t i, j, packet_length, session_done, file_done, packets_received, errors, session_begin, size = 0;
/* Initialise FlashDestination variable */
FlashDestination = ApplicationAddress;
for(session_done = 0, errors = 0, session_begin = 0;;) {
for(packets_received = 0, file_done = 0, buf_ptr = buf;;) {
switch(Receive_Packet(packet_data, &packet_length,
NAK_TIMEOUT)) {
case 0:
errors = 0;
switch(packet_length) {
/* Abort by sender */
case -1:
Send_Byte(ACK);
return 0;
/* End of transmission */
case 0:
Send_Byte(ACK);
file_done = 1;
break;
/* Normal packet */
default:
if((packet_data[PACKET_SEQNO_INDEX] & 0xff) != (packets_received & 0xff)) {
Send_Byte(NAK);
} else {
if(packets_received == 0) {/* Filename packet */
if(packet_data[PACKET_HEADER] != 0) {/* Filename packet has valid data */
for(i = 0, file_ptr = packet_data + PACKET_HEADER; (*file_ptr != 0) && (i < FILE_NAME_LENGTH);) {
file_name[i++] = *file_ptr++;
}
file_name[i++] = '\0';
for(i = 0, file_ptr++; (*file_ptr != ' ') & (i < FILE_SIZE_LENGTH);) {
file_size[i++] = *file_ptr++;
}
file_size[i++] = '\0';
Str2Int(file_size, &size);
/* Test the size of the image to be sent */
/* Image size is greater than Flash size */
if(size > (FLASH_SIZE - 1)) {
/* End session */
Send_Byte(CA);
Send_Byte(CA);
return -1;
}
/* Erase the needed pages where the user application will be loaded */
/* Define the number of page to be erased */
NbrOfPage = FLASH_PagesMask(size);
/* Erase the FLASH pages */
for(EraseCounter = 0; (EraseCounter < NbrOfPage) && (FLASHStatus == FLASH_COMPLETE); EraseCounter++) {
FLASHStatus = FLASH_ErasePage(FlashDestination + (PageSize * EraseCounter));
}
Send_Byte(ACK);
Send_Byte(CRC16);
}
/* Filename packet is empty, end session */
else {
Send_Byte(ACK);
file_done = 1;
session_done = 1;
break;
}
}
/* Data packet */
else {
memcpy(buf_ptr, packet_data + PACKET_HEADER, packet_length);
RamSource = (uint32_t) buf;
for(j = 0; (j < packet_length) && (FlashDestination < ApplicationAddress + size); j += 4) {
/* Program the data received into STM32F10x Flash */
FLASH_ProgramWord(FlashDestination, *(uint32_t*) RamSource);
if(*(uint32_t*) FlashDestination != *(uint32_t*) RamSource) {
/* End session */
Send_Byte(CA);
Send_Byte(CA);
return -2;
}
FlashDestination += 4;
RamSource += 4;
}
Send_Byte(ACK);
}
packets_received++;
session_begin = 1;
}
}
break;
case 1:
Send_Byte(CA);
Send_Byte(CA);
return -3;
default:
if(session_begin > 0) {
errors++;
}
if(errors > MAX_ERRORS) {
Send_Byte(CA);
Send_Byte(CA);
return 0;
}
Send_Byte(CRC16);
break;
}
if(file_done != 0) {
break;
}
}
if(session_done != 0) {
break;
}
}
return (int32_t) size;
}
/**
* Receive byte from sender
* \param[in] c Character
* \param[in] timeout Timeout
* \return 0 Byte received
* \return -1 Timeout
*/
static int32_t Receive_Byte(uint8_t *c, uint32_t timeout)
{
while(timeout-- > 0) {
if(PIOS_COM_ReceiveBufferUsed(OPBL_COM_PORT) > 0) {
*c = PIOS_COM_ReceiveBuffer(OPBL_COM_PORT);
return 0;
}
}
return -1;
}
/**
* Send a byte
* \param[in] c Character
* \return 0 Byte sent
*/
static uint32_t Send_Byte(uint8_t c)
{
PIOS_COM_SendChar(OPBL_COM_PORT, c);
return 0;
}
/**
* Receive a packet from sender
* \param[in] data
* \param[in] length
* \param[in] timeout
* 0 end of transmission
* -1 abort by sender
* >0 packet length
* \return 0 normally return
* \return -1 timeout or packet error
* \return 1 abort by user
*/
static int32_t Receive_Packet(uint8_t *data, int32_t *length, uint32_t timeout)
{
uint16_t i, packet_size;
uint8_t c;
*length = 0;
if(Receive_Byte(&c, timeout) != 0) {
return -1;
}
switch(c) {
case SOH:
packet_size = PACKET_SIZE;
break;
case STX:
packet_size = PACKET_1K_SIZE;
break;
case EOT:
return 0;
case CA:
if((Receive_Byte(&c, timeout) == 0) && (c == CA)) {
*length = -1;
return 0;
} else {
return -1;
}
case ABORT1:
case ABORT2:
return 1;
default:
return -1;
}
*data = c;
for(i = 1; i < (packet_size + PACKET_OVERHEAD); i++) {
if(Receive_Byte(data + i, timeout) != 0) {
return -1;
}
}
if(data[PACKET_SEQNO_INDEX] != ((data[PACKET_SEQNO_COMP_INDEX] ^ 0xff)
& 0xff)) {
return -1;
}
*length = packet_size;
return 0;
}
/**
* Convert a string to an integer
* \param[in] inputstr The string to be converted
* \param[in] intnum The intger value
* \return 1 Correct
* \return 0 Error
*/
static uint32_t Str2Int(uint8_t *inputstr, int32_t *intnum)
{
uint32_t i = 0, res = 0;
uint32_t val = 0;
if(inputstr[0] == '0' && (inputstr[1] == 'x' || inputstr[1] == 'X')) {
if(inputstr[2] == '\0') {
return 0;
}
for(i = 2; i < 11; i++) {
if(inputstr[i] == '\0') {
*intnum = val;
/* return 1; */
res = 1;
break;
}
if(ISVALIDHEX(inputstr[i])) {
val = (val << 4) + CONVERTHEX(inputstr[i]);
} else {
/* return 0, Invalid input */
res = 0;
break;
}
}
/* over 8 digit hex --invalid */
if(i >= 11) {
res = 0;
}
} else /* max 10-digit decimal input */
{
for(i = 0; i < 11; i++) {
if(inputstr[i] == '\0') {
*intnum = val;
/* return 1 */
res = 1;
break;
} else if((inputstr[i] == 'k' || inputstr[i] == 'K')
&& (i > 0)) {
val = val << 10;
*intnum = val;
res = 1;
break;
} else if((inputstr[i] == 'm' || inputstr[i] == 'M')
&& (i > 0)) {
val = val << 20;
*intnum = val;
res = 1;
break;
} else if(ISVALIDDEC(inputstr[i])) {
val = val * 10 + CONVERTDEC(inputstr[i]);
} else {
/* return 0, Invalid input */
res = 0;
break;
}
}
/* Over 10 digit decimal --invalid */
if(i >= 11) {
res = 0;
}
}
return res;
}

View File

@ -1,589 +0,0 @@
#####
# Project: OpenPilot
#
#
# Makefile for OpenPilot project build PiOS and the AP.
#
# The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2009.
#
#
# This program is free software; you can redistribute it and/or modify
# it under the terms of the GNU General Public License as published by
# the Free Software Foundation; either version 3 of the License, or
# (at your option) any later version.
#
# This program is distributed in the hope that it will be useful, but
# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
# for more details.
#
# You should have received a copy of the GNU General Public License along
# with this program; if not, write to the Free Software Foundation, Inc.,
# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
#####
# Set developer code and compile options
# Set to YES to compile for debugging
DEBUG ?= YES
# Set to YES when using Code Sourcery toolchain
CODE_SOURCERY ?= NO
# Toolchain prefix (i.e arm-elf- -> arm-elf-gcc.exe)
TCHAIN_PREFIX ?= arm-none-eabi-
# Remove command is different for Code Sourcery on Windows
ifeq ($(CODE_SOURCERY), YES)
REMOVE_CMD = cs-rm
else
REMOVE_CMD = rm
endif
FLASH_TOOL = OPENOCD
# YES enables -mthumb option to flags for source-files listed
# in SRC and CPPSRC
USE_THUMB_MODE = YES
# MCU name, submodel and board
# - MCU used for compiler-option (-mcpu)
# - MODEL used for linker-script name (-T) and passed as define
# - BOARD just passed as define (optional)
MCU = cortex-m3
CHIP = STM32F103RET
BOARD = STM3210E_OP
MODEL = HD
# Directory for output files (lst, obj, dep, elf, sym, map, hex, bin etc.)
OUTDIR = Build
# Target file name (without extension).
TARGET = bootloader
# Paths
HIDSYSTEM = .
HIDSYSTEMINC = ./inc
PIOS = ../../PiOS
PIOSINC = $(PIOS)/inc
PIOSSTM32F10X = $(PIOS)/STM32F10x
PIOSCOMMON = $(PIOS)/Common
APPLIBDIR = $(PIOSSTM32F10X)/Libraries
STMLIBDIR = $(APPLIBDIR)
STMSPDDIR = $(STMLIBDIR)/STM32F10x_StdPeriph_Driver
STMUSBDIR = $(STMLIBDIR)/STM32_USB-FS-Device_Driver
STMSPDSRCDIR = $(STMSPDDIR)/src
STMSPDINCDIR = $(STMSPDDIR)/inc
STMUSBSRCDIR = $(STMUSBDIR)/src
STMUSBINCDIR = $(STMUSBDIR)/inc
CMSISDIR = $(STMLIBDIR)/CMSIS/Core/CM3
DOXYGENDIR = .../Doc/Doxygen
## OPENPILOT CORE:
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
SRC += $(HIDSYSTEM)/stopwatch.c
SRC += $(HIDSYSTEM)/op_dfu.c
SRC += $(HIDSYSTEM)/flash_dfu.c
## CMSIS for STM32
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_flash.c
SRC += $(STMSPDSRCDIR)/stm32f10x_gpio.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)/misc.c
SRC += $(STMSPDSRCDIR)/stm32f10x_sdio.c
## STM32 USB Library
SRC += $(STMUSBSRCDIR)/usb_core.c
SRC += $(STMUSBSRCDIR)/usb_init.c
SRC += $(STMUSBSRCDIR)/usb_int.c
SRC += $(STMUSBSRCDIR)/usb_mem.c
SRC += $(STMUSBSRCDIR)/usb_regs.c
SRC += $(STMUSBSRCDIR)/usb_sil.c
# List C source files here which must be compiled in ARM-Mode (no -mthumb).
# use file-extension c for "c-only"-files
## just for testing, timer.c could be compiled in thumb-mode too
SRCARM =
# List C++ source files here.
# use file-extension .cpp for C++-files (not .C)
CPPSRC =
# List C++ source files here which must be compiled in ARM-Mode.
# use file-extension .cpp for C++-files (not .C)
#CPPSRCARM = $(TARGET).cpp
CPPSRCARM =
# List Assembler source files here.
# Make them always end in a capital .S. Files ending in a lowercase .s
# will not be considered source files but generated files (assembler
# output from the compiler), and will be deleted upon "make clean"!
# Even though the DOS/Win* filesystem matches both .s and .S the same,
# it will preserve the spelling of the filenames, and gcc itself does
# care about how the name is spelled on its command-line.
ASRC = $(PIOSSTM32F10X)/startup_stm32f10x_$(MODEL).S
# List Assembler source files here which must be assembled in ARM-Mode..
ASRCARM =
# List any extra directories to look for include files here.
# Each directory must be seperated by a space.
EXTRAINCDIRS = $(HIDSYSTEM)
EXTRAINCDIRS = $(HIDSYSTEMINC)
EXTRAINCDIRS += $(STMSPDINCDIR)
EXTRAINCDIRS += $(STMUSBINCDIR)
EXTRAINCDIRS += $(CMSISDIR)
EXTRAINCDIRS += $(CMSISCS)
# List any extra directories to look for library files here.
# Also add directories where the linker should search for
# includes from linker-script to the list
# Each directory must be seperated by a space.
EXTRA_LIBDIRS =
# Extra Libraries
# Each library-name must be seperated by a space.
# i.e. to link with libxyz.a, libabc.a and libefsl.a:
# EXTRA_LIBS = xyz abc efsl
# for newlib-lpc (file: libnewlibc-lpc.a):
# EXTRA_LIBS = newlib-lpc
EXTRA_LIBS =
# Path to Linker-Scripts
LINKERSCRIPTPATH = $(PIOSSTM32F10X)
# Optimization level, can be [0, 1, 2, 3, s].
# 0 = turn off optimization. s = optimize for size.
# (Note: 3 is not always the best optimization level. See avr-libc FAQ.)
ifeq ($(DEBUG),YES)
OPT = s
else
OPT = s
endif
# Output format. (can be ihex or binary or both)
# binary to create a load-image in raw-binary format i.e. for SAM-BA,
# ihex to create a load-image in Intel hex format
#LOADFORMAT = ihex
#LOADFORMAT = binary
LOADFORMAT = both
# Debugging format.
DEBUGF = dwarf-2
# Place project-specific -D (define) and/or
# -U options for C here.
CDEFS = -DSTM32F10X_$(MODEL)
CDEFS += -DUSE_STDPERIPH_DRIVER
CDEFS += -DUSE_$(BOARD)
CDEFS += -DUSE_STM3210E_EVAL
# Place project-specific -D and/or -U options for
# Assembler with preprocessor here.
#ADEFS = -DUSE_IRQ_ASM_WRAPPER
ADEFS = -D__ASSEMBLY__
# Compiler flag to set the C Standard level.
# c89 - "ANSI" C
# gnu89 - c89 plus GCC extensions
# c99 - ISO C99 standard (not yet fully implemented)
# gnu99 - c99 plus GCC extensions
CSTANDARD = -std=gnu99
#-----
# Compiler flags.
# -g*: generate debugging information
# -O*: optimization level
# -f...: tuning, see GCC manual and avr-libc documentation
# -Wall...: warning level
# -Wa,...: tell GCC to pass this to the assembler.
# -adhlns...: create assembler listing
#
# Flags for C and C++ (arm-elf-gcc/arm-elf-g++)
ifeq ($(DEBUG),YES)
CFLAGS = -g$(DEBUGF) -DDEBUG
endif
CFLAGS += -O$(OPT)
CFLAGS += -mcpu=$(MCU) -mthumb
CFLAGS += $(CDEFS)
CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I.
CFLAGS += -mapcs-frame
CFLAGS += -fomit-frame-pointer
CFLAGS += -fpromote-loop-indices
CFLAGS += -Wall
CFLAGS += -Werror
CFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<))))
# Compiler flags to generate dependency files:
CFLAGS += -MD -MP -MF $(OUTDIR)/dep/$(@F).d
# flags only for C
#CONLYFLAGS += -Wnested-externs
CONLYFLAGS += $(CSTANDARD)
# Assembler flags.
# -Wa,...: tell GCC to pass this to the assembler.
# -ahlns: create listing
ASFLAGS = -mcpu=$(MCU) -mthumb -I. -x assembler-with-cpp
ASFLAGS += $(ADEFS)
ASFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<))))
ASFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS))
MATH_LIB = -lm
# Linker flags.
# -Wl,...: tell GCC to pass this to linker.
# -Map: create map file
# --cref: add cross reference to map file
LDFLAGS = -nostartfiles -Wl,-Map=$(OUTDIR)/$(TARGET).map,--cref,--gc-sections
LDFLAGS += $(patsubst %,-L%,$(EXTRA_LIBDIRS))
LDFLAGS += -lc
LDFLAGS += $(patsubst %,-l%,$(EXTRA_LIBS))
LDFLAGS += $(MATH_LIB)
LDFLAGS += -lc -lgcc
# Set linker-script name depending on selected submodel name
LDFLAGS +=-T$(LINKERSCRIPTPATH)/link_stm32f10x_$(MODEL).ld
# ---------------------------------------------------------------------------
# Options for OpenOCD flash-programming
# see openocd.pdf/openocd.texi for further information
#
OOCD_LOADFILE+=$(OUTDIR)/$(TARGET).elf
# if OpenOCD is in the $PATH just set OOCD_EXE=openocd
OOCD_EXE=openocd
# debug level
OOCD_CL=-d0
# interface and board/target settings (using the OOCD target-library here)
OOCD_CL+=-f ../../Project/OpenOCD/floss-jtag.openpilot.cfg -f ../../Project/OpenOCD/stm32.cfg
# initialize
OOCD_CL+=-c init
# show the targets
OOCD_CL+=-c targets
# commands to prepare flash-write
OOCD_CL+= -c "reset halt"
# flash erase
OOCD_CL+=-c "stm32x mass_erase 0"
# flash-write
OOCD_CL+=-c "flash write_image $(OOCD_LOADFILE)"
# Verify
OOCD_CL+=-c "verify_image $(OOCD_LOADFILE)"
# reset target
OOCD_CL+=-c "reset run"
# terminate OOCD after programming
OOCD_CL+=-c shutdown
# ---------------------------------------------------------------------------
# Define programs and commands.
CC = $(TCHAIN_PREFIX)gcc
CPP = $(TCHAIN_PREFIX)g++
AR = $(TCHAIN_PREFIX)ar
OBJCOPY = $(TCHAIN_PREFIX)objcopy
OBJDUMP = $(TCHAIN_PREFIX)objdump
SIZE = $(TCHAIN_PREFIX)size
NM = $(TCHAIN_PREFIX)nm
REMOVE = $(REMOVE_CMD) -f
###SHELL = sh
###COPY = cp
# Define Messages
# English
MSG_ERRORS_NONE = Errors: none
MSG_BEGIN = ${quote}-------- begin (mode: $(RUN_MODE)) --------${quote}
MSG_END = ${quote}-------- end --------${quote}
MSG_MODINIT = ${quote}**** Generating ModInit.c${quote}
MSG_SIZE_BEFORE = ${quote}Size before:${quote}
MSG_SIZE_AFTER = ${quote}Size after build:${quote}
MSG_LOAD_FILE = ${quote}Creating load file:${quote}
MSG_EXTENDED_LISTING = ${quote}Creating Extended Listing/Disassembly:${quote}
MSG_SYMBOL_TABLE = ${quote}Creating Symbol Table:${quote}
MSG_LINKING = ${quote}**** Linking :${quote}
MSG_COMPILING = ${quote}**** Compiling C :${quote}
MSG_COMPILING_ARM = ${quote}**** Compiling C (ARM-only):${quote}
MSG_COMPILINGCPP = ${quote}Compiling C++ :${quote}
MSG_COMPILINGCPP_ARM = ${quote}Compiling C++ (ARM-only):${quote}
MSG_ASSEMBLING = ${quote}**** Assembling:${quote}
MSG_ASSEMBLING_ARM = ${quote}****Assembling (ARM-only):${quote}
MSG_CLEANING = ${quote}Cleaning project:${quote}
MSG_FORMATERROR = ${quote}Can not handle output-format${quote}
MSG_ASMFROMC = ${quote}Creating asm-File from C-Source:${quote}
MSG_ASMFROMC_ARM = ${quote}Creating asm-File from C-Source (ARM-only):${quote}
# List of all source files.
ALLSRC = $(ASRCARM) $(ASRC) $(SRCARM) $(SRC) $(CPPSRCARM) $(CPPSRC)
# List of all source files without directory and file-extension.
ALLSRCBASE = $(notdir $(basename $(ALLSRC)))
# Define all object files.
ALLOBJ = $(addprefix $(OUTDIR)/, $(addsuffix .o, $(ALLSRCBASE)))
# Define all listing files (used for make clean).
LSTFILES = $(addprefix $(OUTDIR)/, $(addsuffix .lst, $(ALLSRCBASE)))
# Define all depedency-files (used for make clean).
DEPFILES = $(addprefix $(OUTDIR)/dep/, $(addsuffix .o.d, $(ALLSRCBASE)))
elf: $(OUTDIR)/$(TARGET).elf
lss: $(OUTDIR)/$(TARGET).lss
sym: $(OUTDIR)/$(TARGET).sym
hex: $(OUTDIR)/$(TARGET).hex
bin: $(OUTDIR)/$(TARGET).bin
# Default target.
#all: begin gccversion sizebefore build sizeafter finished end
all: begin gccversion build sizeafter finished end
ifeq ($(LOADFORMAT),ihex)
build: elf hex lss sym
else
ifeq ($(LOADFORMAT),binary)
build: elf bin lss sym
else
ifeq ($(LOADFORMAT),both)
build: elf hex bin lss sym
else
$(error "$(MSG_FORMATERROR) $(FORMAT)")
endif
endif
endif
# Test if quotes are needed for the echo-command
result = ${shell echo "test"}
ifeq (${result}, test)
quote = '
else
quote =
endif
${OUTDIR}/InitMods.c: Makefile
@echo ${MSG_MODINIT}
@echo ${quote}// Autogenerated file${quote} > ${OUTDIR}/InitMods.c
@echo ${quote}${foreach MOD, ${MODNAMES}, extern unsigned int ${MOD}Initialize(void);}${quote} >> ${OUTDIR}/InitMods.c
@echo ${quote}void InitModules() {${quote} >> ${OUTDIR}/InitMods.c
@echo ${quote}${foreach MOD, ${MODNAMES}, ${MOD}Initialize();}${quote} >> ${OUTDIR}/InitMods.c
@echo ${quote}}${quote} >> ${OUTDIR}/InitMods.c
# Eye candy.
begin:
## @echo
@echo $(MSG_BEGIN)
finished:
## @echo $(MSG_ERRORS_NONE)
end:
@echo $(MSG_END)
## @echo
# Display sizes of sections.
ELFSIZE = $(SIZE) -A $(OUTDIR)/$(TARGET).elf
##ELFSIZE = $(SIZE) --format=Berkeley --common $(OUTDIR)/$(TARGET).elf
sizebefore:
# @if [ -f $(OUTDIR)/$(TARGET).elf ]; then echo; echo $(MSG_SIZE_BEFORE); $(ELFSIZE); echo; fi
sizeafter:
# @if [ -f $(OUTDIR)/$(TARGET).elf ]; then echo; echo $(MSG_SIZE_AFTER); $(ELFSIZE); echo; fi
@echo $(MSG_SIZE_AFTER)
$(ELFSIZE)
# Display compiler version information.
gccversion :
@$(CC) --version
# @echo $(ALLOBJ)
# Program the device.
ifeq ($(FLASH_TOOL),OPENOCD)
# Program the device with Dominic Rath's OPENOCD in "batch-mode", needs cfg and "reset-script".
program: $(OUTDIR)/$(TARGET).elf
@echo ${quote}Programming with OPENOCD${quote}
$(OOCD_EXE) $(OOCD_CL)
endif
# Create final output file (.hex) from ELF output file.
%.hex: %.elf
## @echo
@echo $(MSG_LOAD_FILE) $@
$(OBJCOPY) -O ihex $< $@
# Create final output file (.bin) from ELF output file.
%.bin: %.elf
## @echo
@echo $(MSG_LOAD_FILE) $@
$(OBJCOPY) -O binary $< $@
# Create extended listing file/disassambly from ELF output file.
# using objdump testing: option -C
%.lss: %.elf
## @echo
@echo $(MSG_EXTENDED_LISTING) $@
$(OBJDUMP) -h -S -C -r $< > $@
# $(OBJDUMP) -x -S $< > $@
# Create a symbol table from ELF output file.
%.sym: %.elf
## @echo
@echo $(MSG_SYMBOL_TABLE) $@
$(NM) -n $< > $@
# Link: create ELF output file from object files.
.SECONDARY : $(TARGET).elf
.PRECIOUS : $(ALLOBJ)
%.elf: $(ALLOBJ)
@echo $(MSG_LINKING) $@
# use $(CC) for C-only projects or $(CPP) for C++-projects:
$(CC) $(THUMB) $(CFLAGS) $(ALLOBJ) --output $@ $(LDFLAGS)
# $(CPP) $(THUMB) $(CFLAGS) $(ALLOBJ) --output $@ $(LDFLAGS)
# Assemble: create object files from assembler source files.
define ASSEMBLE_TEMPLATE
$(OUTDIR)/$(notdir $(basename $(1))).o : $(1)
## @echo
@echo $(MSG_ASSEMBLING) $$< to $$@
$(CC) -c $(THUMB) $$(ASFLAGS) $$< -o $$@
endef
$(foreach src, $(ASRC), $(eval $(call ASSEMBLE_TEMPLATE, $(src))))
# Assemble: create object files from assembler source files. ARM-only
define ASSEMBLE_ARM_TEMPLATE
$(OUTDIR)/$(notdir $(basename $(1))).o : $(1)
## @echo
@echo $(MSG_ASSEMBLING_ARM) $$< to $$@
$(CC) -c $$(ASFLAGS) $$< -o $$@
endef
$(foreach src, $(ASRCARM), $(eval $(call ASSEMBLE_ARM_TEMPLATE, $(src))))
# Compile: create object files from C source files.
define COMPILE_C_TEMPLATE
$(OUTDIR)/$(notdir $(basename $(1))).o : $(1)
## @echo
@echo $(MSG_COMPILING) $$< to $$@
$(CC) -c $(THUMB) $$(CFLAGS) $$(CONLYFLAGS) $$< -o $$@
endef
$(foreach src, $(SRC), $(eval $(call COMPILE_C_TEMPLATE, $(src))))
# Compile: create object files from C source files. ARM-only
define COMPILE_C_ARM_TEMPLATE
$(OUTDIR)/$(notdir $(basename $(1))).o : $(1)
## @echo
@echo $(MSG_COMPILING_ARM) $$< to $$@
$(CC) -c $$(CFLAGS) $$(CONLYFLAGS) $$< -o $$@
endef
$(foreach src, $(SRCARM), $(eval $(call COMPILE_C_ARM_TEMPLATE, $(src))))
# Compile: create object files from C++ source files.
define COMPILE_CPP_TEMPLATE
$(OUTDIR)/$(notdir $(basename $(1))).o : $(1)
## @echo
@echo $(MSG_COMPILINGCPP) $$< to $$@
$(CC) -c $(THUMB) $$(CFLAGS) $$(CPPFLAGS) $$< -o $$@
endef
$(foreach src, $(CPPSRC), $(eval $(call COMPILE_CPP_TEMPLATE, $(src))))
# Compile: create object files from C++ source files. ARM-only
define COMPILE_CPP_ARM_TEMPLATE
$(OUTDIR)/$(notdir $(basename $(1))).o : $(1)
## @echo
@echo $(MSG_COMPILINGCPP_ARM) $$< to $$@
$(CC) -c $$(CFLAGS) $$(CPPFLAGS) $$< -o $$@
endef
$(foreach src, $(CPPSRCARM), $(eval $(call COMPILE_CPP_ARM_TEMPLATE, $(src))))
# Compile: create assembler files from C source files. ARM/Thumb
$(SRC:.c=.s) : %.s : %.c
@echo $(MSG_ASMFROMC) $< to $@
$(CC) $(THUMB) -S $(CFLAGS) $(CONLYFLAGS) $< -o $@
# Compile: create assembler files from C source files. ARM only
$(SRCARM:.c=.s) : %.s : %.c
@echo $(MSG_ASMFROMC_ARM) $< to $@
$(CC) -S $(CFLAGS) $(CONLYFLAGS) $< -o $@
# Generate Doxygen documents
docs:
doxygen $(DOXYGENDIR)/doxygen.cfg
# Target: clean project.
clean: begin clean_list finished end
clean_list :
## @echo
@echo $(MSG_CLEANING)
$(REMOVE) $(OUTDIR)/$(TARGET).map
$(REMOVE) $(OUTDIR)/$(TARGET).elf
$(REMOVE) $(OUTDIR)/$(TARGET).hex
$(REMOVE) $(OUTDIR)/$(TARGET).bin
$(REMOVE) $(OUTDIR)/$(TARGET).sym
$(REMOVE) $(OUTDIR)/$(TARGET).lss
$(REMOVE) $(ALLOBJ)
$(REMOVE) $(LSTFILES)
$(REMOVE) $(DEPFILES)
$(REMOVE) $(SRC:.c=.s)
$(REMOVE) $(SRCARM:.c=.s)
$(REMOVE) $(CPPSRC:.cpp=.s)
$(REMOVE) $(CPPSRCARM:.cpp=.s)
# Create output files directory
# all known MS Windows OS define the ComSpec environment variable
ifdef ComSpec
$(shell md $(OUTDIR) 2>NUL)
else
$(shell mkdir $(OUTDIR) 2>/dev/null)
endif
# Include the dependency files.
ifdef ComSpec
-include $(shell md $(OUTDIR)\dep 2>NUL) $(wildcard $(OUTDIR)/dep/*)
else
-include $(shell mkdir $(OUTDIR) 2>/dev/null) $(shell mkdir $(OUTDIR)/dep 2>/dev/null) $(wildcard $(OUTDIR)/dep/*)
endif
# Listing of phony targets.
.PHONY : all begin finish end sizebefore sizeafter gccversion \
build elf hex bin lss sym clean clean_list program

View File

@ -1,90 +0,0 @@
/******************** (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"
#include <string.h>
#include "op_dfu.h"
//extern uint32_t baseOfAdressType(DFUTransfer type);
//extern uint8_t* SendBuffer;
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
//uint32_t downPacketCurrent = 0;
//uint8_t downType = 0;
//uint32_t downSizeOfLastPacket = 0;
//uint32_t downPacketTotal = 0;
//extern DFUStates DeviceState;
//extern uint32_t Aditionals;
uint8_t FLASH_Ini() {
FLASH_Unlock();
return 1;
}
uint8_t *FLASH_If_Read(uint32_t SectorAddress, uint32_t DataLength) {
return (uint8_t*) (SectorAddress);
}
uint8_t FLASH_Start(uint32_t size) {
FLASH_ErasePage(0x08008800);
uint32_t pageAdress;
pageAdress = StartOfUserCode;
uint8_t fail = FALSE;
while ((pageAdress < StartOfUserCode + size) || (fail == TRUE)) {
for (int retry = 0; retry < MAX_DEL_RETRYS; ++retry) {
if (FLASH_ErasePage(pageAdress) == FLASH_COMPLETE) {
fail = FALSE;
break;
} else {
fail = TRUE;
}
}
#ifdef STM32F10X_HD
pageAdress += 2048;
#endif
#ifdef STM32F10X_MD
pageAdress += 1024;
#endif
}
if (fail == FALSE) {
#ifdef STM32F10X_HD
pageAdress = StartOfUserCode + SizeOfHash + SizeOfDescription
+ SizeOfCode - 2048;
#endif
#ifdef STM32F10X_MD
pageAdress = StartOfUserCode+SizeOfHash+SizeOfDescription+SizeOfCode-1024;
#endif
for (int retry = 0; retry < MAX_DEL_RETRYS; ++retry) {
if (FLASH_ErasePage(pageAdress) == FLASH_COMPLETE) {
fail = FALSE;
break;
} else
fail = TRUE;
}
}
return (fail == TRUE) ? 0 : 1;
}
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -1,416 +0,0 @@
/******************** (C) COPYRIGHT 2010 STMicroelectronics ********************
* File Name : hw_config.c
* Author : MCD Application Team
* Version : V3.2.1
* Date : 07/05/2010
* Description : Hardware Configuration & Setup
********************************************************************************
* 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 "platform_config.h"
#include "hw_config.h"
#include "usb_lib.h"
#include "usb_desc.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
* Description : Configures Main system clocks & power.
* Input : None.
* Return : None.
*******************************************************************************/
void Set_System(void)
{
/* SYSCLK, HCLK, PCLK2 and PCLK1 configuration -----------------------------*/
/* RCC system reset(for debug purpose) */
RCC_DeInit();
/* Enable HSE */
RCC_HSEConfig(RCC_HSE_ON);
/* Wait till HSE is ready */
HSEStartUpStatus = RCC_WaitForHSEStartUp();
if (HSEStartUpStatus == SUCCESS)
{
/* Enable Prefetch Buffer */
FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
/* Flash 2 wait state */
FLASH_SetLatency(FLASH_Latency_2);
/* HCLK = SYSCLK */
RCC_HCLKConfig(RCC_SYSCLK_Div1);
/* PCLK2 = HCLK */
RCC_PCLK2Config(RCC_HCLK_Div1);
/* 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
* Description : Configures USB Clock input (48MHz).
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void Set_USBClock(void)
{
#ifdef STM32F10X_CL
/* Select USBCLK source */
RCC_OTGFSCLKConfig(RCC_OTGFSCLKSource_PLLVCO_Div3);
/* Enable the USB clock */
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_OTG_FS, ENABLE) ;
#else
/* Select USBCLK source */
RCC_USBCLKConfig(RCC_USBCLKSource_PLLCLK_1Div5);
/* Enable the USB clock */
RCC_APB1PeriphClockCmd(RCC_APB1Periph_USB, ENABLE);
#endif /* STM32F10X_CL */
}
/*******************************************************************************
* Function Name : Enter_LowPowerMode.
* Description : Power-off system clocks and power while entering suspend mode.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void Enter_LowPowerMode(void)
{
/* Set the device state to suspend */
bDeviceState = SUSPENDED;
}
/*******************************************************************************
* Function Name : Leave_LowPowerMode.
* Description : Restores system clocks and power while exiting suspend mode.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
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
{
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
*******************************************************************************/
void USB_Cable_Config (FunctionalState NewState)
{
#ifdef USE_STM3210C_EVAL
if (NewState != DISABLE)
{
USB_DevConnect();
}
else
{
USB_DevDisconnect();
}
#else /* USE_STM3210B_EVAL or USE_STM3210E_EVAL */
if (NewState != DISABLE)
{
GPIO_ResetBits(USB_DISCONNECT, USB_DISCONNECT_PIN);
}
else
{
GPIO_SetBits(USB_DISCONNECT, USB_DISCONNECT_PIN);
}
#endif /* USE_STM3210C_EVAL */
}
/*******************************************************************************
* Function Name : Reset_Device.
* Description : Reset the device.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void Reset_Device(void)
{
USB_Cable_Config(DISABLE);
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;
#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 */
}
/*******************************************************************************
* 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.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void Get_SerialNum(void)
{
uint32_t Device_Serial0, Device_Serial1, Device_Serial2;
Device_Serial0 = *(__IO uint32_t*)(0x1FFFF7E8);
Device_Serial1 = *(__IO uint32_t*)(0x1FFFF7EC);
Device_Serial2 = *(__IO uint32_t*)(0x1FFFF7F0);
Device_Serial0 += Device_Serial2;
if (Device_Serial0 != 0)
{
IntToUnicode (Device_Serial0, &CustomHID_StringSerial[2] , 8);
IntToUnicode (Device_Serial1, &CustomHID_StringSerial[18], 4);
}
}
/*******************************************************************************
* Function Name : HexToChar.
* Description : Convert Hex 32Bits value into char.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
static void IntToUnicode (uint32_t value , uint8_t *pbuf , uint8_t len)
{
uint8_t idx = 0;
for( idx = 0 ; idx < len ; idx ++)
{
if( ((value >> 28)) < 0xA )
{
pbuf[ 2* idx] = (value >> 28) + '0';
}
else
{
pbuf[2* idx] = (value >> 28) + 'A' - 10;
}
value = value << 4;
pbuf[ 2* idx + 1] = 0;
}
}
#ifdef STM32F10X_CL
/*******************************************************************************
* Function Name : USB_OTG_BSP_uDelay.
* Description : provide delay (usec).
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void USB_OTG_BSP_uDelay (const uint32_t usec)
{
RCC_ClocksTypeDef RCC_Clocks;
/* Configure HCLK clock as SysTick clock source */
SysTick_CLKSourceConfig(SysTick_CLKSource_HCLK);
RCC_GetClocksFreq(&RCC_Clocks);
SysTick_Config(usec * (RCC_Clocks.HCLK_Frequency / 1000000));
SysTick->CTRL &= ~SysTick_CTRL_TICKINT_Msk ;
while (!(SysTick->CTRL & SysTick_CTRL_COUNTFLAG_Msk));
}
#endif
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -1,31 +0,0 @@
/*
* board.h
*
* Created on: 2010/08/31
* Author: Programacao
*/
#ifndef BOARD_H_
#define BOARD_H_
#define deviceID 69
#define board_can_read 1
#define board_can_write 1
/**************************************************/
/* OP_DFU Memory locations */
/**************************************************/
#define StartOfUserCode 0x08006000
/**************************************************/
/* OP_DFU Mem Sizes */
/**************************************************/
#define SizeOfHash 20//0x14
#define SizeOfDescription 100 //0x64 start=807FFEC
#define SizeOfCode 499712-SizeOfHash-SizeOfDescription //488K
//524288
#endif /* BOARD_H_ */

View File

@ -1,82 +0,0 @@
/*
* common.h
*
* Created on: 2010/08/18
* Author: Programacao
*/
#ifndef COMMON_H_
#define COMMON_H_
#include "board.h"
typedef enum {
start, keepgoing,
} DownloadAction;
/**************************************************/
/* OP_DFU states */
/**************************************************/
typedef enum {
DFUidle, //0
uploading, //1
wrong_packet_received, //2
too_many_packets, //3
too_few_packets, //4
Last_operation_Success, //5
downloading, //6
idle, //7
Last_operation_failed, //8
uploadingStarting, //9
outsideDevCapabilities, //10
test
} DFUStates;
/**************************************************/
/* OP_DFU commands */
/**************************************************/
typedef enum {
Reserved, //0
Req_Capabilities, //1
Rep_Capabilities, //2
EnterDFU, //3
JumpFW, //4
Reset, //5
Abort_Operation, //6
Upload, //7
Op_END, //8
Download_Req, //9
Download, //10
Status_Request, //11
Status_Rep
//12
} DFUCommands;
/**************************************************/
/* OP_DFU transfer types */
/**************************************************/
typedef enum {
FW, //0
Hash, //1
Descript
//2
} DFUTransfer;
/**************************************************/
/* OP_DFU programable programable HW types */
/**************************************************/
typedef enum {
Self_flash, //0
Remote_flash_via_spi
//1
} DFUProgType;
/**************************************************/
/* OP_DFU programable sources */
/**************************************************/
#define USB 0
#define SPI 1
#define DownloadDelay 100000
#define MAX_DEL_RETRYS 3
#define MAX_WRI_RETRYS 3
#endif /* COMMON_H_ */

View File

@ -1,15 +0,0 @@
/*
* flash_dfu.h
*
* Created on: 2010/08/31
* Author: Programacao
*/
#ifndef FLASH_DFU_H_
#define FLASH_DFU_H_
uint8_t FLASH_Ini();
uint8_t FLASH_Start(uint32_t size);
uint8_t *FLASH_If_Read(uint32_t SectorAddress, uint32_t DataLength);
#endif /* FLASH_DFU_H_ */

View File

@ -1,41 +0,0 @@
/******************** (C) COPYRIGHT 2010 STMicroelectronics ********************
* File Name : hw_config.h
* Author : MCD Application Team
* Version : V3.2.1
* Date : 07/05/2010
* Description : Hardware Configuration & Setup
********************************************************************************
* 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 __HW_CONFIG_H
#define __HW_CONFIG_H
/* Includes ------------------------------------------------------------------*/
#include "usb_type.h"
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
/* Exported define -----------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
void Set_System(void);
void Set_USBClock(void);
void Enter_LowPowerMode(void);
void Leave_LowPowerMode(void);
void USB_Interrupts_Config(void);
void USB_Cable_Config (FunctionalState NewState);
void GPIO_Configuration(void);
void EXTI_Configuration(void);
void ADC_Configuration(void);
void Get_SerialNum(void);
void Reset_Device(void);
#endif /*__HW_CONFIG_H*/
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -1,48 +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 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 __OP_DFU_H
#define __OP_DFU_H
#include "common.h"
/* Includes ------------------------------------------------------------------*/
/* Exported types ------------------------------------------------------------*/
typedef struct
{
uint8_t programmingType;
uint8_t readWriteFlags;
uint32_t startOfUserCode;
uint32_t sizeOfCode;
uint8_t sizeOfDescription;
uint8_t sizeOfHash;
uint8_t devID;
}Device;
/* Exported constants --------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
/* Exported define -----------------------------------------------------------*/
#define COMMAND 0
#define COUNT 1
#define DATA 5
/* Exported functions ------------------------------------------------------- */
void processComand(uint8_t *Receive_Buffer);
uint32_t baseOfAdressType(uint8_t type);
uint8_t isBiggerThanAvailable(uint8_t type, uint32_t size);
void OPDfuIni(void);
void DataDownload(DownloadAction);
#endif /* __OP_DFU_H */
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -1,59 +0,0 @@
/******************** (C) COPYRIGHT 2010 STMicroelectronics ********************
* File Name : platform_config.h
* Author : MCD Application Team
* Version : V3.2.1
* Date : 07/05/2010
* Description : Evaluation board specific 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.
* 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 __PLATFORM_CONFIG_H
#define __PLATFORM_CONFIG_H
/* Includes ------------------------------------------------------------------*/
/* 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
#define USE_STM3210C_EVAL
#endif
/* Define the STM32F10x hardware depending on the used evaluation board */
#ifdef USE_STM3210B_EVAL
#define USB_DISCONNECT GPIOD
#define USB_DISCONNECT_PIN GPIO_Pin_9
#define RCC_APB2Periph_GPIO_DISCONNECT RCC_APB2Periph_GPIOD
#elif defined (USE_STM3210E_EVAL)
#define USB_DISCONNECT GPIOC
#define USB_DISCONNECT_PIN GPIO_Pin_4
#define RCC_APB2Periph_GPIO_DISCONNECT RCC_APB2Periph_GPIOC
#elif defined (USE_STM3210C_EVAL)
#define USB_DISCONNECT 0
#define USB_DISCONNECT_PIN 0
#define RCC_APB2Periph_GPIO_DISCONNECT 0
#endif /* USE_STM3210B_EVAL */
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
#endif /* __PLATFORM_CONFIG_H */
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -1,327 +0,0 @@
/**
******************************************************************************
* @file stm3210e_eval.h
* @author MCD Application Team
* @version V4.2.0
* @date 04/16/2010
* @brief This file contains definitions for STM3210E_EVAL's Leds, push-buttons
* COM ports, sFLASH (on SPI) and Temperature Sensor LM75 (on I2C)
* hardware resources.
******************************************************************************
* @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>
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM3210E_EVAL_H
#define __STM3210E_EVAL_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32_eval.h"
/** @addtogroup Utilities
* @{
*/
/** @addtogroup STM32_EVAL
* @{
*/
/** @addtogroup STM3210E_EVAL
* @{
*/
/** @addtogroup STM3210E_EVAL_LOW_LEVEL
* @{
*/
/** @defgroup STM3210E_EVAL_LOW_LEVEL_Exported_Types
* @{
*/
/**
* @}
*/
/** @defgroup STM3210E_EVAL_LOW_LEVEL_Exported_Constants
* @{
*/
/** @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
/**
* @}
*/
/** @addtogroup STM3210E_EVAL_LOW_LEVEL_BUTTON
* @{
*/
#define BUTTONn 8
/**
* @brief Wakeup push-button
*/
#define WAKEUP_BUTTON_PIN GPIO_Pin_0
#define WAKEUP_BUTTON_GPIO_PORT GPIOA
#define WAKEUP_BUTTON_GPIO_CLK RCC_APB2Periph_GPIOA
#define WAKEUP_BUTTON_EXTI_LINE EXTI_Line0
#define WAKEUP_BUTTON_EXTI_PORT_SOURCE GPIO_PortSourceGPIOA
#define WAKEUP_BUTTON_EXTI_PIN_SOURCE GPIO_PinSource0
#define WAKEUP_BUTTON_EXTI_IRQn EXTI0_IRQn
/**
* @brief Tamper push-button
*/
#define TAMPER_BUTTON_PIN GPIO_Pin_13
#define TAMPER_BUTTON_GPIO_PORT GPIOC
#define TAMPER_BUTTON_GPIO_CLK RCC_APB2Periph_GPIOC
#define TAMPER_BUTTON_EXTI_LINE EXTI_Line13
#define TAMPER_BUTTON_EXTI_PORT_SOURCE GPIO_PortSourceGPIOC
#define TAMPER_BUTTON_EXTI_PIN_SOURCE GPIO_PinSource13
#define TAMPER_BUTTON_EXTI_IRQn EXTI15_10_IRQn
/**
* @brief Key push-button
*/
#define KEY_BUTTON_PIN GPIO_Pin_8
#define KEY_BUTTON_GPIO_PORT GPIOG
#define KEY_BUTTON_GPIO_CLK RCC_APB2Periph_GPIOG
#define KEY_BUTTON_EXTI_LINE EXTI_Line8
#define KEY_BUTTON_EXTI_PORT_SOURCE GPIO_PortSourceGPIOG
#define KEY_BUTTON_EXTI_PIN_SOURCE GPIO_PinSource8
#define KEY_BUTTON_EXTI_IRQn EXTI9_5_IRQn
/**
* @brief Joystick Right push-button
*/
#define RIGHT_BUTTON_PIN GPIO_Pin_13
#define RIGHT_BUTTON_GPIO_PORT GPIOG
#define RIGHT_BUTTON_GPIO_CLK RCC_APB2Periph_GPIOG
#define RIGHT_BUTTON_EXTI_LINE EXTI_Line13
#define RIGHT_BUTTON_EXTI_PORT_SOURCE GPIO_PortSourceGPIOG
#define RIGHT_BUTTON_EXTI_PIN_SOURCE GPIO_PinSource13
#define RIGHT_BUTTON_EXTI_IRQn EXTI15_10_IRQn
/**
* @brief Joystick Left push-button
*/
#define LEFT_BUTTON_PIN GPIO_Pin_14
#define LEFT_BUTTON_GPIO_PORT GPIOG
#define LEFT_BUTTON_GPIO_CLK RCC_APB2Periph_GPIOG
#define LEFT_BUTTON_EXTI_LINE EXTI_Line14
#define LEFT_BUTTON_EXTI_PORT_SOURCE GPIO_PortSourceGPIOG
#define LEFT_BUTTON_EXTI_PIN_SOURCE GPIO_PinSource14
#define LEFT_BUTTON_EXTI_IRQn EXTI15_10_IRQn
/**
* @brief Joystick Up push-button
*/
#define UP_BUTTON_PIN GPIO_Pin_15
#define UP_BUTTON_GPIO_PORT GPIOG
#define UP_BUTTON_GPIO_CLK RCC_APB2Periph_GPIOG
#define UP_BUTTON_EXTI_LINE EXTI_Line15
#define UP_BUTTON_EXTI_PORT_SOURCE GPIO_PortSourceGPIOG
#define UP_BUTTON_EXTI_PIN_SOURCE GPIO_PinSource15
#define UP_BUTTON_EXTI_IRQn EXTI15_10_IRQn
/**
* @brief Joystick Down push-button
*/
#define DOWN_BUTTON_PIN GPIO_Pin_3
#define DOWN_BUTTON_GPIO_PORT GPIOD
#define DOWN_BUTTON_GPIO_CLK RCC_APB2Periph_GPIOD
#define DOWN_BUTTON_EXTI_LINE EXTI_Line3
#define DOWN_BUTTON_EXTI_PORT_SOURCE GPIO_PortSourceGPIOD
#define DOWN_BUTTON_EXTI_PIN_SOURCE GPIO_PinSource3
#define DOWN_BUTTON_EXTI_IRQn EXTI3_IRQn
/**
* @brief Joystick Sel push-button
*/
#define SEL_BUTTON_PIN GPIO_Pin_7
#define SEL_BUTTON_GPIO_PORT GPIOG
#define SEL_BUTTON_GPIO_CLK RCC_APB2Periph_GPIOG
#define SEL_BUTTON_EXTI_LINE EXTI_Line7
#define SEL_BUTTON_EXTI_PORT_SOURCE GPIO_PortSourceGPIOG
#define SEL_BUTTON_EXTI_PIN_SOURCE GPIO_PinSource7
#define SEL_BUTTON_EXTI_IRQn EXTI9_5_IRQn
/**
* @}
*/
/** @addtogroup STM3210E_EVAL_LOW_LEVEL_COM
* @{
*/
#define COMn 2
/**
* @brief Definition for COM port1, connected to USART1
*/
#define EVAL_COM1 USART1
#define EVAL_COM1_CLK RCC_APB2Periph_USART1
#define EVAL_COM1_TX_PIN GPIO_Pin_9
#define EVAL_COM1_TX_GPIO_PORT GPIOA
#define EVAL_COM1_TX_GPIO_CLK RCC_APB2Periph_GPIOA
#define EVAL_COM1_RX_PIN GPIO_Pin_10
#define EVAL_COM1_RX_GPIO_PORT GPIOA
#define EVAL_COM1_RX_GPIO_CLK RCC_APB2Periph_GPIOA
#define EVAL_COM1_IRQn USART1_IRQn
/**
* @brief Definition for COM port2, connected to USART2
*/
#define EVAL_COM2 USART2
#define EVAL_COM2_CLK RCC_APB1Periph_USART2
#define EVAL_COM2_TX_PIN GPIO_Pin_2
#define EVAL_COM2_TX_GPIO_PORT GPIOA
#define EVAL_COM2_TX_GPIO_CLK RCC_APB2Periph_GPIOA
#define EVAL_COM2_RX_PIN GPIO_Pin_3
#define EVAL_COM2_RX_GPIO_PORT GPIOA
#define EVAL_COM2_RX_GPIO_CLK RCC_APB2Periph_GPIOA
#define EVAL_COM2_IRQn USART2_IRQn
/**
* @}
*/
/** @addtogroup STM3210E_EVAL_LOW_LEVEL_SD_FLASH
* @{
*/
/**
* @brief SD FLASH SDIO Interface
*/
#define SD_DETECT_PIN GPIO_Pin_11 /* PF.11 */
#define SD_DETECT_GPIO_PORT GPIOF /* GPIOF */
#define SD_DETECT_GPIO_CLK RCC_APB2Periph_GPIOF
#define SDIO_FIFO_ADDRESS ((uint32_t)0x40018080)
/**
* @brief SDIO Intialization Frequency (400KHz max)
*/
#define SDIO_INIT_CLK_DIV ((uint8_t)0xB2)
/**
* @brief SDIO Data Transfer Frequency (25MHz max)
*/
#define SDIO_TRANSFER_CLK_DIV ((uint8_t)0x1)
/**
* @}
*/
/** @addtogroup STM3210E_EVAL_LOW_LEVEL_M25P_FLASH_SPI
* @{
*/
/**
* @brief M25P FLASH SPI Interface pins
*/
#define sFLASH_SPI SPI1
#define sFLASH_SPI_CLK RCC_APB2Periph_SPI1
#define sFLASH_SPI_SCK_PIN GPIO_Pin_5 /* PA.05 */
#define sFLASH_SPI_SCK_GPIO_PORT GPIOA /* GPIOA */
#define sFLASH_SPI_SCK_GPIO_CLK RCC_APB2Periph_GPIOA
#define sFLASH_SPI_MISO_PIN GPIO_Pin_6 /* PA.06 */
#define sFLASH_SPI_MISO_GPIO_PORT GPIOA /* GPIOA */
#define sFLASH_SPI_MISO_GPIO_CLK RCC_APB2Periph_GPIOA
#define sFLASH_SPI_MOSI_PIN GPIO_Pin_7 /* PA.07 */
#define sFLASH_SPI_MOSI_GPIO_PORT GPIOA /* GPIOA */
#define sFLASH_SPI_MOSI_GPIO_CLK RCC_APB2Periph_GPIOA
#define sFLASH_CS_PIN GPIO_Pin_2 /* PB.02 */
#define sFLASH_CS_GPIO_PORT GPIOB /* GPIOB */
#define sFLASH_CS_GPIO_CLK RCC_APB2Periph_GPIOB
/**
* @}
*/
/** @addtogroup STM3210E_EVAL_LOW_LEVEL_TSENSOR_I2C
* @{
*/
/**
* @brief LM75 Temperature Sensor I2C Interface pins
*/
#define LM75_I2C I2C1
#define LM75_I2C_CLK RCC_APB1Periph_I2C1
#define LM75_I2C_SCL_PIN GPIO_Pin_6 /* PB.06 */
#define LM75_I2C_SCL_GPIO_PORT GPIOB /* GPIOB */
#define LM75_I2C_SCL_GPIO_CLK RCC_APB2Periph_GPIOB
#define LM75_I2C_SDA_PIN GPIO_Pin_7 /* PB.07 */
#define LM75_I2C_SDA_GPIO_PORT GPIOB /* GPIOB */
#define LM75_I2C_SDA_GPIO_CLK RCC_APB2Periph_GPIOB
#define LM75_I2C_SMBUSALERT_PIN GPIO_Pin_5 /* PB.05 */
#define LM75_I2C_SMBUSALERT_GPIO_PORT GPIOB /* GPIOB */
#define LM75_I2C_SMBUSALERT_GPIO_CLK RCC_APB2Periph_GPIOB
/**
* @}
*/
/**
* @}
*/
/** @defgroup STM3210E_EVAL_LOW_LEVEL_Exported_Macros
* @{
*/
/**
* @}
*/
/** @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);
void SD_LowLevel_DeInit(void);
void SD_LowLevel_Init(void);
void SD_LowLevel_DMA_TxConfig(uint32_t *BufferSRC, uint32_t BufferSize);
void SD_LowLevel_DMA_RxConfig(uint32_t *BufferDST, uint32_t BufferSize);
void SD_WaitForDMAEndOfTransfer(void);
void sFLASH_LowLevel_DeInit(void);
void sFLASH_LowLevel_Init(void);
void LM75_LowLevel_DeInit(void);
void LM75_LowLevel_Init(void);
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __STM3210E_EVAL_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -1,354 +0,0 @@
/**
******************************************************************************
* @file stm32_eval.h
* @author MCD Application Team
* @version V4.2.0
* @date 04/16/2010
* @brief Header file for stm32_eval.c module.
******************************************************************************
* @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>
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32_EVAL_H
#define __STM32_EVAL_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
/** @addtogroup Utilities
* @{
*/
/** @addtogroup STM32_EVAL
* @{
*/
/** @defgroup STM32_EVAL_Abstraction_Layer
* @{
*/
/** @defgroup STM32_EVAL_HARDWARE_RESOURCES
* @{
*/
/**
@code
The table below gives an overview of the hardware resources supported by each
STM32 EVAL board.
- LCD: TFT Color LCD (Parallel (FSMC) and Serial (SPI))
- IOE: IO Expander on I2C
- sFLASH: serial SPI FLASH (M25Pxxx)
- sEE: serial I2C EEPROM (M24C08, M24C32, M24C64)
- TSENSOR: Temperature Sensor (LM75)
- SD: SD Card memory (SPI and SDIO (SD Card MODE))
=================================================================================================================+
STM32 EVAL | LED | Buttons | Com Ports | LCD | IOE | sFLASH | sEE | TSENSOR | SD (SPI) | SD(SDIO) |
=================================================================================================================+
STM3210B-EVAL | 4 | 8 | 2 | YES (SPI) | NO | YES | NO | YES | YES | NO |
-----------------------------------------------------------------------------------------------------------------+
STM3210E-EVAL | 4 | 8 | 2 | YES (FSMC)| NO | YES | NO | YES | NO | YES |
-----------------------------------------------------------------------------------------------------------------+
STM3210C-EVAL | 4 | 3 | 1 | YES (SPI) | YES | NO | YES | NO | YES | NO |
-----------------------------------------------------------------------------------------------------------------+
STM32100B-EVAL | 4 | 8 | 2 | YES (SPI) | NO | YES | NO | YES | YES | NO |
=================================================================================================================+
@endcode
*/
/**
* @}
*/
/** @defgroup STM32_EVAL_Exported_Types
* @{
*/
typedef enum
{
LED1 = 0,
LED2 = 1,
LED3 = 2,
LED4 = 3
} Led_TypeDef;
typedef enum
{
BUTTON_WAKEUP = 0,
BUTTON_TAMPER = 1,
BUTTON_KEY = 2,
BUTTON_RIGHT = 3,
BUTTON_LEFT = 4,
BUTTON_UP = 5,
BUTTON_DOWN = 6,
BUTTON_SEL = 7
} Button_TypeDef;
typedef enum
{
BUTTON_MODE_GPIO = 0,
BUTTON_MODE_EXTI = 1
} ButtonMode_TypeDef;
typedef enum
{
JOY_NONE = 0,
JOY_SEL = 1,
JOY_DOWN = 2,
JOY_LEFT = 3,
JOY_RIGHT = 4,
JOY_UP = 5
} JOYState_TypeDef
;
typedef enum
{
COM1 = 0,
COM2 = 1
} COM_TypeDef;
/**
* @}
*/
/** @defgroup STM32_EVAL_Exported_Constants
* @{
*/
/**
* @brief Uncomment the line corresponding to the STMicroelectronics evaluation
* board used in your application.
*
* Tip: To avoid modifying this file each time you need to switch between these
* boards, you can define the board in your toolchain compiler preprocessor.
*/
#if !defined (USE_STM32100B_EVAL) && !defined (USE_STM3210B_EVAL) && !defined (USE_STM3210E_EVAL) && !defined (USE_STM3210C_EVAL)
//#define USE_STM32100B_EVAL
//#define USE_STM3210B_EVAL
//#define USE_STM3210E_EVAL
//#define USE_STM3210C_EVAL
#endif
#ifdef USE_STM32100B_EVAL
#include "stm32f10x.h"
#include "stm32100b_eval/stm32100b_eval.h"
#elif defined USE_STM3210B_EVAL
#include "stm32f10x.h"
#include "stm3210b_eval/stm3210b_eval.h"
#elif defined USE_STM3210E_EVAL
#include "stm32f10x.h"
#include "stm3210e_eval.h"
#elif defined USE_STM3210C_EVAL
#include "stm32f10x.h"
#include "stm3210c_eval/stm3210c_eval.h"
#else
#error "Please select first the STM32 EVAL board to be used (in stm32_eval.h)"
#endif
/**
* @brief STM32 Button Defines Legacy
*/
#define Button_WAKEUP BUTTON_WAKEUP
#define Button_TAMPER BUTTON_TAMPER
#define Button_KEY BUTTON_KEY
#define Button_RIGHT BUTTON_RIGHT
#define Button_LEFT BUTTON_LEFT
#define Button_UP BUTTON_UP
#define Button_DOWN BUTTON_DOWN
#define Button_SEL BUTTON_SEL
#define Mode_GPIO BUTTON_MODE_GPIO
#define Mode_EXTI BUTTON_MODE_EXTI
#define Button_Mode_TypeDef ButtonMode_TypeDef
#define JOY_CENTER JOY_SEL
#define JOY_State_TypeDef JOYState_TypeDef
/**
* @brief LCD Defines Legacy
*/
#define LCD_RSNWR_GPIO_CLK LCD_NWR_GPIO_CLK
#define LCD_SPI_GPIO_PORT LCD_SPI_SCK_GPIO_PORT
#define LCD_SPI_GPIO_CLK LCD_SPI_SCK_GPIO_CLK
#define R0 LCD_REG_0
#define R1 LCD_REG_1
#define R2 LCD_REG_2
#define R3 LCD_REG_3
#define R4 LCD_REG_4
#define R5 LCD_REG_5
#define R6 LCD_REG_6
#define R7 LCD_REG_7
#define R8 LCD_REG_8
#define R9 LCD_REG_9
#define R10 LCD_REG_10
#define R12 LCD_REG_12
#define R13 LCD_REG_13
#define R14 LCD_REG_14
#define R15 LCD_REG_15
#define R16 LCD_REG_16
#define R17 LCD_REG_17
#define R18 LCD_REG_18
#define R19 LCD_REG_19
#define R20 LCD_REG_20
#define R21 LCD_REG_21
#define R22 LCD_REG_22
#define R23 LCD_REG_23
#define R24 LCD_REG_24
#define R25 LCD_REG_25
#define R26 LCD_REG_26
#define R27 LCD_REG_27
#define R28 LCD_REG_28
#define R29 LCD_REG_29
#define R30 LCD_REG_30
#define R31 LCD_REG_31
#define R32 LCD_REG_32
#define R33 LCD_REG_33
#define R34 LCD_REG_34
#define R36 LCD_REG_36
#define R37 LCD_REG_37
#define R40 LCD_REG_40
#define R41 LCD_REG_41
#define R43 LCD_REG_43
#define R45 LCD_REG_45
#define R48 LCD_REG_48
#define R49 LCD_REG_49
#define R50 LCD_REG_50
#define R51 LCD_REG_51
#define R52 LCD_REG_52
#define R53 LCD_REG_53
#define R54 LCD_REG_54
#define R55 LCD_REG_55
#define R56 LCD_REG_56
#define R57 LCD_REG_57
#define R59 LCD_REG_59
#define R60 LCD_REG_60
#define R61 LCD_REG_61
#define R62 LCD_REG_62
#define R63 LCD_REG_63
#define R64 LCD_REG_64
#define R65 LCD_REG_65
#define R66 LCD_REG_66
#define R67 LCD_REG_67
#define R68 LCD_REG_68
#define R69 LCD_REG_69
#define R70 LCD_REG_70
#define R71 LCD_REG_71
#define R72 LCD_REG_72
#define R73 LCD_REG_73
#define R74 LCD_REG_74
#define R75 LCD_REG_75
#define R76 LCD_REG_76
#define R77 LCD_REG_77
#define R78 LCD_REG_78
#define R79 LCD_REG_79
#define R80 LCD_REG_80
#define R81 LCD_REG_81
#define R82 LCD_REG_82
#define R83 LCD_REG_83
#define R96 LCD_REG_96
#define R97 LCD_REG_97
#define R106 LCD_REG_106
#define R118 LCD_REG_118
#define R128 LCD_REG_128
#define R129 LCD_REG_129
#define R130 LCD_REG_130
#define R131 LCD_REG_131
#define R132 LCD_REG_132
#define R133 LCD_REG_133
#define R134 LCD_REG_134
#define R135 LCD_REG_135
#define R136 LCD_REG_136
#define R137 LCD_REG_137
#define R139 LCD_REG_139
#define R140 LCD_REG_140
#define R141 LCD_REG_141
#define R143 LCD_REG_143
#define R144 LCD_REG_144
#define R145 LCD_REG_145
#define R146 LCD_REG_146
#define R147 LCD_REG_147
#define R148 LCD_REG_148
#define R149 LCD_REG_149
#define R150 LCD_REG_150
#define R151 LCD_REG_151
#define R152 LCD_REG_152
#define R153 LCD_REG_153
#define R154 LCD_REG_154
#define R157 LCD_REG_157
#define R192 LCD_REG_192
#define R193 LCD_REG_193
#define R227 LCD_REG_227
#define R229 LCD_REG_229
#define R231 LCD_REG_231
#define R239 LCD_REG_239
#define White LCD_COLOR_WHITE
#define Black LCD_COLOR_BLACK
#define Grey LCD_COLOR_GREY
#define Blue LCD_COLOR_BLUE
#define Blue2 LCD_COLOR_BLUE2
#define Red LCD_COLOR_RED
#define Magenta LCD_COLOR_MAGENTA
#define Green LCD_COLOR_GREEN
#define Cyan LCD_COLOR_CYAN
#define Yellow LCD_COLOR_YELLOW
#define Line0 LCD_LINE_0
#define Line1 LCD_LINE_1
#define Line2 LCD_LINE_2
#define Line3 LCD_LINE_3
#define Line4 LCD_LINE_4
#define Line5 LCD_LINE_5
#define Line6 LCD_LINE_6
#define Line7 LCD_LINE_7
#define Line8 LCD_LINE_8
#define Line9 LCD_LINE_9
#define Horizontal LCD_DIR_HORIZONTAL
#define Vertical LCD_DIR_VERTICAL
/**
* @}
*/
/** @defgroup STM32_EVAL_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup STM32_EVAL_Exported_Functions
* @{
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __STM32_EVAL_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -1,72 +0,0 @@
/******************** (C) COPYRIGHT 2010 STMicroelectronics ********************
* File Name : stm32f10x_conf.h
* Author : MCD Application Team
* Version : V3.2.1
* Date : 07/05/2010
* Description : Library 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.
* 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 __STM32F10x_CONF_H
#define __STM32F10x_CONF_H
/* Includes ------------------------------------------------------------------*/
/* Uncomment the line below to enable peripheral header file inclusion */
#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_exti.h"
#include "stm32f10x_flash.h"
/* #include "stm32f10x_fsmc.h" */
#include "stm32f10x_gpio.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_tim.h" */
#include "stm32f10x_usart.h"
/* #include "stm32f10x_wwdg.h" */
#include "misc.h" /* High level functions for NVIC and SysTick (add-on to CMSIS functions) */
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* Uncomment the line below to expanse the "assert_param" macro in the
Standard Peripheral Library drivers code */
/* #define USE_FULL_ASSERT 1 */
/* Exported macro ------------------------------------------------------------*/
#ifdef USE_FULL_ASSERT
/*******************************************************************************
* Macro Name : assert_param
* Description : The assert_param macro is used for function's parameters check.
* Input : - expr: If expr is false, it calls assert_failed function
* which reports the name of the source file and the source
* line number of the call that failed.
* If expr is true, it returns no value.
* Return : None
*******************************************************************************/
#define assert_param(expr) ((expr) ? (void)0 : assert_failed((uint8_t *)__FILE__, __LINE__))
/* Exported functions ------------------------------------------------------- */
void assert_failed(uint8_t* file, uint32_t line);
#else
#define assert_param(expr) ((void)0)
#endif /* USE_FULL_ASSERT */
#endif /* __STM32F10x_CONF_H */
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -1,52 +0,0 @@
/******************** (C) COPYRIGHT 2010 STMicroelectronics ********************
* File Name : stm32f10x_it.h
* Author : MCD Application Team
* Version : V3.2.1
* Date : 07/05/2010
* Description : This file contains the headers of the interrupt handlers.
********************************************************************************
* 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 __STM32F10x_IT_H
#define __STM32F10x_IT_H
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
void NMI_Handler(void);
void HardFault_Handler(void);
void MemManage_Handler(void);
void BusFault_Handler(void);
void UsageFault_Handler(void);
void SVC_Handler(void);
void DebugMon_Handler(void);
void PendSV_Handler(void);
void SysTick_Handler(void);
#ifndef STM32F10X_CL
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 */
#endif /* __STM32F10x_IT_H */
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -1,29 +0,0 @@
#ifndef _STOPWATCH_H
#define _STOPWATCH_H
/////////////////////////////////////////////////////////////////////////////
// Global definitions
/////////////////////////////////////////////////////////////////////////////
/////////////////////////////////////////////////////////////////////////////
// Global Types
/////////////////////////////////////////////////////////////////////////////
/////////////////////////////////////////////////////////////////////////////
// Prototypes
/////////////////////////////////////////////////////////////////////////////
extern s32 STOPWATCH_Init(u32 resolution);
extern s32 STOPWATCH_Reset(void);
extern u32 STOPWATCH_ValueGet(void);
/////////////////////////////////////////////////////////////////////////////
// Export global variables
/////////////////////////////////////////////////////////////////////////////
#endif /* _STOPWATCH_H */

View File

@ -1,186 +0,0 @@
/******************** (C) COPYRIGHT 2010 STMicroelectronics ********************
* File Name : usb_conf.h
* Author : MCD Application Team
* Version : V3.2.1
* Date : 07/05/2010
* 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.
* 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_CONF_H
#define __USB_CONF_H
/* Includes ------------------------------------------------------------------*/
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
/* External variables --------------------------------------------------------*/
/*-------------------------------------------------------------*/
/* EP_NUM */
/* defines how many endpoints are used by the device */
/*-------------------------------------------------------------*/
#define EP_NUM (2)
#ifndef STM32F10X_CL
/*-------------------------------------------------------------*/
/* -------------- Buffer Description Table -----------------*/
/*-------------------------------------------------------------*/
/* buffer table base address */
/* buffer table base address */
#define BTABLE_ADDRESS (0x00)
/* EP0 */
/* rx/tx buffer base address */
#define ENDP0_RXADDR (0x18)
#define ENDP0_TXADDR (0x58)
/* EP1 */
/* tx buffer base address */
#define ENDP1_TXADDR (0x100)
#define ENDP1_RXADDR (0x124)
/*-------------------------------------------------------------*/
/* ------------------- ISTR events -------------------------*/
/*-------------------------------------------------------------*/
/* 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 )
#endif /* STM32F10X_CL */
#ifdef STM32F10X_CL
/*******************************************************************************
* FIFO Size Configuration
*
* (i) Dedicated data FIFO SPRAM of 1.25 Kbytes = 1280 bytes = 320 32-bits words
* available for the endpoints IN and OUT.
* Device mode features:
* -1 bidirectional CTRL EP 0
* -3 IN EPs to support any kind of Bulk, Interrupt or Isochronous transfer
* -3 OUT EPs to support any kind of Bulk, Interrupt or Isochronous transfer
*
* ii) Receive data FIFO size = RAM for setup packets +
* OUT endpoint control information +
* data OUT packets + miscellaneous
* Space = ONE 32-bits words
* --> RAM for setup packets = 4 * n + 6 space
* (n is the nbr of CTRL EPs the device core supports)
* --> OUT EP CTRL info = 1 space
* (one space for status information written to the FIFO along with each
* received packet)
* --> data OUT packets = (Largest Packet Size / 4) + 1 spaces
* (MINIMUM to receive packets)
* --> OR data OUT packets = at least 2*(Largest Packet Size / 4) + 1 spaces
* (if high-bandwidth EP is enabled or multiple isochronous EPs)
* --> miscellaneous = 1 space per OUT EP
* (one space for transfer complete status information also pushed to the
* FIFO with each endpoint's last packet)
*
* (iii)MINIMUM RAM space required for each IN EP Tx FIFO = MAX packet size for
* that particular IN EP. More space allocated in the IN EP Tx FIFO results
* in a better performance on the USB and can hide latencies on the AHB.
*
* (iv) TXn min size = 16 words. (n : Transmit FIFO index)
* (v) When a TxFIFO is not used, the Configuration should be as follows:
* case 1 : n > m and Txn is not used (n,m : Transmit FIFO indexes)
* --> Txm can use the space allocated for Txn.
* case2 : n < m and Txn is not used (n,m : Transmit FIFO indexes)
* --> Txn should be configured with the minimum space of 16 words
* (vi) The FIFO is used optimally when used TxFIFOs are allocated in the top
* of the FIFO.Ex: use EP1 and EP2 as IN instead of EP1 and EP3 as IN ones.
*******************************************************************************/
#define RX_FIFO_SIZE 128
#define TX0_FIFO_SIZE 64
#define TX1_FIFO_SIZE 64
#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
#define INTR_SOFINTR
#define INTR_RXSTSQLVL /* Mandatory */
//#define INTR_NPTXFEMPTY
//#define INTR_GINNAKEFF
//#define INTR_GOUTNAKEFF
//#define INTR_ERLYSUSPEND
#define INTR_USBSUSPEND /* Mandatory */
#define INTR_USBRESET /* Mandatory */
#define INTR_ENUMDONE /* Mandatory */
//#define INTR_ISOOUTDROP
//#define INTR_EOPFRAME
//#define INTR_EPMISMATCH
#define INTR_INEPINTR /* Mandatory */
#define INTR_OUTEPINTR /* Mandatory */
//#define INTR_INCOMPLISOIN
//#define INTR_INCOMPLISOOUT
#define INTR_WKUPINTR /* Mandatory */
/* OTGD-FS-DEVICE IP interrupts subroutines */
/* Comment the define to enable the selected interrupt subroutine and replace it
by user code */
#define INTR_MODEMISMATCH_Callback NOP_Process
#define INTR_SOFINTR_Callback NOP_Process
#define INTR_RXSTSQLVL_Callback NOP_Process
#define INTR_NPTXFEMPTY_Callback NOP_Process
#define INTR_NPTXFEMPTY_Callback NOP_Process
#define INTR_GINNAKEFF_Callback NOP_Process
#define INTR_GOUTNAKEFF_Callback NOP_Process
#define INTR_ERLYSUSPEND_Callback NOP_Process
#define INTR_USBSUSPEND_Callback NOP_Process
#define INTR_USBRESET_Callback NOP_Process
#define INTR_ENUMDONE_Callback NOP_Process
#define INTR_ISOOUTDROP_Callback NOP_Process
#define INTR_EOPFRAME_Callback NOP_Process
#define INTR_EPMISMATCH_Callback NOP_Process
#define INTR_INEPINTR_Callback NOP_Process
#define INTR_OUTEPINTR_Callback NOP_Process
#define INTR_INCOMPLISOIN_Callback NOP_Process
#define INTR_INCOMPLISOOUT_Callback NOP_Process
#define INTR_WKUPINTR_Callback NOP_Process
/* Isochronous data update */
#define INTR_RXSTSQLVL_ISODU_Callback NOP_Process
/* Isochronous transfer parameters */
/* Size of a single Isochronous buffer (size of a single transfer) */
#define ISOC_BUFFER_SZE 1
/* Number of sub-buffers (number of single buffers/transfers), should be even */
#define NUM_SUB_BUFFERS 2
#endif /* STM32F10X_CL */
/* CTR service routines */
/* associated to defined endpoints */
//#define EP1_IN_Callback NOP_Process
#define EP2_IN_Callback NOP_Process
#define EP3_IN_Callback NOP_Process
#define EP4_IN_Callback NOP_Process
#define EP5_IN_Callback NOP_Process
#define EP6_IN_Callback NOP_Process
#define EP7_IN_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
#define EP5_OUT_Callback NOP_Process
#define EP6_OUT_Callback NOP_Process
#define EP7_OUT_Callback NOP_Process
#endif /*__USB_CONF_H*/
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -1,56 +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 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

@ -1,121 +0,0 @@
/******************** (C) COPYRIGHT 2010 STMicroelectronics ********************
* File Name : usb_istr.h
* Author : MCD Application Team
* Version : V3.2.1
* Date : 07/05/2010
* Description : This file includes the peripherals header files in the
* user application.
********************************************************************************
* 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_ISTR_H
#define __USB_ISTR_H
/* Includes ------------------------------------------------------------------*/
#include "usb_conf.h"
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
#ifndef STM32F10X_CL
void USB_Istr(void);
#else /* STM32F10X_CL */
u32 STM32_PCD_OTG_ISR_Handler(void);
#endif /* STM32F10X_CL */
/* function prototypes Automatically built defining related macros */
void EP1_IN_Callback(void);
void EP2_IN_Callback(void);
void EP3_IN_Callback(void);
void EP4_IN_Callback(void);
void EP5_IN_Callback(void);
void EP6_IN_Callback(void);
void EP7_IN_Callback(void);
void EP1_OUT_Callback(void);
void EP2_OUT_Callback(void);
void EP3_OUT_Callback(void);
void EP4_OUT_Callback(void);
void EP5_OUT_Callback(void);
void EP6_OUT_Callback(void);
void EP7_OUT_Callback(void);
#ifndef STM32F10X_CL
#ifdef CTR_CALLBACK
void CTR_Callback(void);
#endif
#ifdef DOVR_CALLBACK
void DOVR_Callback(void);
#endif
#ifdef ERR_CALLBACK
void ERR_Callback(void);
#endif
#ifdef WKUP_CALLBACK
void WKUP_Callback(void);
#endif
#ifdef SUSP_CALLBACK
void SUSP_Callback(void);
#endif
#ifdef RESET_CALLBACK
void RESET_Callback(void);
#endif
#ifdef SOF_CALLBACK
void SOF_Callback(void);
#endif
#ifdef ESOF_CALLBACK
void ESOF_Callback(void);
#endif
#else /* STM32F10X_CL */
/* Interrupt subroutines user callbacks prototypes.
These callbacks are called into the respective interrupt sunroutine functinos
and can be tailored for various user application purposes.
Note: Make sure that the correspondant interrupt is enabled through the
definition in usb_conf.h file */
void INTR_MODEMISMATCH_Callback(void);
void INTR_SOFINTR_Callback(void);
void INTR_RXSTSQLVL_Callback(void);
void INTR_NPTXFEMPTY_Callback(void);
void INTR_GINNAKEFF_Callback(void);
void INTR_GOUTNAKEFF_Callback(void);
void INTR_ERLYSUSPEND_Callback(void);
void INTR_USBSUSPEND_Callback(void);
void INTR_USBRESET_Callback(void);
void INTR_ENUMDONE_Callback(void);
void INTR_ISOOUTDROP_Callback(void);
void INTR_EOPFRAME_Callback(void);
void INTR_EPMISMATCH_Callback(void);
void INTR_INEPINTR_Callback(void);
void INTR_OUTEPINTR_Callback(void);
void INTR_INCOMPLISOIN_Callback(void);
void INTR_INCOMPLISOOUT_Callback(void);
void INTR_WKUPINTR_Callback(void);
/* Isochronous data update */
void INTR_RXSTSQLVL_ISODU_Callback(void);
#endif /* STM32F10X_CL */
#endif /*__USB_ISTR_H*/
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -1,70 +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 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

@ -1,58 +0,0 @@
/******************** (C) COPYRIGHT 2010 STMicroelectronics ********************
* File Name : usb_pwr.h
* Author : MCD Application Team
* Version : V3.2.1
* Date : 07/05/2010
* Description : Connection/disconnection & power management header
********************************************************************************
* 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_PWR_H
#define __USB_PWR_H
/* Includes ------------------------------------------------------------------*/
/* Exported types ------------------------------------------------------------*/
typedef enum _RESUME_STATE
{
RESUME_EXTERNAL,
RESUME_INTERNAL,
RESUME_LATER,
RESUME_WAIT,
RESUME_START,
RESUME_ON,
RESUME_OFF,
RESUME_ESOF
} RESUME_STATE;
typedef enum _DEVICE_STATE
{
UNCONNECTED,
ATTACHED,
POWERED,
SUSPENDED,
ADDRESSED,
CONFIGURED
} DEVICE_STATE;
/* Exported constants --------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
void Suspend(void);
void Resume_Init(void);
void Resume(RESUME_STATE eResumeSetVal);
RESULT PowerOn(void);
RESULT PowerOff(void);
/* External variables --------------------------------------------------------*/
extern __IO uint32_t bDeviceState; /* USB device status */
extern __IO bool fSuspendEnabled; /* true when suspend is possible */
#endif /*__USB_PWR_H*/
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -1,213 +0,0 @@
/******************** (C) COPYRIGHT 2010 STMicroelectronics ********************
* File Name : main.c
* Author : MCD Application Team
* Version : V3.2.1
* Date : 07/05/2010
* 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.
* 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 "hw_config.h"
#include "stm32_eval.h"
#include "common.h"
#include "platform_config.h"
#include "stopwatch.h"
#include "op_dfu.h"
extern void FLASH_Download();
#define BSL_HOLD_STATE ((USB_DISCONNECT->IDR & USB_DISCONNECT_PIN) ? 0 : 1)
/* Private typedef -----------------------------------------------------------*/
typedef void (*pFunction)(void);
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
pFunction Jump_To_Application;
uint32_t JumpAddress;
/// LEDs PWM
uint32_t period1 = 50; // *100 uS -> 5 mS
uint32_t sweep_steps1 = 100; // * 5 mS -> 500 mS
uint32_t period2 = 50; // *100 uS -> 5 mS
uint32_t sweep_steps2 = 100; // * 5 mS -> 500 mS
/* Extern variables ----------------------------------------------------------*/
DFUStates DeviceState;
uint8_t JumpToApp = 0;
/* Private function prototypes -----------------------------------------------*/
void Delay(__IO uint32_t nCount);
void DelayWithDown(__IO uint32_t nCount);
uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count);
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
* Function Name : main.
* Description : main routine.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
int main(void) {
Set_System();
if (BSL_HOLD_STATE == 0) {
OPDfuIni();
USB_Interrupts_Config();
Set_USBClock();
USB_Init();
DeviceState = idle;
STOPWATCH_Init(100);
} else
JumpToApp = TRUE;
STOPWATCH_Reset();
while (JumpToApp == 0) {
//pwm_period = 50; // *100 uS -> 5 mS
//pwm_sweep_steps =100; // * 5 mS -> 500 mS
switch (DeviceState) {
case Last_operation_Success:
case uploadingStarting:
case DFUidle:
period1 = 50;
sweep_steps1 = 100;
STM_EVAL_LEDOff(LED2);
period2 = 0;
break;
case uploading:
period1 = 50;
sweep_steps1 = 100;
period2 = 25;
sweep_steps2 = 50;
break;
case downloading:
period1 = 25;
sweep_steps1 = 50;
STM_EVAL_LEDOff(LED2);
period2 = 0;
break;
case idle:
period1 = 0;
STM_EVAL_LEDOn(LED1);
period2=0;
break;
default://error
period1 = 50;
sweep_steps1 = 100;
period2 = 50;
sweep_steps2 = 100;
}
if (period1 != 0) {
if (LedPWM(period1, sweep_steps1, STOPWATCH_ValueGet()))
STM_EVAL_LEDOn(LED1);
else
STM_EVAL_LEDOff(LED1);
} else
STM_EVAL_LEDOn(LED1);
if (period2 != 0) {
if (LedPWM(period2, sweep_steps2, STOPWATCH_ValueGet()))
STM_EVAL_LEDOn(LED2);
else
STM_EVAL_LEDOff(LED2);
} else
STM_EVAL_LEDOff(LED2);
if (STOPWATCH_ValueGet() > 100 * 50 * 100)
STOPWATCH_Reset();
if ((STOPWATCH_ValueGet() > 70000) && (DeviceState == idle))
JumpToApp = TRUE;
DataDownload(start);
//DelayWithDown(10);//1000000);
}
if (((*(__IO uint32_t*) StartOfUserCode) & 0x2FFE0000) == 0x20000000) { /* Jump to user application */
FLASH_Lock();
RCC_APB2PeriphResetCmd(0xffffffff, ENABLE);
RCC_APB1PeriphResetCmd(0xffffffff, ENABLE);
RCC_APB2PeriphResetCmd(0xffffffff, DISABLE);
RCC_APB1PeriphResetCmd(0xffffffff, DISABLE);
_SetCNTR(0); // clear interrupt mask
_SetISTR(0); // clear all requests
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_LEDOff(LED1);
// STM_EVAL_LEDOff(LED2);
// while(1){}
if (LedPWM(50, 100, STOPWATCH_ValueGet())) {
STM_EVAL_LEDOn(LED2);
STM_EVAL_LEDOff(LED1);
} else {
STM_EVAL_LEDOn(LED1);
STM_EVAL_LEDOff(LED2);
}
if (STOPWATCH_ValueGet() > 2*50 * 100)
STOPWATCH_Reset();
DataDownload(start);
}
}
uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count) {
uint32_t pwm_duty = ((count / pwm_period) % pwm_sweep_steps)
/ (pwm_sweep_steps / pwm_period);
if ((count % (2 * pwm_period * pwm_sweep_steps)) > pwm_period
* pwm_sweep_steps)
pwm_duty = pwm_period - pwm_duty; // negative direction each 50*100 ticks
return ((count % pwm_period) > pwm_duty) ? 1 : 0;
}
/*******************************************************************************
* 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 : assert_failed
* Description : Reports the name of the source file and the source line number
* where the assert_param error has occurred.
* Input : - file: pointer to the source file name
* - line: assert_param error line source number
* Output : None
* 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)
{
}
}
#endif
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -1,408 +0,0 @@
/******************** (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 "hw_config.h"
#include <string.h>
#include "op_dfu.h"
#include "flash_dfu.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
//programmable devices
Device devicesTable[10];
uint8_t numberOfDevices = 0;
DFUProgType currentProgrammingDestination; //flash, flash_trough spi
uint8_t currentDeviceCanRead;
uint8_t currentDeviceCanWrite;
Device currentDevice;
uint8_t Buffer[64];
uint8_t echoBuffer[64];
uint8_t SendBuffer[64];
uint8_t Command = 0;
uint8_t EchoReqFlag = 0;
uint8_t EchoAnsFlag = 0;
uint8_t StartFlag = 0;
uint32_t Aditionals = 0;
uint32_t SizeOfTransfer = 0;
uint8_t SizeOfLastPacket = 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;
uint8_t offset = 0;
uint32_t aux;
//Download vars
uint32_t downSizeOfLastPacket = 0;
uint32_t downPacketTotal = 0;
uint32_t downPacketCurrent = 0;
DFUTransfer downType = 0;
/* Extern variables ----------------------------------------------------------*/
extern DFUStates DeviceState;
extern uint8_t JumpToApp;
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
void DataDownload(DownloadAction action) {
if ((DeviceState == downloading)) {
if((action==start) && downPacketCurrent!=0)
return;
uint8_t packetSize;
uint32_t offset;
SendBuffer[0] = 0x01;
SendBuffer[1] = Download;
SendBuffer[2] = downPacketCurrent >> 24;
SendBuffer[3] = downPacketCurrent >> 16;
SendBuffer[4] = downPacketCurrent >> 8;
SendBuffer[5] = downPacketCurrent;
if (downPacketCurrent == downPacketTotal-1) {
packetSize = downSizeOfLastPacket;
}
else {
packetSize = 14;
}
for (uint8_t x = 0; x < packetSize; ++x) {
switch (currentProgrammingDestination) {
case Self_flash:
offset=baseOfAdressType(downType) + (downPacketCurrent * 14 * 4) + (x * 4);
SendBuffer[6 + (x * 4)] = *FLASH_If_Read(offset, 0);
SendBuffer[7 + (x * 4)] = *FLASH_If_Read(offset+1, 0);
SendBuffer[8 + (x * 4)] = *FLASH_If_Read(offset+2, 0);
SendBuffer[9 + (x * 4)] = *FLASH_If_Read(offset+3, 0);
break;
case Remote_flash_via_spi:
//TODO result=SPI_FLASH();
break;
}
}
USB_SIL_Write(EP1_IN, (uint8_t*) SendBuffer, 64);
downPacketCurrent = downPacketCurrent + 1;
if (downPacketCurrent > downPacketTotal-1) {
// STM_EVAL_LEDOn(LED2);
DeviceState = Last_operation_Success;
Aditionals = (uint32_t) Download;
}
SetEPTxValid(ENDP1);
}
}
void processComand(uint8_t *Receive_Buffer) {
Command = Receive_Buffer[COMMAND];
EchoReqFlag = (Command >> 7);
EchoAnsFlag = (Command >> 6) & 0x01;
StartFlag = (Command >> 5) & 0x01;
Count = Receive_Buffer[COUNT] << 24;
Count += Receive_Buffer[COUNT + 1] << 16;
Count += Receive_Buffer[COUNT + 2] << 8;
Count += Receive_Buffer[COUNT + 3];
Data = Receive_Buffer[DATA] << 24;
Data += Receive_Buffer[DATA + 1] << 16;
Data += Receive_Buffer[DATA + 2] << 8;
Data += Receive_Buffer[DATA + 3];
Data0 = Receive_Buffer[DATA];
Data1 = Receive_Buffer[DATA + 1];
Data2 = Receive_Buffer[DATA + 2];
Data3 = Receive_Buffer[DATA + 3];
Command = Command & 0b00011111;
if (EchoReqFlag == 1) {
memcpy(echoBuffer, Buffer, 64);
}
switch (Command) {
case EnterDFU:
if (((DeviceState == idle) && (Data0 < numberOfDevices)) || (DeviceState == DFUidle)) {
DeviceState = DFUidle;
currentProgrammingDestination = devicesTable[Data0].programmingType;
currentDeviceCanRead = devicesTable[Data0].readWriteFlags & 0x01;
currentDeviceCanWrite = devicesTable[Data0].readWriteFlags >> 1 & 0x01;
currentDevice = devicesTable[Data0];
uint8_t result = 0;
switch (currentProgrammingDestination) {
case Self_flash:
result = FLASH_Ini();
break;
case Remote_flash_via_spi:
//TODO result=SPI_FLASH();
break;
default:
DeviceState = Last_operation_failed;
Aditionals = (uint16_t) Command;
}
if (result != 1) {
DeviceState = Last_operation_failed;
Aditionals = (uint32_t) Command;
}
} else {
DeviceState = outsideDevCapabilities;
Aditionals = (uint32_t) Command;
}
break;
case Upload:
if ((DeviceState == DFUidle) || (DeviceState == uploading)) {
if ((StartFlag == 1) && (Next_Packet == 0)) {
TransferType = Data0;
SizeOfTransfer = Count;
Next_Packet = 1;
SizeOfLastPacket = Data1;
if (isBiggerThanAvailable(TransferType, (SizeOfTransfer - 1) * 14
* 4 + SizeOfLastPacket * 4) == TRUE) {
DeviceState = outsideDevCapabilities;
Aditionals = (uint32_t) Command;
} else {
uint8_t result = 1;
if (TransferType == FW) {
uint32_t size = (SizeOfTransfer - 1) * 14 * 4
+ SizeOfLastPacket * 4;
result = FLASH_Start(size);
}
if (result != 1) {
DeviceState = Last_operation_failed;//ok
Aditionals = (uint32_t) Command;
} else {
DeviceState = uploading;
}
}
} else if ((StartFlag != 1) && (Next_Packet != 0)) {
if (Count > SizeOfTransfer) {
DeviceState = too_many_packets;
Aditionals = Count;
} else if (Count == Next_Packet - 1) {
uint8_t numberOfWords = 14;
if (Count == SizeOfTransfer-1)//is this the last packet?
{
numberOfWords = SizeOfLastPacket;
}
for (uint8_t x = 0; x < numberOfWords; ++x) {
offset = 4 * x;
Data = Receive_Buffer[DATA + offset] << 24;
Data += Receive_Buffer[DATA + 1 + offset] << 16;
Data += Receive_Buffer[DATA + 2 + offset] << 8;
Data += Receive_Buffer[DATA + 3 + offset];
aux = baseOfAdressType(TransferType) + (uint32_t)(Count
* 14 * 4 + x * 4);
uint8_t result = 0;
//uint8_t lol=0;
switch (currentProgrammingDestination) {
case Self_flash:
for (int retry = 0; retry < MAX_WRI_RETRYS; ++retry) {
if (result == 0) {
result = (FLASH_ProgramWord(aux, Data)
== FLASH_COMPLETE) ? 1 : 0;
}
}
break;
case Remote_flash_via_spi:
//TODO result=SPI_FLASH_ProgramWord(aux,Data);
break;
default:
result = 0;
break;
}
if (result != 1) {
DeviceState = Last_operation_failed;
Aditionals = (uint32_t) Command;
}
}
++Next_Packet;
} else {
DeviceState = wrong_packet_received;
Aditionals = Count;
}
// FLASH_ProgramWord(MemLocations[TransferType]+4,++Next_Packet);//+Count,Data);
} else {
DeviceState = Last_operation_failed;
Aditionals = (uint32_t) Command;
}
}
break;
case Req_Capabilities:
Buffer[0] = 0x01;
Buffer[1] = Rep_Capabilities;
if (Data0 == 0) {
Buffer[2] = 0;
Buffer[3] = 0;
Buffer[4] = 0;
Buffer[5] = 0;
Buffer[6] = 0;
Buffer[7] = numberOfDevices;
uint16_t WRFlags = 0;
for (int x = 0; x < numberOfDevices; ++x) {
WRFlags = ((devicesTable[x].readWriteFlags << (x * 2)) | WRFlags);
}
Buffer[8] = WRFlags >> 8;
Buffer[9] = WRFlags;
} else {
Buffer[2] = devicesTable[Data0-1].sizeOfCode >> 24;
Buffer[3] = devicesTable[Data0-1].sizeOfCode >> 16;
Buffer[4] = devicesTable[Data0-1].sizeOfCode >> 8;
Buffer[5] = devicesTable[Data0-1].sizeOfCode;
Buffer[6] = Data0;
Buffer[7] = devicesTable[Data0-1].sizeOfHash;
Buffer[8] = devicesTable[Data0-1].sizeOfDescription;
Buffer[9] = devicesTable[Data0-1].devID;
}
USB_SIL_Write(EP1_IN, (uint8_t*) Buffer, 64);
SetEPTxValid(ENDP1);
break;
case Rep_Capabilities:
break;
case JumpFW:
FLASH_Lock();
JumpToApp = 1;
break;
case Reset:
Reset_Device();
break;
case Abort_Operation:
Next_Packet=0;
DeviceState=DFUidle;
break;
case Op_END:
if (DeviceState == uploading) {
if (Next_Packet - 1 == SizeOfTransfer) {
Next_Packet=0;
DeviceState = Last_operation_Success;
}
if (Next_Packet - 1 < SizeOfTransfer) {
Next_Packet=0;
DeviceState = too_few_packets;
}
}
break;
case Download_Req:
if (DeviceState == DFUidle) {
downType = Data0;
downPacketTotal = Count;
downSizeOfLastPacket = Data1;
if (isBiggerThanAvailable(downType, (downPacketTotal - 1) * 14
+ downSizeOfLastPacket) == 1) {
DeviceState = outsideDevCapabilities;
Aditionals = (uint32_t) Command;
} else
downPacketCurrent=0;
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[5] = 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, 64);
SetEPTxValid(ENDP1);
if (DeviceState == Last_operation_Success) {
DeviceState = DFUidle;
}
break;
case Status_Rep:
break;
}
if (EchoReqFlag == 1) {
echoBuffer[1] = echoBuffer[1] | EchoAnsFlag;
USB_SIL_Write(EP1_IN, (uint8_t*) echoBuffer, 64);
SetEPTxValid(ENDP1);
}
return;
}
void OPDfuIni(void) {
Device dev;
dev.programmingType = Self_flash;
dev.readWriteFlags = (board_can_read | (board_can_write << 1));
dev.startOfUserCode = StartOfUserCode;
dev.sizeOfCode = SizeOfCode;
dev.sizeOfDescription = SizeOfDescription;
dev.sizeOfHash = SizeOfHash;
dev.devID = deviceID;
numberOfDevices = 1;
devicesTable[0] = dev;
//TODO check other devices trough spi or whatever
}
uint32_t baseOfAdressType(DFUTransfer type) {
switch (type) {
case FW:
return currentDevice.startOfUserCode;
break;
case Hash:
return currentDevice.startOfUserCode + currentDevice.sizeOfCode;
break;
case Descript:
return currentDevice.startOfUserCode + currentDevice.sizeOfCode
+ currentDevice.sizeOfHash;
;
break;
default:
return 0;
}
}
uint8_t isBiggerThanAvailable(DFUTransfer type, uint32_t size) {
switch (type) {
case FW:
return (size > currentDevice.sizeOfCode) ? 1 : 0;
break;
case Hash:
return (size > currentDevice.sizeOfHash) ? 1 : 0;
break;
case Descript:
return (size > currentDevice.sizeOfDescription) ? 1 : 0;
break;
default:
return TRUE;
}
}

View File

@ -1,391 +0,0 @@
/**
******************************************************************************
* @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

@ -1,315 +0,0 @@
/******************** (C) COPYRIGHT 2010 STMicroelectronics ********************
* File Name : stm32f10x_it.c
* Author : MCD Application Team
* Version : V3.2.1
* Date : 07/05/2010
* Description : Main Interrupt Service Routines.
* This file provides template for all exceptions handler
* and peripherals interrupt service routine.
********************************************************************************
* 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_it.h"
#include "usb_lib.h"
#include "usb_istr.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 ---------------------------------------------------------*/
/******************************************************************************/
/* Cortex-M3 Processor Exceptions Handlers */
/******************************************************************************/
/*******************************************************************************
* Function Name : NMI_Handler
* Description : This function handles NMI exception.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void NMI_Handler(void)
{
}
/*******************************************************************************
* Function Name : HardFault_Handler
* Description : This function handles Hard Fault exception.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void HardFault_Handler(void)
{
/* Go to infinite loop when Hard Fault exception occurs */
while (1)
{
}
}
/*******************************************************************************
* Function Name : MemManage_Handler
* Description : This function handles Memory Manage exception.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void MemManage_Handler(void)
{
/* Go to infinite loop when Memory Manage exception occurs */
while (1)
{
}
}
/*******************************************************************************
* Function Name : BusFault_Handler
* Description : This function handles Bus Fault exception.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void BusFault_Handler(void)
{
/* Go to infinite loop when Bus Fault exception occurs */
while (1)
{
}
}
/*******************************************************************************
* Function Name : UsageFault_Handler
* Description : This function handles Usage Fault exception.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void UsageFault_Handler(void)
{
/* Go to infinite loop when Usage Fault exception occurs */
while (1)
{
}
}
/*******************************************************************************
* Function Name : SVC_Handler
* Description : This function handles SVCall exception.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void SVC_Handler(void)
{
}
/*******************************************************************************
* Function Name : DebugMon_Handler
* Description : This function handles Debug Monitor exception.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void DebugMon_Handler(void)
{
}
/*******************************************************************************
* Function Name : PendSV_Handler
* Description : This function handles PendSVC exception.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void PendSV_Handler(void)
{
}
/*******************************************************************************
* Function Name : SysTick_Handler
* Description : This function handles SysTick Handler.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void SysTick_Handler(void)
{
}
/******************************************************************************/
/* STM32F10x Peripherals Interrupt Handlers */
/******************************************************************************/
#ifndef STM32F10X_CL
/*******************************************************************************
* Function Name : USB_LP_CAN1_RX0_IRQHandler
* Description : This function handles USB Low Priority or CAN RX0 interrupts
* requests.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void USB_LP_CAN1_RX0_IRQHandler(void)
{
USB_Istr();
}
#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
* Description : This function handles USB-On-The-Go FS global interrupt request.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void OTG_FS_IRQHandler(void)
{
STM32_PCD_OTG_ISR_Handler();
}
#endif /* STM32F10X_CL */
/******************************************************************************/
/* STM32F10x Peripherals Interrupt Handlers */
/* Add here the Interrupt Handler for the used peripheral(s) (PPP), for the */
/* available peripheral interrupt handler's name please refer to the startup */
/* file (startup_stm32f10x_xx.s). */
/******************************************************************************/
/*******************************************************************************
* Function Name : PPP_IRQHandler
* Description : This function handles PPP interrupt request.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
/*void PPP_IRQHandler(void)
{
}*/
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -1,75 +0,0 @@
/////////////////////////////////////////////////////////////////////////////
// Include files
/////////////////////////////////////////////////////////////////////////////
#include "stm32_eval.h"
#include "stm32f10x_tim.h"
/////////////////////////////////////////////////////////////////////////////
// Local definitions
/////////////////////////////////////////////////////////////////////////////
#define STOPWATCH_TIMER_BASE TIM6
#define STOPWATCH_TIMER_RCC RCC_APB1Periph_TIM6
uint32_t STOPWATCH_Init(u32 resolution)
{
// enable timer clock
if( STOPWATCH_TIMER_RCC == RCC_APB2Periph_TIM1 || STOPWATCH_TIMER_RCC == RCC_APB2Periph_TIM8 )
RCC_APB2PeriphClockCmd(STOPWATCH_TIMER_RCC, ENABLE);
else
RCC_APB1PeriphClockCmd(STOPWATCH_TIMER_RCC, ENABLE);
// time base configuration
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
TIM_TimeBaseStructure.TIM_Period = 0xffff; // max period
TIM_TimeBaseStructure.TIM_Prescaler = (72 * resolution)-1; // <resolution> uS accuracy @ 72 MHz
TIM_TimeBaseStructure.TIM_ClockDivision = 0;
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
TIM_TimeBaseInit(STOPWATCH_TIMER_BASE, &TIM_TimeBaseStructure);
// enable interrupt request
TIM_ITConfig(STOPWATCH_TIMER_BASE, TIM_IT_Update, ENABLE);
// start counter
TIM_Cmd(STOPWATCH_TIMER_BASE, ENABLE);
return 0; // no error
}
/////////////////////////////////////////////////////////////////////////////
//! Resets the stopwatch
//! \return < 0 on errors
/////////////////////////////////////////////////////////////////////////////
uint32_t STOPWATCH_Reset(void)
{
// reset counter
STOPWATCH_TIMER_BASE->CNT = 1; // set to 1 instead of 0 to avoid new IRQ request
TIM_ClearITPendingBit(STOPWATCH_TIMER_BASE, TIM_IT_Update);
return 0; // no error
}
/////////////////////////////////////////////////////////////////////////////
//! Returns current value of stopwatch
//! \return 1..65535: valid stopwatch value
//! \return 0xffffffff: counter overrun
/////////////////////////////////////////////////////////////////////////////
uint32_t STOPWATCH_ValueGet(void)
{
uint32_t value = STOPWATCH_TIMER_BASE->CNT;
if( TIM_GetITStatus(STOPWATCH_TIMER_BASE, TIM_IT_Update) != RESET )
value = 0xffffffff;
return value;
}

View File

@ -1,188 +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 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"
#include <stdio.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: Configuration 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,
0x03, /* 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,
0x01, /* 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, 63, /* 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, 63, /* 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

@ -1,52 +0,0 @@
/******************** (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"
#include "op_dfu.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
uint8_t Receive_Buffer[64];
/*******************************************************************************
* Function Name : EP1_OUT_Callback.
* Description : EP1 OUT Callback Routine.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void EP1_OUT_Callback(void)
{
USB_SIL_Read(EP1_OUT, Receive_Buffer);
processComand(Receive_Buffer+1);
SetEPRxStatus(ENDP1, EP_RX_VALID);
}
void EP1_IN_Callback(void)
{
DataDownload(keepgoing);
}
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -1,383 +0,0 @@
/******************** (C) COPYRIGHT 2010 STMicroelectronics ********************
* File Name : usb_istr.c
* Author : MCD Application Team
* Version : V3.2.1
* Date : 07/05/2010
* Description : ISTR events interrupt service 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 "usb_lib.h"
#include "usb_prop.h"
#include "usb_pwr.h"
#include "usb_istr.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
__IO uint16_t wIstr; /* ISTR register last read value */
__IO uint8_t bIntPackSOF = 0; /* SOFs received between 2 consecutive packets */
/* Extern variables ----------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/* function pointers to non-control endpoints service routines */
void (*pEpInt_IN[7])(void) =
{
EP1_IN_Callback,
EP2_IN_Callback,
EP3_IN_Callback,
EP4_IN_Callback,
EP5_IN_Callback,
EP6_IN_Callback,
EP7_IN_Callback,
};
void (*pEpInt_OUT[7])(void) =
{
EP1_OUT_Callback,
EP2_OUT_Callback,
EP3_OUT_Callback,
EP4_OUT_Callback,
EP5_OUT_Callback,
EP6_OUT_Callback,
EP7_OUT_Callback,
};
#ifndef STM32F10X_CL
/*******************************************************************************
* Function Name : USB_Istr
* Description : STR events interrupt service routine
* Input :
* Output :
* Return :
*******************************************************************************/
void USB_Istr(void)
{
wIstr = _GetISTR();
#if (IMR_MSK & ISTR_CTR)
if (wIstr & ISTR_CTR & wInterrupt_Mask)
{
/* servicing of the endpoint correct transfer interrupt */
/* clear of the CTR flag into the sub */
CTR_LP();
#ifdef CTR_CALLBACK
CTR_Callback();
#endif
}
#endif
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
#if (IMR_MSK & ISTR_RESET)
if (wIstr & ISTR_RESET & wInterrupt_Mask)
{
_SetISTR((uint16_t)CLR_RESET);
Device_Property.Reset();
#ifdef RESET_CALLBACK
RESET_Callback();
#endif
}
#endif
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
#if (IMR_MSK & ISTR_DOVR)
if (wIstr & ISTR_DOVR & wInterrupt_Mask)
{
_SetISTR((uint16_t)CLR_DOVR);
#ifdef DOVR_CALLBACK
DOVR_Callback();
#endif
}
#endif
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
#if (IMR_MSK & ISTR_ERR)
if (wIstr & ISTR_ERR & wInterrupt_Mask)
{
_SetISTR((uint16_t)CLR_ERR);
#ifdef ERR_CALLBACK
ERR_Callback();
#endif
}
#endif
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
#if (IMR_MSK & ISTR_WKUP)
if (wIstr & ISTR_WKUP & wInterrupt_Mask)
{
_SetISTR((uint16_t)CLR_WKUP);
Resume(RESUME_EXTERNAL);
#ifdef WKUP_CALLBACK
WKUP_Callback();
#endif
}
#endif
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
#if (IMR_MSK & ISTR_SUSP)
if (wIstr & ISTR_SUSP & wInterrupt_Mask)
{
/* check if SUSPEND is possible */
if (fSuspendEnabled)
{
Suspend();
}
else
{
/* if not possible then resume after xx ms */
Resume(RESUME_LATER);
}
/* clear of the ISTR bit must be done after setting of CNTR_FSUSP */
_SetISTR((uint16_t)CLR_SUSP);
#ifdef SUSP_CALLBACK
SUSP_Callback();
#endif
}
#endif
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
#if (IMR_MSK & ISTR_SOF)
if (wIstr & ISTR_SOF & wInterrupt_Mask)
{
_SetISTR((uint16_t)CLR_SOF);
bIntPackSOF++;
#ifdef SOF_CALLBACK
SOF_Callback();
#endif
}
#endif
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
#if (IMR_MSK & ISTR_ESOF)
if (wIstr & ISTR_ESOF & wInterrupt_Mask)
{
_SetISTR((uint16_t)CLR_ESOF);
/* resume handling timing is made with ESOFs */
Resume(RESUME_ESOF); /* request without change of the machine state */
#ifdef ESOF_CALLBACK
ESOF_Callback();
#endif
}
#endif
} /* USB_Istr */
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
#else /* STM32F10X_CL */
/*******************************************************************************
* Function Name : STM32_PCD_OTG_ISR_Handler
* Description : Handles all USB Device Interrupts
* Input : None
* Output : None
* Return : status
*******************************************************************************/
u32 STM32_PCD_OTG_ISR_Handler (void)
{
USB_OTG_GINTSTS_TypeDef gintr_status;
u32 retval = 0;
if (USBD_FS_IsDeviceMode()) /* ensure that we are in device mode */
{
gintr_status.d32 = OTGD_FS_ReadCoreItr();
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
/* If there is no interrupt pending exit the interrupt routine */
if (!gintr_status.d32)
{
return 0;
}
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
/* Early Suspend interrupt */
#ifdef INTR_ERLYSUSPEND
if (gintr_status.b.erlysuspend)
{
retval |= OTGD_FS_Handle_EarlySuspend_ISR();
}
#endif /* INTR_ERLYSUSPEND */
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
/* End of Periodic Frame interrupt */
#ifdef INTR_EOPFRAME
if (gintr_status.b.eopframe)
{
retval |= OTGD_FS_Handle_EOPF_ISR();
}
#endif /* INTR_EOPFRAME */
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
/* Non Periodic Tx FIFO Emty interrupt */
#ifdef INTR_NPTXFEMPTY
if (gintr_status.b.nptxfempty)
{
retval |= OTGD_FS_Handle_NPTxFE_ISR();
}
#endif /* INTR_NPTXFEMPTY */
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
/* Wakeup or RemoteWakeup interrupt */
#ifdef INTR_WKUPINTR
if (gintr_status.b.wkupintr)
{
retval |= OTGD_FS_Handle_Wakeup_ISR();
}
#endif /* INTR_WKUPINTR */
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
/* Suspend interrupt */
#ifdef INTR_USBSUSPEND
if (gintr_status.b.usbsuspend)
{
/* check if SUSPEND is possible */
if (fSuspendEnabled)
{
Suspend();
}
else
{
/* if not possible then resume after xx ms */
Resume(RESUME_LATER); /* This case shouldn't happen in OTG Device mode because
there's no ESOF interrupt to increment the ResumeS.bESOFcnt in the Resume state machine */
}
retval |= OTGD_FS_Handle_USBSuspend_ISR();
}
#endif /* INTR_USBSUSPEND */
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
/* Start of Frame interrupt */
#ifdef INTR_SOFINTR
if (gintr_status.b.sofintr)
{
/* Update the frame number variable */
bIntPackSOF++;
retval |= OTGD_FS_Handle_Sof_ISR();
}
#endif /* INTR_SOFINTR */
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
/* Receive FIFO Queue Status Level interrupt */
#ifdef INTR_RXSTSQLVL
if (gintr_status.b.rxstsqlvl)
{
retval |= OTGD_FS_Handle_RxStatusQueueLevel_ISR();
}
#endif /* INTR_RXSTSQLVL */
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
/* Enumeration Done interrupt */
#ifdef INTR_ENUMDONE
if (gintr_status.b.enumdone)
{
retval |= OTGD_FS_Handle_EnumDone_ISR();
}
#endif /* INTR_ENUMDONE */
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
/* Reset interrutp */
#ifdef INTR_USBRESET
if (gintr_status.b.usbreset)
{
retval |= OTGD_FS_Handle_UsbReset_ISR();
}
#endif /* INTR_USBRESET */
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
/* IN Endpoint interrupt */
#ifdef INTR_INEPINTR
if (gintr_status.b.inepint)
{
retval |= OTGD_FS_Handle_InEP_ISR();
}
#endif /* INTR_INEPINTR */
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
/* OUT Endpoint interrupt */
#ifdef INTR_OUTEPINTR
if (gintr_status.b.outepintr)
{
retval |= OTGD_FS_Handle_OutEP_ISR();
}
#endif /* INTR_OUTEPINTR */
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
/* Mode Mismatch interrupt */
#ifdef INTR_MODEMISMATCH
if (gintr_status.b.modemismatch)
{
retval |= OTGD_FS_Handle_ModeMismatch_ISR();
}
#endif /* INTR_MODEMISMATCH */
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
/* Global IN Endpoints NAK Effective interrupt */
#ifdef INTR_GINNAKEFF
if (gintr_status.b.ginnakeff)
{
retval |= OTGD_FS_Handle_GInNakEff_ISR();
}
#endif /* INTR_GINNAKEFF */
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
/* Global OUT Endpoints NAK effective interrupt */
#ifdef INTR_GOUTNAKEFF
if (gintr_status.b.goutnakeff)
{
retval |= OTGD_FS_Handle_GOutNakEff_ISR();
}
#endif /* INTR_GOUTNAKEFF */
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
/* Isochrounous Out packet Dropped interrupt */
#ifdef INTR_ISOOUTDROP
if (gintr_status.b.isooutdrop)
{
retval |= OTGD_FS_Handle_IsoOutDrop_ISR();
}
#endif /* INTR_ISOOUTDROP */
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
/* Endpoint Mismatch error interrupt */
#ifdef INTR_EPMISMATCH
if (gintr_status.b.epmismatch)
{
retval |= OTGD_FS_Handle_EPMismatch_ISR();
}
#endif /* INTR_EPMISMATCH */
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
/* Incomplete Isochrous IN tranfer error interrupt */
#ifdef INTR_INCOMPLISOIN
if (gintr_status.b.incomplisoin)
{
retval |= OTGD_FS_Handle_IncomplIsoIn_ISR();
}
#endif /* INTR_INCOMPLISOIN */
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
/* Incomplete Isochrous OUT tranfer error interrupt */
#ifdef INTR_INCOMPLISOOUT
if (gintr_status.b.outepintr)
{
retval |= OTGD_FS_Handle_IncomplIsoOut_ISR();
}
#endif /* INTR_INCOMPLISOOUT */
}
return retval;
}
#endif /* STM32F10X_CL */
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@ -1,425 +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 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, 64);
SetEPRxCount(ENDP1, 64);
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,251 +0,0 @@
/******************** (C) COPYRIGHT 2010 STMicroelectronics ********************
* File Name : usb_pwr.c
* Author : MCD Application Team
* Version : V3.2.1
* Date : 07/05/2010
* Description : Connection/disconnection & power management
********************************************************************************
* 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_pwr.h"
#include "hw_config.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
__IO uint32_t bDeviceState = UNCONNECTED; /* USB device status */
__IO bool fSuspendEnabled = TRUE; /* true when suspend is possible */
struct
{
__IO RESUME_STATE eState;
__IO uint8_t bESOFcnt;
}ResumeS;
/* Extern variables ----------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Extern function prototypes ------------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
* Function Name : PowerOn
* Description :
* Input : None.
* Output : None.
* Return : USB_SUCCESS.
*******************************************************************************/
RESULT PowerOn(void)
{
#ifndef STM32F10X_CL
uint16_t wRegVal;
/*** cable plugged-in ? ***/
USB_Cable_Config(ENABLE);
/*** CNTR_PWDN = 0 ***/
wRegVal = CNTR_FRES;
_SetCNTR(wRegVal);
/*** CNTR_FRES = 0 ***/
wInterrupt_Mask = 0;
_SetCNTR(wInterrupt_Mask);
/*** Clear pending interrupts ***/
_SetISTR(0);
/*** Set interrupt mask ***/
wInterrupt_Mask = CNTR_RESETM | CNTR_SUSPM | CNTR_WKUPM;
_SetCNTR(wInterrupt_Mask);
#endif /* STM32F10X_CL */
return USB_SUCCESS;
}
/*******************************************************************************
* Function Name : PowerOff
* Description : handles switch-off conditions
* Input : None.
* Output : None.
* Return : USB_SUCCESS.
*******************************************************************************/
RESULT PowerOff()
{
#ifndef STM32F10X_CL
/* disable all ints and force USB reset */
_SetCNTR(CNTR_FRES);
/* clear interrupt status register */
_SetISTR(0);
/* Disable the Pull-Up*/
USB_Cable_Config(DISABLE);
/* switch-off device */
_SetCNTR(CNTR_FRES + CNTR_PDWN);
#endif /* STM32F10X_CL */
/* sw variables reset */
/* ... */
return USB_SUCCESS;
}
/*******************************************************************************
* Function Name : Suspend
* Description : sets suspend mode operating conditions
* Input : None.
* Output : None.
* Return : USB_SUCCESS.
*******************************************************************************/
void Suspend(void)
{
#ifndef STM32F10X_CL
uint16_t wCNTR;
/* suspend preparation */
/* ... */
/* macrocell enters suspend mode */
wCNTR = _GetCNTR();
wCNTR |= CNTR_FSUSP;
_SetCNTR(wCNTR);
#endif /* STM32F10X_CL */
/* ------------------ ONLY WITH BUS-POWERED DEVICES ---------------------- */
/* power reduction */
/* ... on connected devices */
#ifndef STM32F10X_CL
/* force low-power mode in the macrocell */
wCNTR = _GetCNTR();
wCNTR |= CNTR_LPMODE;
_SetCNTR(wCNTR);
#endif /* STM32F10X_CL */
/* switch-off the clocks */
/* ... */
Enter_LowPowerMode();
}
/*******************************************************************************
* Function Name : Resume_Init
* Description : Handles wake-up restoring normal operations
* Input : None.
* Output : None.
* Return : USB_SUCCESS.
*******************************************************************************/
void Resume_Init(void)
{
#ifndef STM32F10X_CL
uint16_t wCNTR;
#endif /* STM32F10X_CL */
/* ------------------ ONLY WITH BUS-POWERED DEVICES ---------------------- */
/* restart the clocks */
/* ... */
#ifndef STM32F10X_CL
/* CNTR_LPMODE = 0 */
wCNTR = _GetCNTR();
wCNTR &= (~CNTR_LPMODE);
_SetCNTR(wCNTR);
#endif /* STM32F10X_CL */
/* restore full power */
/* ... on connected devices */
Leave_LowPowerMode();
#ifndef STM32F10X_CL
/* reset FSUSP bit */
_SetCNTR(IMR_MSK);
#endif /* STM32F10X_CL */
/* reverse suspend preparation */
/* ... */
}
/*******************************************************************************
* Function Name : Resume
* Description : This is the state machine handling resume operations and
* timing sequence. The control is based on the Resume structure
* variables and on the ESOF interrupt calling this subroutine
* without changing machine state.
* Input : a state machine value (RESUME_STATE)
* RESUME_ESOF doesn't change ResumeS.eState allowing
* decrementing of the ESOF counter in different states.
* Output : None.
* Return : None.
*******************************************************************************/
void Resume(RESUME_STATE eResumeSetVal)
{
#ifndef STM32F10X_CL
uint16_t wCNTR;
#endif /* STM32F10X_CL */
if (eResumeSetVal != RESUME_ESOF)
ResumeS.eState = eResumeSetVal;
switch (ResumeS.eState)
{
case RESUME_EXTERNAL:
Resume_Init();
ResumeS.eState = RESUME_OFF;
break;
case RESUME_INTERNAL:
Resume_Init();
ResumeS.eState = RESUME_START;
break;
case RESUME_LATER:
ResumeS.bESOFcnt = 2;
ResumeS.eState = RESUME_WAIT;
break;
case RESUME_WAIT:
ResumeS.bESOFcnt--;
if (ResumeS.bESOFcnt == 0)
ResumeS.eState = RESUME_START;
break;
case RESUME_START:
#ifdef STM32F10X_CL
OTGD_FS_SetRemoteWakeup();
#else
wCNTR = _GetCNTR();
wCNTR |= CNTR_RESUME;
_SetCNTR(wCNTR);
#endif /* STM32F10X_CL */
ResumeS.eState = RESUME_ON;
ResumeS.bESOFcnt = 10;
break;
case RESUME_ON:
#ifndef STM32F10X_CL
ResumeS.bESOFcnt--;
if (ResumeS.bESOFcnt == 0)
{
#endif /* STM32F10X_CL */
#ifdef STM32F10X_CL
OTGD_FS_ResetRemoteWakeup();
#else
wCNTR = _GetCNTR();
wCNTR &= (~CNTR_RESUME);
_SetCNTR(wCNTR);
#endif /* STM32F10X_CL */
ResumeS.eState = RESUME_OFF;
#ifndef STM32F10X_CL
}
#endif /* STM32F10X_CL */
break;
case RESUME_OFF:
case RESUME_ESOF:
default:
ResumeS.eState = RESUME_OFF;
break;
}
}
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/