Wrote basic command funcs, acmd41 begun, cmd55, dmainit

This commit is contained in:
Mario Hüttel 2015-10-13 18:39:29 +02:00
parent 9979813693
commit ae9679f10f
10 changed files with 993 additions and 14 deletions

View File

@ -12,7 +12,7 @@
#include <shimatta_sdio-driver.h>
/* Definitions of physical drive number for each drive */
#define SDIO 0 /* Example: Map ATA harddisk to physical drive 0 */
#define SDCARD 0 /* Example: Map ATA harddisk to physical drive 0 */
/*-----------------------------------------------------------------------*/
/* Get Drive Status */
@ -22,7 +22,7 @@ DSTATUS disk_status(BYTE pdrv /* Physical drive number to identify the drive */
) {
switch (pdrv) {
case SDIO:
case SDCARD:
return SDIO_status();
break;
}
@ -38,7 +38,7 @@ DSTATUS disk_initialize(BYTE pdrv /* Physical drive number to identify the drive
switch (pdrv) {
case SDIO:
case SDCARD:
return SDIO_initialize();
break;
}
@ -56,7 +56,7 @@ UINT count /* Number of sectors to read */
) {
switch (pdrv) {
case SDIO:
case SDCARD:
return SDIO_disk_read(buff, sector, count);
break;
}
@ -75,7 +75,7 @@ DWORD sector, /* Sector address in LBA */
UINT count /* Number of sectors to write */
) {
switch (pdrv) {
case SDIO:
case SDCARD:
return SDIO_disk_write(buff, sector, count);
break;
}
@ -94,7 +94,7 @@ void *buff /* Buffer to send/receive control data */
) {
switch (pdrv) {
case SDIO:
case SDCARD:
return SDIO_disk_ioctl(cmd, buff);
break;
}

View File

@ -2654,7 +2654,6 @@ FRESULT f_write (
const BYTE *wbuff = (const BYTE*)buff;
BYTE csect;
*bw = 0; /* Clear write byte counter */
res = validate(fp); /* Check validity */

View File

@ -33,7 +33,7 @@
/ 3: f_lseek() function is removed in addition to 2. */
#define _USE_STRFUNC 0
#define _USE_STRFUNC 1
/* This option switches string functions, f_gets(), f_putc(), f_puts() and
/ f_printf().
/
@ -145,8 +145,8 @@
/* Number of volumes (logical drives) to be used. */
#define _STR_VOLUME_ID 0
#define _VOLUME_STRS "RAM","NAND","CF","SD1","SD2","USB1","USB2","USB3"
#define _STR_VOLUME_ID 1
#define _VOLUME_STRS "SD"
/* _STR_VOLUME_ID option switches string volume ID feature.
/ When _STR_VOLUME_ID is set to 1, also pre-defined strings can be used as drive
/ number in the path name. _VOLUME_STRS defines the drive ID strings for each

View File

@ -2,21 +2,56 @@
* shimatta_sdio-driver.c
*
* Created on: Apr 30, 2015
* Author: mari
* Mario Hüttel
*/
#include <shimatta_sdio-driver.h>
#define SETAF(PORT,PIN,AF) PORT->AFR[(PIN < 8 ? 0 : 1)] |= AF << ((PIN < 8 ? PIN : (PIN - 8)) * 4)
#define READCTRL ((BLOCKSIZE << 4) | SDIO_DCTRL_DMAEN)
#define DMAP2M (DMA_SxCR_CHSEL_2 | DMA_SxCR_PBURST_0 | DMA_SxCR_MBURST_0 | DMA_SxCR_MSIZE_1 | DMA_SxCR_PSIZE_1 | DMA_SxCR_MINC | DMA_SxCR_PFCTRL)
#define DMAM2P (DMA_SxCR_CHSEL_2 | DMA_SxCR_PBURST_0 | DMA_SxCR_MBURST_0 | DMA_SxCR_MSIZE_1 | DMA_SxCR_PSIZE_1 | DMA_SxCR_MINC | DMA_SxCR_PFCTRL | DMA_SxCR_DIR_0)
#define SHORT_ANS 1
#define LONG_ANS 3
#define NO_ANS 0
#define CCRCFAIL -1
#define CTIMEOUT -2
void SDIO_DMA_Init();
void SDIO_InitModule();
int SDIO_sendCmd(uint8_t CMD, uint32_t arg, uint8_t expectedAns);
int SDIO_getResp(uint8_t expectedCMD, uint8_t typeOfAns, uint32_t* responseBuffer);
int SDIO_parseR1Ans(uint32_t resp, StatusConv_t converter);
int SDIO_send_ACMD41();
int SDIO_send_CMD55();
//BYTE rxtxbuffer[1<<BLOCKSIZE]; //Data RX and TX Buffer not needed anymore. thanks to DMA
SDInfo_t cardInfo;
DSTATUS SDIO_status(){
return 0;
}
DSTATUS SDIO_initialize(){
cardInfo.rca = 0;
cardInfo.type = CARD_NONE;
SDIO_DMA_Init();
SDIO_InitModule();
return 0;
}
DRESULT SDIO_disk_read(BYTE *buff, DWORD sector, UINT count){
return RES_OK;
}
DRESULT SDIO_disk_write(BYTE *buff, DWORD sector, UINT count){
DRESULT SDIO_disk_write(const BYTE *buff, DWORD sector, UINT count){
return RES_OK;
}
DRESULT SDIO_disk_ioctl(BYTE cmd, void* buff){
@ -25,3 +60,133 @@ DRESULT SDIO_disk_ioctl(BYTE cmd, void* buff){
DWORD __attribute__((weak)) get_fattime(){
return 0;
}
void SDIO_DMA_Init(){
RCC->AHB1ENR |= RCC_AHB1ENR_DMA2EN;
DMASTREAM->CR = DMAM2P;
//Address Conffiguration
//Memory address is set by write and read block functions
//DMASTREAM->M0AR = (uint32_t)&rxtxbuffer;
DMASTREAM->PAR = (uint32_t)&SDIO->FIFO; //Not sure if this works
//DMASTREAM->CR |= DMA_SxCR_EN;
}
void SDIO_InitModule(){
//Init Clocks
RCC->AHB1ENR |= PORTCLKMASK;
RCC->APB2ENR |= RCC_APB2ENR_SDIOEN;
//Init Alternate Functions
CLKPORT->MODER |= (2<<CLKPIN*2);
D0PORT->MODER |= (2<<D0PIN*2);
#if BUSWIDTH==1
D1PORT->MODER |= (2<<D1PIN*2);
D2PORT->MODER |= (2<<D2PIN*2);
D3PORT->MODER |= (2<<D3PIN*2);
#endif
//CLKPORT->AFR[(CLKPIN < 8 ? 0 : 1)] |= ALTFUNC << ((CLKPIN < 8 ? CLKPIN : (CLKPIN - 8)) * 4);
SETAF(CLKPORT, CLKPIN, ALTFUNC);
SETAF(D0PORT, D0PIN, ALTFUNC);
#if BUSWIDTH==1
SETAF(D1PORT, D1PIN, ALTFUNC);
SETAF(D2PORT, D2PIN, ALTFUNC);
SETAF(D3PORT, D3PIN, ALTFUNC);
#endif
//Init Module
//Set CLK Control Register
SDIO->CLKCR = (HW_FLOW<<14) | (BUSWIDTH<<11) | SDIO_CLKCR_CLKEN | (INITCLK & SDIO_CLKCR_CLKDIV);
//Set Data Timeout
SDIO->DTIMER = DTIMEOUT;
//Set Data Parameters
//SDIO->DCTRL = (BLOCKSIZE << 4) | SDIO_DCTRL_DMAEN;
//Set Power Register: Power up Card CLK
SDIO->POWER = SDIO_POWER_PWRCTRL_0 | SDIO_POWER_PWRCTRL_1;
}
int SDIO_parseR1Ans(uint32_t resp, StatusConv_t converter){
statusConverter.value = resp;
return 0;
}
//Send Command
//Clear respone Flags
//->CRC Fail, complete response, Timeout
int SDIO_sendCmd(uint8_t CMD, uint32_t arg, uint8_t expectedAns){
//Clear Flags
SDIO->ICR = SDIO_ICR_CCRCFAILC | SDIO_ICR_CMDRENDC | SDIO_ICR_CTIMEOUTC;
//Send command
SDIO->ARG = arg;
SDIO->CMD = (CMD & SDIO_CMD_CMDINDEX) | SDIO_CMD_CPSMEN | SDIO_CMD_WAITPEND | ((expectedAns << 6) & SDIO_CMD_WAITRESP);
return 0;
}
int SDIO_getResp(uint8_t expectedCMD, uint8_t typeOfAns, uint32_t *responseBuffer) {
//Return with success because no data is needed
if (typeOfAns == NO_ANS) return 0;
//Wait for error or success
while (1) {
if (SDIO->STA & SDIO_STA_CMDREND) break; //Corrct Respone Received
//Exclude 41 from valid CRC check
if ((SDIO->STA & SDIO_STA_CCRCFAIL)) {
if(expectedCMD == 41) {
//This command does not have a CRC...Doushite....
break;//Hopefully the response is correct. Even without CRC....
}
}
if (SDIO->STA & SDIO_STA_CTIMEOUT)
return CTIMEOUT;
}
//Valid Respone Received
if ((SDIO->RESPCMD & SDIO_RESPCMD_RESPCMD) != expectedCMD) return -1; //Not the expected respose
//Correct Response
*(responseBuffer++) = SDIO->RESP1;
//Long response. Never needed with SD Cards
if (typeOfAns == LONG_ANS) {
*(responseBuffer++) = SDIO->RESP2;
*(responseBuffer++) = SDIO->RESP3;
*(responseBuffer++) = SDIO->RESP4;
}
}
int SDIO_send_CMD55(){
int retry = 0x20;
StatusConv_t converter;
uint32_t response;
do {
//Execute Command and check for valid response
SDIO_sendCmd(55, cardInfo.rca, SHORT_ANS);
if (!SDIO_getResp(55, SHORT_ANS, &response))
{
//Response valid. Check if Card has accepted switch to application command mode
converter.value = response;
if (converter.statusstruct.APP_CMD == 1)
return 0;
}
}while(--retry > 0);
return -1;
}
int SDIO_send_ACMD41(){
int retry = 0x200;
if (SDIO_send_CMD55()) return -1;
do {
SDIO_sendCmd(41, 1<<30, SHORT_ANS);
//TODO: Implement Response Check...
}while(--retry > 0);
}

View File

@ -2,19 +2,114 @@
* shimatta_sdio-driver.h
*
* Created on: Apr 26, 2015
* Author: mari
* Mario Hüttel
*/
#ifndef FATFS_SHIMATTA_SDIO_DRIVER_SHIMATTA_SDIO_DRIVER_H_
#define FATFS_SHIMATTA_SDIO_DRIVER_SHIMATTA_SDIO_DRIVER_H_
#include <diskio.h>
#include <stm32f4xx.h>
DSTATUS SDIO_status();
DSTATUS SDIO_initialize();
DRESULT SDIO_disk_read(BYTE *buff, DWORD sector, UINT count);
DRESULT SDIO_disk_write(BYTE *buff, DWORD sector, UINT count);
DRESULT SDIO_disk_write(const BYTE *buff, DWORD sector, UINT count);
DRESULT SDIO_disk_ioctl(BYTE cmd, void* buff);
DWORD get_fattime();
#define CURRENT_STATE_IDLE 0
#define CURRENT_STATE_READY 1
#define CURRENT_STATE_IDENT 2
#define CURRENT_STATE_STBY 3
#define CURRENT_STATE_TRAN 4
#define CURRENT_STATE_DATA 5
#define CURRENT_STATE_RCV 6
#define CURRENT_STATE_PRG 7
#define CURRENT_STATE_DIS 8
typedef struct _CardStatus {
uint32_t reserved : 3;
uint32_t AKE_SEQ_ERROR : 1;
uint32_t reserved_2 : 1;
uint32_t APP_CMD : 1;
uint32_t reserved_3 : 2;
uint32_t READY_FOR_DATA : 1;
uint32_t CURRENT_STATE : 4;
uint32_t ERASE_RESET : 1;
uint32_t CARD_ECC_DIABLED : 1;
uint32_t WP_ERASE_SKIP : 1;
uint32_t CSD_OVERWRITE : 1;
uint32_t reserved17 : 1;
uint32_t reserved18 : 1;
uint32_t ERROR : 1;
uint32_t CC_ERROR : 1;
uint32_t CARD_ECC_FAILED : 1;
uint32_t ILLEGAL_COMMAND : 1;
uint32_t COM_CRC_ERROR : 1;
uint32_t LOCK_UNLOCK_FAILED : 1;
uint32_t CARD_IS_LOCKED : 1;
uint32_t WP_VIOLATION : 1;
uint32_t ERASE_PARAM : 1;
uint32_t ERASE_SEQ_ERROR : 1;
uint32_t BLOCK_LEN_ERROR : 1;
uint32_t ADDRESS_ERROR : 1;
uint32_t OUT_OF_RANGE : 1;
}CardStatus_t;
#define CARD_SD 1
#define CARD_MMC 2//Never use. MMC not supported
#define CARD_NONE 0
typedef struct _SDInfo {
uint32_t rca;
uint8_t type;
}SDInfo_t
typedef union _StatusConv {
CardStatus_t statusstruct;
uint32_t value;
}StatusConv_t;
//General Definitions
//Blocksize: 512 = 2^9 => 9
#define BLOCKSIZE 9 //9
//Hardware Flow: Prevents over- and underruns.
#define HW_FLOW 0 //0
//1 bit: 0
//4 bit: 1
#define BUSWIDTH 1 //1
//Initial Transfer CLK (ca. 400kHz)
#define INITCLK 120 //120
//Working CLK (Maximum)
#define WORKCLK 0 //0
//Data Timeout in CLK Cycles
#define DTIMEOUT 150 //150
//DMA Stream used for TX and RX DMA2 Stream 3 or 6 possible
#define DMASTREAM DMA2_Stream3
//Port Definitions
#define PORTCLKMASK (RCC_AHB1ENR_GPIODEN | RCC_AHB1ENR_GPIOCEN)
#define ALTFUNC 12
#define CLKPORT GPIOC
#define D0PORT GPIOC
#define D1PORT GPIOC
#define D2PORT GPIOC
#define D3PORT GPIOC
#define CMDPORT GPIOD
#define CLKPIN 12
#define D0PIN 8
#define D1PIN 9
#define D2PIN 10
#define D3PIN 11
#define CMDPIN 2
#endif /* FATFS_SHIMATTA_SDIO_DRIVER_SHIMATTA_SDIO_DRIVER_H_ */

82
Makefile Normal file
View File

@ -0,0 +1,82 @@
################################Shimatta Makefile####################################
#CPU: STM32F407VGT6
#Compiler: arm-none-eabi
#####################################################################################
#Add Files and Folders below#########################################################
CFILES = main.c syscalls.c UART/uart.c cmsis_boot/system_stm32f4xx.c
ASFILES = boot/startup_stm32f4xx.S
INCLUDEPATH = -Iboot -Imathlib -Icmsis -Icmsis_boot -IUART
target = stm32f4sdio
LIBRARYPATH = -L. -Lmathlib
LIBRARIES = -larm_cortexM4lf_math
DEFINES = -DSTM32F407xx -DSTM32F4XX -DARM_MATH_CM4
mapfile = qttemplate
##Custom Files###
#TODO
CFILES += FATFS/option/syscall.c FATFS/option/ccsbcs.c FATFS/diskio.c FATFS/ff.c FATFS/shimatta_sdio_driver/shimatta_sdio-driver.c
INCLUDEPATH += -IFATFS -IFATFS/shimatta_sdio_driver
###################################################################################
CC=arm-none-eabi-gcc
OBJCOPY=arm-none-eabi-objcopy
LFLAGS = -mlittle-endian -mthumb -mcpu=cortex-m4 -mthumb-interwork
LFLAGS += -mfloat-abi=hard -mfpu=fpv4-sp-d16 --disable-newlib-supplied-syscalls -nostartfiles
LFLAGS += -Tstm32f407vgt6_flash.ld -Wl,-Map=$(mapfile).map
CFLAGS = -c -fmessage-length=0 -mlittle-endian -mthumb -mcpu=cortex-m4 -mthumb-interwork
CFLAGS += -mfloat-abi=hard -mfpu=fpv4-sp-d16 -nostartfiles
####################################################################################
OBJ = $(CFILES:%.c=%.o)
OBJ += $(ASFILES:%.S=%.o)
default: $(target).elf
%.bin: %.elf
$(OBJCOPY) -O binary $^ $@
%.hex: %.elf
$(OBJCOPY) -O ihex $^ $@
#Linking
$(target).elf: $(OBJ)
$(CC) $(LFLAGS) $(LIBRARYPATH) -o $@ $^ $(LIBRARIES)
#Compiling
%.o: %.c
$(CC) $(CFLAGS) $(INCLUDEPATH) $(DEFINES) -o $@ $<
.PHONY: qtproject clean mrproper objcopy
objcopy: $(target).bin $(target).hex
mrproper:
rm -f $(target).pro
clean:
rm -f $(target).elf $(target).bin $(target).hex $(OBJ) $(mapfile).map
qtproject:
echo -e "TEMPLATE = app\nCONFIG -= console app_bundle qt" > $(target).pro
echo -e "SOURCES += $(CFILES) $(ASFILES)" >> $(target).pro
echo -ne "INCLUDEPATH += " >> $(target).pro
echo "$(INCLUDEPATH)" | sed "s!-I!./!g" >> $(target).pro
echo -ne "HEADERS += " >> $(target).pro
find -name "*.h" | tr "\\n" " " >> $(target).pro
echo -ne "\nDEFINES += " >> $(target).pro
echo "$(DEFINES)" | sed "s/-D//g" >> $(target).pro

373
qttemplate.map Normal file
View File

@ -0,0 +1,373 @@
Allocating common symbols
Common symbol size file
file 0x224 main.o
SDfs 0x230 main.o
Memory Configuration
Name Origin Length Attributes
FLASH 0x0000000008000000 0x0000000000100000 xr
RAM 0x0000000020000000 0x0000000000020000 xrw
CCM 0x0000000010000000 0x0000000000010000 xrw
MEMORY_B1 0x0000000060000000 0x0000000000000000 xr
*default* 0x0000000000000000 0xffffffffffffffff
Linker script and memory map
LOAD main.o
LOAD syscalls.o
LOAD UART/uart.o
LOAD cmsis_boot/system_stm32f4xx.o
LOAD FATFS/option/syscall.o
LOAD FATFS/option/ccsbcs.o
LOAD FATFS/diskio.o
LOAD FATFS/ff.o
LOAD FATFS/shimatta_sdio_driver/shimatta_sdio-driver.o
LOAD boot/startup_stm32f4xx.o
LOAD mathlib/libarm_cortexM4lf_math.a
START GROUP
LOAD /usr/lib/gcc/arm-none-eabi/5.2.0/armv7e-m/fpu/libgcc.a
LOAD /usr/lib/gcc/arm-none-eabi/5.2.0/../../../../arm-none-eabi/lib/armv7e-m/fpu/libc.a
END GROUP
0x0000000020020000 _estack = 0x20020000
0x0000000000000000 _Min_Heap_Size = 0x0
0x0000000000000400 _Min_Stack_Size = 0x400
.isr_vector 0x0000000008000000 0x188
0x0000000008000000 . = ALIGN (0x4)
*(.isr_vector)
.isr_vector 0x0000000008000000 0x188 boot/startup_stm32f4xx.o
0x0000000008000000 g_pfnVectors
0x0000000008000188 . = ALIGN (0x4)
.text 0x0000000008000188 0x4ef4
0x0000000008000188 . = ALIGN (0x4)
*(.text)
.text 0x0000000008000188 0xe8 main.o
0x0000000008000220 main
0x0000000008000250 SysTick_Handler
.text 0x0000000008000270 0xec syscalls.o
0x0000000008000270 _sbrk
0x00000000080002c4 _isatty
0x00000000080002dc _close
0x00000000080002f4 _open
0x000000000800030c _fstat
0x000000000800031c _lseek
0x000000000800032c _read
0x000000000800033c _write
.text 0x000000000800035c 0xf8 UART/uart.o
0x000000000800035c initUART
0x00000000080003dc sendChar
0x000000000800040c sendString
.text 0x0000000008000454 0x260 cmsis_boot/system_stm32f4xx.o
0x0000000008000454 SystemInit
0x00000000080004c0 SystemCoreClockUpdate
.text 0x00000000080006b4 0x0 FATFS/option/syscall.o
.text 0x00000000080006b4 0xd4 FATFS/option/ccsbcs.o
0x00000000080006b4 ff_convert
0x000000000800072c ff_wtoupper
.text 0x0000000008000788 0xd8 FATFS/diskio.o
0x0000000008000788 disk_status
0x00000000080007ac disk_initialize
0x00000000080007d0 disk_read
0x0000000008000800 disk_write
0x0000000008000830 disk_ioctl
.text 0x0000000008000860 0x40d8 FATFS/ff.o
0x0000000008000b7c clust2sect
0x0000000008000bbc get_fat
0x0000000008000d2c put_fat
0x0000000008002b70 f_mount
0x0000000008002bf8 f_open
0x0000000008002e80 f_read
0x00000000080030f0 f_write
0x00000000080033c8 f_sync
0x0000000008003514 f_close
0x000000000800354c f_lseek
0x00000000080037b4 f_opendir
0x0000000008003878 f_closedir
0x00000000080038a0 f_readdir
0x0000000008003930 f_stat
0x00000000080039ac f_getfree
0x0000000008003b34 f_truncate
0x0000000008003c7c f_unlink
0x0000000008003dd4 f_mkdir
0x000000000800401c f_chmod
0x00000000080040d0 f_rename
0x000000000800428c f_utime
0x0000000008004348 f_gets
0x0000000008004428 f_putc
0x0000000008004490 f_puts
0x0000000008004504 f_printf
.text 0x0000000008004938 0x17c FATFS/shimatta_sdio_driver/shimatta_sdio-driver.o
0x0000000008004938 SDIO_status
0x0000000008004948 SDIO_initialize
0x000000000800495c SDIO_disk_read
0x0000000008004978 SDIO_disk_write
0x0000000008004994 SDIO_disk_ioctl
0x00000000080049b0 get_fattime
0x00000000080049c0 SDIO_DMA_Init
0x00000000080049f4 SDIO_InitModule
.text 0x0000000008004ab4 0x14 boot/startup_stm32f4xx.o
*(.text*)
.text.Reset_Handler
0x0000000008004ac8 0x44 boot/startup_stm32f4xx.o
0x0000000008004ac8 Reset_Handler
.text.Default_Handler
0x0000000008004b0c 0x2 boot/startup_stm32f4xx.o
0x0000000008004b0c RTC_Alarm_IRQHandler
0x0000000008004b0c HASH_RNG_IRQHandler
0x0000000008004b0c EXTI2_IRQHandler
0x0000000008004b0c TIM8_CC_IRQHandler
0x0000000008004b0c DebugMon_Handler
0x0000000008004b0c TIM1_CC_IRQHandler
0x0000000008004b0c DMA2_Stream5_IRQHandler
0x0000000008004b0c HardFault_Handler
0x0000000008004b0c DMA1_Stream5_IRQHandler
0x0000000008004b0c PVD_IRQHandler
0x0000000008004b0c SDIO_IRQHandler
0x0000000008004b0c TAMP_STAMP_IRQHandler
0x0000000008004b0c PendSV_Handler
0x0000000008004b0c NMI_Handler
0x0000000008004b0c CAN2_RX1_IRQHandler
0x0000000008004b0c EXTI3_IRQHandler
0x0000000008004b0c TIM8_TRG_COM_TIM14_IRQHandler
0x0000000008004b0c TIM1_UP_TIM10_IRQHandler
0x0000000008004b0c TIM8_UP_TIM13_IRQHandler
0x0000000008004b0c I2C3_ER_IRQHandler
0x0000000008004b0c EXTI0_IRQHandler
0x0000000008004b0c I2C2_EV_IRQHandler
0x0000000008004b0c DMA1_Stream2_IRQHandler
0x0000000008004b0c CAN1_RX0_IRQHandler
0x0000000008004b0c FPU_IRQHandler
0x0000000008004b0c OTG_HS_WKUP_IRQHandler
0x0000000008004b0c UsageFault_Handler
0x0000000008004b0c CAN2_SCE_IRQHandler
0x0000000008004b0c DMA2_Stream2_IRQHandler
0x0000000008004b0c SPI1_IRQHandler
0x0000000008004b0c TIM6_DAC_IRQHandler
0x0000000008004b0c TIM1_BRK_TIM9_IRQHandler
0x0000000008004b0c DCMI_IRQHandler
0x0000000008004b0c CAN2_RX0_IRQHandler
0x0000000008004b0c DMA2_Stream3_IRQHandler
0x0000000008004b0c USART6_IRQHandler
0x0000000008004b0c USART3_IRQHandler
0x0000000008004b0c CRYP_IRQHandler
0x0000000008004b0c CAN1_RX1_IRQHandler
0x0000000008004b0c UART5_IRQHandler
0x0000000008004b0c DMA2_Stream0_IRQHandler
0x0000000008004b0c TIM4_IRQHandler
0x0000000008004b0c I2C1_EV_IRQHandler
0x0000000008004b0c DMA1_Stream6_IRQHandler
0x0000000008004b0c DMA1_Stream1_IRQHandler
0x0000000008004b0c UART4_IRQHandler
0x0000000008004b0c TIM3_IRQHandler
0x0000000008004b0c RCC_IRQHandler
0x0000000008004b0c TIM8_BRK_TIM12_IRQHandler
0x0000000008004b0c Default_Handler
0x0000000008004b0c EXTI15_10_IRQHandler
0x0000000008004b0c ADC_IRQHandler
0x0000000008004b0c DMA1_Stream7_IRQHandler
0x0000000008004b0c TIM7_IRQHandler
0x0000000008004b0c CAN2_TX_IRQHandler
0x0000000008004b0c TIM5_IRQHandler
0x0000000008004b0c DMA2_Stream7_IRQHandler
0x0000000008004b0c I2C3_EV_IRQHandler
0x0000000008004b0c EXTI9_5_IRQHandler
0x0000000008004b0c RTC_WKUP_IRQHandler
0x0000000008004b0c ETH_WKUP_IRQHandler
0x0000000008004b0c SPI2_IRQHandler
0x0000000008004b0c OTG_HS_EP1_IN_IRQHandler
0x0000000008004b0c MemManage_Handler
0x0000000008004b0c DMA1_Stream0_IRQHandler
0x0000000008004b0c CAN1_TX_IRQHandler
0x0000000008004b0c SVC_Handler
0x0000000008004b0c EXTI4_IRQHandler
0x0000000008004b0c FSMC_IRQHandler
0x0000000008004b0c ETH_IRQHandler
0x0000000008004b0c OTG_HS_EP1_OUT_IRQHandler
0x0000000008004b0c WWDG_IRQHandler
0x0000000008004b0c TIM2_IRQHandler
0x0000000008004b0c OTG_FS_WKUP_IRQHandler
0x0000000008004b0c TIM1_TRG_COM_TIM11_IRQHandler
0x0000000008004b0c OTG_HS_IRQHandler
0x0000000008004b0c EXTI1_IRQHandler
0x0000000008004b0c USART2_IRQHandler
0x0000000008004b0c I2C2_ER_IRQHandler
0x0000000008004b0c DMA2_Stream1_IRQHandler
0x0000000008004b0c CAN1_SCE_IRQHandler
0x0000000008004b0c FLASH_IRQHandler
0x0000000008004b0c DMA2_Stream4_IRQHandler
0x0000000008004b0c BusFault_Handler
0x0000000008004b0c USART1_IRQHandler
0x0000000008004b0c OTG_FS_IRQHandler
0x0000000008004b0c SPI3_IRQHandler
0x0000000008004b0c DMA1_Stream4_IRQHandler
0x0000000008004b0c I2C1_ER_IRQHandler
0x0000000008004b0c DMA2_Stream6_IRQHandler
0x0000000008004b0c DMA1_Stream3_IRQHandler
*(.rodata)
*fill* 0x0000000008004b0e 0x2
.rodata 0x0000000008004b10 0x4c0 FATFS/option/ccsbcs.o
.rodata 0x0000000008004fd0 0xac FATFS/ff.o
*(.rodata*)
*(.glue_7)
.glue_7 0x000000000800507c 0x0 linker stubs
*(.glue_7t)
.glue_7t 0x000000000800507c 0x0 linker stubs
*(.eh_frame)
*(.init)
*(.fini)
0x000000000800507c . = ALIGN (0x4)
0x000000000800507c _etext = .
0x000000000800507c _exit = .
.vfp11_veneer 0x000000000800507c 0x0
.vfp11_veneer 0x000000000800507c 0x0 linker stubs
.v4_bx 0x000000000800507c 0x0
.v4_bx 0x000000000800507c 0x0 linker stubs
.iplt 0x000000000800507c 0x0
.iplt 0x000000000800507c 0x0 syscalls.o
.rel.dyn 0x000000000800507c 0x0
.rel.iplt 0x000000000800507c 0x0 syscalls.o
.ARM.extab
*(.ARM.extab* .gnu.linkonce.armextab.*)
.ARM 0x000000000800507c 0x0
0x000000000800507c __exidx_start = .
*(.ARM.exidx*)
0x000000000800507c __exidx_end = .
.preinit_array 0x000000000800507c 0x0
[!provide] PROVIDE (__preinit_array_start, .)
*(.preinit_array*)
[!provide] PROVIDE (__preinit_array_end, .)
.init_array 0x000000000800507c 0x0
[!provide] PROVIDE (__init_array_start, .)
*(SORT(.init_array.*))
*(.init_array*)
[!provide] PROVIDE (__init_array_end, .)
.fini_array 0x000000000800507c 0x0
[!provide] PROVIDE (__fini_array_start, .)
*(.fini_array*)
*(SORT(.fini_array.*))
[!provide] PROVIDE (__fini_array_end, .)
0x000000000800507c _siccmram = LOADADDR (.ccmram)
.ccmram 0x0000000010000000 0x0 load address 0x000000000800507c
0x0000000010000000 . = ALIGN (0x4)
0x0000000010000000 _sccmram = .
*(.ccmram)
*(.ccmram*)
0x0000000010000000 . = ALIGN (0x4)
0x0000000010000000 _eccmram = .
0x000000000800507c _sidata = LOADADDR (.data)
.data 0x0000000020000000 0x14 load address 0x000000000800507c
0x0000000020000000 . = ALIGN (0x4)
0x0000000020000000 _sdata = .
*(.data)
.data 0x0000000020000000 0x0 main.o
.data 0x0000000020000000 0x0 syscalls.o
.data 0x0000000020000000 0x0 UART/uart.o
.data 0x0000000020000000 0x14 cmsis_boot/system_stm32f4xx.o
0x0000000020000000 SystemCoreClock
0x0000000020000004 AHBPrescTable
.data 0x0000000020000014 0x0 FATFS/option/syscall.o
.data 0x0000000020000014 0x0 FATFS/option/ccsbcs.o
.data 0x0000000020000014 0x0 FATFS/diskio.o
.data 0x0000000020000014 0x0 FATFS/ff.o
.data 0x0000000020000014 0x0 FATFS/shimatta_sdio_driver/shimatta_sdio-driver.o
.data 0x0000000020000014 0x0 boot/startup_stm32f4xx.o
*(.data*)
0x0000000020000014 . = ALIGN (0x4)
0x0000000020000014 _edata = .
.igot.plt 0x0000000020000014 0x0 load address 0x0000000008005090
.igot.plt 0x0000000020000014 0x0 syscalls.o
0x0000000020000014 . = ALIGN (0x4)
.bss 0x0000000020000014 0x660 load address 0x0000000008005090
0x0000000020000014 _sbss = .
0x0000000020000014 __bss_start__ = _sbss
*(.bss)
.bss 0x0000000020000014 0x0 main.o
.bss 0x0000000020000014 0x4 syscalls.o
.bss 0x0000000020000018 0x0 UART/uart.o
.bss 0x0000000020000018 0x0 cmsis_boot/system_stm32f4xx.o
.bss 0x0000000020000018 0x0 FATFS/option/syscall.o
.bss 0x0000000020000018 0x0 FATFS/option/ccsbcs.o
.bss 0x0000000020000018 0x0 FATFS/diskio.o
.bss 0x0000000020000018 0x208 FATFS/ff.o
.bss 0x0000000020000220 0x0 FATFS/shimatta_sdio_driver/shimatta_sdio-driver.o
.bss 0x0000000020000220 0x0 boot/startup_stm32f4xx.o
*(.bss*)
*(COMMON)
COMMON 0x0000000020000220 0x454 main.o
0x0000000020000220 file
0x0000000020000444 SDfs
0x0000000020000674 . = ALIGN (0x4)
0x0000000020000674 _ebss = .
0x0000000020000674 __bss_end__ = _ebss
._user_heap_stack
0x0000000020000674 0x400 load address 0x0000000008005090
0x0000000020000674 . = ALIGN (0x4)
0x0000000020000674 PROVIDE (heap_low, .)
[!provide] PROVIDE (end, .)
[!provide] PROVIDE (_end, .)
0x0000000020000674 . = (. + _Min_Heap_Size)
0x0000000020000674 PROVIDE (heap_top, .)
0x0000000020000a74 . = (. + _Min_Stack_Size)
*fill* 0x0000000020000674 0x400
0x0000000020000a74 . = ALIGN (0x4)
.memory_b1_text
*(.mb1text)
*(.mb1text*)
*(.mb1rodata)
*(.mb1rodata*)
.ARM.attributes
0x0000000000000000 0x37
*(.ARM.attributes)
.ARM.attributes
0x0000000000000000 0x39 main.o
.ARM.attributes
0x0000000000000039 0x39 syscalls.o
.ARM.attributes
0x0000000000000072 0x39 UART/uart.o
.ARM.attributes
0x00000000000000ab 0x39 cmsis_boot/system_stm32f4xx.o
.ARM.attributes
0x00000000000000e4 0x39 FATFS/option/syscall.o
.ARM.attributes
0x000000000000011d 0x39 FATFS/option/ccsbcs.o
.ARM.attributes
0x0000000000000156 0x39 FATFS/diskio.o
.ARM.attributes
0x000000000000018f 0x39 FATFS/ff.o
.ARM.attributes
0x00000000000001c8 0x39 FATFS/shimatta_sdio_driver/shimatta_sdio-driver.o
.ARM.attributes
0x0000000000000201 0x21 boot/startup_stm32f4xx.o
OUTPUT(stm32f4sdio.elf elf32-littlearm)
.comment 0x0000000000000000 0x1d
.comment 0x0000000000000000 0x1d main.o
0x1e (size before relaxing)
.comment 0x000000000000001d 0x1e syscalls.o
.comment 0x000000000000001d 0x1e UART/uart.o
.comment 0x000000000000001d 0x1e cmsis_boot/system_stm32f4xx.o
.comment 0x000000000000001d 0x1e FATFS/option/syscall.o
.comment 0x000000000000001d 0x1e FATFS/option/ccsbcs.o
.comment 0x000000000000001d 0x1e FATFS/diskio.o
.comment 0x000000000000001d 0x1e FATFS/ff.o
.comment 0x000000000000001d 0x1e FATFS/shimatta_sdio_driver/shimatta_sdio-driver.o

BIN
stm32f4sdio.elf Executable file

Binary file not shown.

6
stm32f4sdio.pro Normal file
View File

@ -0,0 +1,6 @@
TEMPLATE = app
CONFIG -= console app_bundle qt
SOURCES += main.c syscalls.c UART/uart.c cmsis_boot/system_stm32f4xx.c FATFS/option/syscall.c FATFS/option/ccsbcs.c FATFS/diskio.c FATFS/ff.c FATFS/shimatta_sdio_driver/shimatta_sdio-driver.c boot/startup_stm32f4xx.S
INCLUDEPATH += ./boot ./mathlib ./cmsis ./cmsis_boot ./UART ./FATFS ./FATFS/shimatta_sdio_driver
HEADERS += ./cmsis/core_cm4_simd.h ./cmsis/core_cmFunc.h ./cmsis/core_cm4.h ./cmsis/core_cmInstr.h ./cmsis_boot/stm32f407xx.h ./cmsis_boot/system_stm32f4xx.h ./cmsis_boot/stm32f4xx.h ./mathlib/arm_math.h ./UART/uart.h ./FATFS/ffconf.h ./FATFS/integer.h ./FATFS/ff.h ./FATFS/diskio.h ./FATFS/shimatta_sdio_driver/shimatta_sdio-driver.h
DEFINES += STM32F407xx STM32F4XX ARM_MATH_CM4

259
stm32f4sdio.pro.user Normal file
View File

@ -0,0 +1,259 @@
<?xml version="1.0" encoding="UTF-8"?>
<!DOCTYPE QtCreatorProject>
<!-- Written by QtCreator 3.5.0, 2015-10-13T18:38:33. -->
<qtcreator>
<data>
<variable>EnvironmentId</variable>
<value type="QByteArray">{29630dae-3008-4619-87cd-d5d4312504fa}</value>
</data>
<data>
<variable>ProjectExplorer.Project.ActiveTarget</variable>
<value type="int">0</value>
</data>
<data>
<variable>ProjectExplorer.Project.EditorSettings</variable>
<valuemap type="QVariantMap">
<value type="bool" key="EditorConfiguration.AutoIndent">true</value>
<value type="bool" key="EditorConfiguration.AutoSpacesForTabs">false</value>
<value type="bool" key="EditorConfiguration.CamelCaseNavigation">true</value>
<valuemap type="QVariantMap" key="EditorConfiguration.CodeStyle.0">
<value type="QString" key="language">Cpp</value>
<valuemap type="QVariantMap" key="value">
<value type="QByteArray" key="CurrentPreferences">CppGlobal</value>
</valuemap>
</valuemap>
<valuemap type="QVariantMap" key="EditorConfiguration.CodeStyle.1">
<value type="QString" key="language">QmlJS</value>
<valuemap type="QVariantMap" key="value">
<value type="QByteArray" key="CurrentPreferences">QmlJSGlobal</value>
</valuemap>
</valuemap>
<value type="int" key="EditorConfiguration.CodeStyle.Count">2</value>
<value type="QByteArray" key="EditorConfiguration.Codec">UTF-8</value>
<value type="bool" key="EditorConfiguration.ConstrainTooltips">false</value>
<value type="int" key="EditorConfiguration.IndentSize">4</value>
<value type="bool" key="EditorConfiguration.KeyboardTooltips">false</value>
<value type="int" key="EditorConfiguration.MarginColumn">80</value>
<value type="bool" key="EditorConfiguration.MouseHiding">true</value>
<value type="bool" key="EditorConfiguration.MouseNavigation">true</value>
<value type="int" key="EditorConfiguration.PaddingMode">1</value>
<value type="bool" key="EditorConfiguration.ScrollWheelZooming">true</value>
<value type="bool" key="EditorConfiguration.ShowMargin">false</value>
<value type="int" key="EditorConfiguration.SmartBackspaceBehavior">0</value>
<value type="bool" key="EditorConfiguration.SpacesForTabs">true</value>
<value type="int" key="EditorConfiguration.TabKeyBehavior">0</value>
<value type="int" key="EditorConfiguration.TabSize">8</value>
<value type="bool" key="EditorConfiguration.UseGlobal">true</value>
<value type="int" key="EditorConfiguration.Utf8BomBehavior">1</value>
<value type="bool" key="EditorConfiguration.addFinalNewLine">true</value>
<value type="bool" key="EditorConfiguration.cleanIndentation">true</value>
<value type="bool" key="EditorConfiguration.cleanWhitespace">true</value>
<value type="bool" key="EditorConfiguration.inEntireDocument">false</value>
</valuemap>
</data>
<data>
<variable>ProjectExplorer.Project.PluginSettings</variable>
<valuemap type="QVariantMap"/>
</data>
<data>
<variable>ProjectExplorer.Project.Target.0</variable>
<valuemap type="QVariantMap">
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Desktop</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName">Desktop</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">{f9533759-631a-48e3-8d5c-9080c252ea8d}</value>
<value type="int" key="ProjectExplorer.Target.ActiveBuildConfiguration">0</value>
<value type="int" key="ProjectExplorer.Target.ActiveDeployConfiguration">0</value>
<value type="int" key="ProjectExplorer.Target.ActiveRunConfiguration">0</value>
<valuemap type="QVariantMap" key="ProjectExplorer.Target.BuildConfiguration.0">
<value type="QString" key="ProjectExplorer.BuildConfiguration.BuildDirectory">/home/mari/projects/arm/qt/stm32fatfs</value>
<valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.0">
<valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.0">
<value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Make</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.MakeStep</value>
<valuelist type="QVariantList" key="Qt4ProjectManager.MakeStep.AutomaticallyAddedMakeArguments">
<value type="QString">-w</value>
<value type="QString">-r</value>
</valuelist>
<value type="bool" key="Qt4ProjectManager.MakeStep.Clean">false</value>
<value type="QString" key="Qt4ProjectManager.MakeStep.MakeArguments"></value>
<value type="QString" key="Qt4ProjectManager.MakeStep.MakeCommand"></value>
</valuemap>
<value type="int" key="ProjectExplorer.BuildStepList.StepsCount">1</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Build</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Build</value>
</valuemap>
<valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.1">
<valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.0">
<value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Make</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.MakeStep</value>
<valuelist type="QVariantList" key="Qt4ProjectManager.MakeStep.AutomaticallyAddedMakeArguments">
<value type="QString">-w</value>
<value type="QString">-r</value>
</valuelist>
<value type="bool" key="Qt4ProjectManager.MakeStep.Clean">true</value>
<value type="QString" key="Qt4ProjectManager.MakeStep.MakeArguments">clean</value>
<value type="QString" key="Qt4ProjectManager.MakeStep.MakeCommand"></value>
</valuemap>
<value type="int" key="ProjectExplorer.BuildStepList.StepsCount">1</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Clean</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Clean</value>
</valuemap>
<value type="int" key="ProjectExplorer.BuildConfiguration.BuildStepListCount">2</value>
<value type="bool" key="ProjectExplorer.BuildConfiguration.ClearSystemEnvironment">false</value>
<valuelist type="QVariantList" key="ProjectExplorer.BuildConfiguration.UserEnvironmentChanges"/>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Debug</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.Qt4BuildConfiguration</value>
<value type="int" key="Qt4ProjectManager.Qt4BuildConfiguration.BuildConfiguration">2</value>
<value type="bool" key="Qt4ProjectManager.Qt4BuildConfiguration.UseShadowBuild">true</value>
</valuemap>
<valuemap type="QVariantMap" key="ProjectExplorer.Target.BuildConfiguration.1">
<value type="QString" key="ProjectExplorer.BuildConfiguration.BuildDirectory">/home/mari/projects/arm/qt/build-stm32f4sdio-Desktop-Release</value>
<valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.0">
<valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.0">
<value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">qmake</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">QtProjectManager.QMakeBuildStep</value>
<value type="bool" key="QtProjectManager.QMakeBuildStep.LinkQmlDebuggingLibrary">false</value>
<value type="bool" key="QtProjectManager.QMakeBuildStep.LinkQmlDebuggingLibraryAuto">true</value>
<value type="QString" key="QtProjectManager.QMakeBuildStep.QMakeArguments"></value>
<value type="bool" key="QtProjectManager.QMakeBuildStep.QMakeForced">false</value>
<value type="bool" key="QtProjectManager.QMakeBuildStep.SeparateDebugInfo">false</value>
<value type="bool" key="QtProjectManager.QMakeBuildStep.UseQtQuickCompiler">false</value>
</valuemap>
<valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.1">
<value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Make</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.MakeStep</value>
<valuelist type="QVariantList" key="Qt4ProjectManager.MakeStep.AutomaticallyAddedMakeArguments">
<value type="QString">-w</value>
<value type="QString">-r</value>
</valuelist>
<value type="bool" key="Qt4ProjectManager.MakeStep.Clean">false</value>
<value type="QString" key="Qt4ProjectManager.MakeStep.MakeArguments"></value>
<value type="QString" key="Qt4ProjectManager.MakeStep.MakeCommand"></value>
</valuemap>
<value type="int" key="ProjectExplorer.BuildStepList.StepsCount">2</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Build</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Build</value>
</valuemap>
<valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.1">
<valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.0">
<value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Make</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.MakeStep</value>
<valuelist type="QVariantList" key="Qt4ProjectManager.MakeStep.AutomaticallyAddedMakeArguments">
<value type="QString">-w</value>
<value type="QString">-r</value>
</valuelist>
<value type="bool" key="Qt4ProjectManager.MakeStep.Clean">true</value>
<value type="QString" key="Qt4ProjectManager.MakeStep.MakeArguments">clean</value>
<value type="QString" key="Qt4ProjectManager.MakeStep.MakeCommand"></value>
</valuemap>
<value type="int" key="ProjectExplorer.BuildStepList.StepsCount">1</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Clean</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Clean</value>
</valuemap>
<value type="int" key="ProjectExplorer.BuildConfiguration.BuildStepListCount">2</value>
<value type="bool" key="ProjectExplorer.BuildConfiguration.ClearSystemEnvironment">false</value>
<valuelist type="QVariantList" key="ProjectExplorer.BuildConfiguration.UserEnvironmentChanges"/>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Release</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.Qt4BuildConfiguration</value>
<value type="int" key="Qt4ProjectManager.Qt4BuildConfiguration.BuildConfiguration">0</value>
<value type="bool" key="Qt4ProjectManager.Qt4BuildConfiguration.UseShadowBuild">true</value>
</valuemap>
<value type="int" key="ProjectExplorer.Target.BuildConfigurationCount">2</value>
<valuemap type="QVariantMap" key="ProjectExplorer.Target.DeployConfiguration.0">
<valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.0">
<value type="int" key="ProjectExplorer.BuildStepList.StepsCount">0</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Deploy</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Deploy</value>
</valuemap>
<value type="int" key="ProjectExplorer.BuildConfiguration.BuildStepListCount">1</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Deploy locally</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.DefaultDeployConfiguration</value>
</valuemap>
<value type="int" key="ProjectExplorer.Target.DeployConfigurationCount">1</value>
<valuemap type="QVariantMap" key="ProjectExplorer.Target.PluginSettings"/>
<valuemap type="QVariantMap" key="ProjectExplorer.Target.RunConfiguration.0">
<valuelist type="QVariantList" key="Analyzer.Valgrind.AddedSuppressionFiles"/>
<value type="bool" key="Analyzer.Valgrind.Callgrind.CollectBusEvents">false</value>
<value type="bool" key="Analyzer.Valgrind.Callgrind.CollectSystime">false</value>
<value type="bool" key="Analyzer.Valgrind.Callgrind.EnableBranchSim">false</value>
<value type="bool" key="Analyzer.Valgrind.Callgrind.EnableCacheSim">false</value>
<value type="bool" key="Analyzer.Valgrind.Callgrind.EnableEventToolTips">true</value>
<value type="double" key="Analyzer.Valgrind.Callgrind.MinimumCostRatio">0.01</value>
<value type="double" key="Analyzer.Valgrind.Callgrind.VisualisationMinimumCostRatio">10</value>
<value type="bool" key="Analyzer.Valgrind.FilterExternalIssues">true</value>
<value type="int" key="Analyzer.Valgrind.LeakCheckOnFinish">1</value>
<value type="int" key="Analyzer.Valgrind.NumCallers">25</value>
<valuelist type="QVariantList" key="Analyzer.Valgrind.RemovedSuppressionFiles"/>
<value type="int" key="Analyzer.Valgrind.SelfModifyingCodeDetection">1</value>
<value type="bool" key="Analyzer.Valgrind.Settings.UseGlobalSettings">true</value>
<value type="bool" key="Analyzer.Valgrind.ShowReachable">false</value>
<value type="bool" key="Analyzer.Valgrind.TrackOrigins">true</value>
<value type="QString" key="Analyzer.Valgrind.ValgrindExecutable">valgrind</value>
<valuelist type="QVariantList" key="Analyzer.Valgrind.VisibleErrorKinds">
<value type="int">0</value>
<value type="int">1</value>
<value type="int">2</value>
<value type="int">3</value>
<value type="int">4</value>
<value type="int">5</value>
<value type="int">6</value>
<value type="int">7</value>
<value type="int">8</value>
<value type="int">9</value>
<value type="int">10</value>
<value type="int">11</value>
<value type="int">12</value>
<value type="int">13</value>
<value type="int">14</value>
</valuelist>
<value type="int" key="PE.EnvironmentAspect.Base">2</value>
<valuelist type="QVariantList" key="PE.EnvironmentAspect.Changes"/>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">stm32f4sdio</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.Qt4RunConfiguration:/home/mari/projects/arm/qt/stm32fatfs/stm32f4sdio.pro</value>
<value type="QString" key="Qt4ProjectManager.Qt4RunConfiguration.CommandLineArguments"></value>
<value type="QString" key="Qt4ProjectManager.Qt4RunConfiguration.ProFile">stm32f4sdio.pro</value>
<value type="bool" key="Qt4ProjectManager.Qt4RunConfiguration.UseDyldImageSuffix">false</value>
<value type="bool" key="Qt4ProjectManager.Qt4RunConfiguration.UseTerminal">false</value>
<value type="QString" key="Qt4ProjectManager.Qt4RunConfiguration.UserWorkingDirectory"></value>
<value type="uint" key="RunConfiguration.QmlDebugServerPort">3768</value>
<value type="bool" key="RunConfiguration.UseCppDebugger">false</value>
<value type="bool" key="RunConfiguration.UseCppDebuggerAuto">true</value>
<value type="bool" key="RunConfiguration.UseMultiProcess">false</value>
<value type="bool" key="RunConfiguration.UseQmlDebugger">false</value>
<value type="bool" key="RunConfiguration.UseQmlDebuggerAuto">true</value>
</valuemap>
<value type="int" key="ProjectExplorer.Target.RunConfigurationCount">1</value>
</valuemap>
</data>
<data>
<variable>ProjectExplorer.Project.TargetCount</variable>
<value type="int">1</value>
</data>
<data>
<variable>ProjectExplorer.Project.Updater.FileVersion</variable>
<value type="int">18</value>
</data>
<data>
<variable>Version</variable>
<value type="int">18</value>
</data>
</qtcreator>