# HG changeset patch # User Daniel O'Connor # Date 1325377873 -37800 # Node ID 74e9b3baac1eec054a8d346bffff7eccf0a6a48b # Parent 274e01fa5a4ca4819129c970bbd538fd187f6325 Jumbo commit to make things work. Note I have t diff -r 274e01fa5a4c -r 74e9b3baac1e .hgignore --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/.hgignore Sun Jan 01 11:01:13 2012 +1030 @@ -0,0 +1,3 @@ +obj/.* +.*~ + diff -r 274e01fa5a4c -r 74e9b3baac1e BSDmakefile --- a/BSDmakefile Sat Oct 08 20:35:34 2011 +1030 +++ b/BSDmakefile Sun Jan 01 11:01:13 2012 +1030 @@ -1,22 +1,20 @@ PROG= main -SRCS= main.c \ - comm.c \ +SRCS= comm.c \ + core_cm3.c \ + lcd.c \ + main.c \ + misc.c \ + startup_stm32f10x_md_mthomas.c \ syscalls.c \ - startup_stm32f10x_md_mthomas.c \ - core_cm3.c \ system_stm32f10x.c \ - stm32f10x_usart.c \ - stm32f10x_flash.c \ - stm32f10x_gpio.c \ - stm32f10x_rcc.c \ - stm32f10x_spi.c \ - stm32f10x_rtc.c \ - stm32f10x_bkp.c \ - stm32f10x_pwr.c \ - stm32f10x_dma.c \ - stm32f10x_tim.c \ - misc.c + +STM32LIBS= usart gpio rcc rtc pwr bkp fsmc + +.for f in ${STM32LIBS} +SRCS+= stm32f10x_${f}.c +CFLAGS+= -DSTM32F10X_${f:U}_EN +.endfor # Linker file LINKFILE= ${.CURDIR}/STM32F10x_512k_64k_flash.ld @@ -26,7 +24,7 @@ # Enable thumb code (since the Cortex M3 only does thumb) COMMONFLAGS+= -mthumb # Debugging & optimisation -COMMONFLAGS+= -g -Os +COMMONFLAGS+= -g -O2 # Put functions & data in individual sections to allow the linker to optimise (breaks debugging apparently) #COMMONFLAGS+= -ffunction-sections -fdata-sections # We aren't using exceptions @@ -35,15 +33,16 @@ CFLAGS+= -I ${.CURDIR} # Set device type -CFLAGS+= -DSTM32F10X_MD +CFLAGS+= -DSTM32F10X_HD # Set clocks -CFLAGS+= -DHSE_VALUE=8000000UL -DSYSCLK_FREQ_72MHz=72000000 +CFLAGS+= -DHSE_VALUE=8000000UL -DSYSCLK_FREQ_72MHz=72000000 # Enable STM peripheral drivers CFLAGS+= -DUSE_STDPERIPH_DRIVER # Enable startup delay #CFLAGS+= -DSTARTUP_DELAY # Vector table in flash CFLAGS+= -DVECT_TAB_FLASH +CFLAGS+= -mthumb-interwork # Enable warnings (disable char-subscripts otherwise ctypes.h generates warnings CFLAGS+= -Wall -Wextra -pedantic -Wimplicit -Wcast-align -Wpointer-arith -Wredundant-decls -Wshadow -Wcast-qual -Wcast-align -Wnested-externs -Wno-char-subscripts -std=gnu99 @@ -64,6 +63,9 @@ .PATH: ${SYSDIR} debug: - ${GDB} --eval-command="target remote 10.211.55.3:61234" --eval-command "load" ${PROG}.elf + ${GDB} --eval-command="target remote 127.0.0.1:61234" ${PROG}.elf + +load: + ${GDB} --eval-command="target remote 127.0.0.1:61234" --eval-command "load" ${PROG}.elf .include "${.CURDIR}/BSDmakefile.arm" diff -r 274e01fa5a4c -r 74e9b3baac1e BSDmakefile.arm --- a/BSDmakefile.arm Sat Oct 08 20:35:34 2011 +1030 +++ b/BSDmakefile.arm Sun Jan 01 11:01:13 2012 +1030 @@ -4,7 +4,7 @@ .MAIN: ${PROG}.bin -TCHAIN= arm-none-eabi +TCHAIN= ${HOME}/sat/bin/arm-none-eabi #TCHAIN= arm-elf #TCHAINSF= -4.6 diff -r 274e01fa5a4c -r 74e9b3baac1e README.txt --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/README.txt Sun Jan 01 11:01:13 2012 +1030 @@ -0,0 +1,34 @@ +Board +===== +Board is a http://ourstm.5d6d.com STM32 Strive mini with a touchscreen +LCD board which has a STM32F103VET (512k flash, 64k RAM). + +Unfortunately the CD that came with it is in Chinese, this page has a review +http://www.deeplyembedded.net/index.php/categories/8-hardware-reviews/5-strive-mini-stm32?showall=&limitstart= + +The RTC is powered by a CR1220 battery. + +It has a SST25VF016B connected to SPI and a micro SD slot connected to +SDIO. + +The LCD is driven by an ILI9325 connected in parallel 16 bit mode via +the FSMC controller. + +Toolchain +========= +Created from https://github.com/MikeSmith/summon-arm-toolchain run +as.. +/summon-arm-toolchain DARWIN_OPT_PATH=/opt/local LIBSTM32_EN=1 LIBSTM32_EN=1 + +MacPorts tools did not work properly - it generated code which jumped +to 0x00 in random places. + +Debug tool +========== +mkdir /tmp/stlink +cp darwin/Info.plist /tmp/stlink +sudo chown -R root: /tmp/stlink +sudo kextload /tmp/stlink + +~/projects/stlink32/build/st-util 61234 /dev/dummy + diff -r 274e01fa5a4c -r 74e9b3baac1e docs/CD00171190.pdf Binary file docs/CD00171190.pdf has changed diff -r 274e01fa5a4c -r 74e9b3baac1e docs/CD00191185.pdf Binary file docs/CD00191185.pdf has changed diff -r 274e01fa5a4c -r 74e9b3baac1e docs/Strive Mini LCD STM32 Schematic.pdf Binary file docs/Strive Mini LCD STM32 Schematic.pdf has changed diff -r 274e01fa5a4c -r 74e9b3baac1e docs/Strive Mini STM32 Schematic.pdf Binary file docs/Strive Mini STM32 Schematic.pdf has changed diff -r 274e01fa5a4c -r 74e9b3baac1e docs/ili9325-v0.35.pdf Binary file docs/ili9325-v0.35.pdf has changed diff -r 274e01fa5a4c -r 74e9b3baac1e lcd.c --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/lcd.c Sun Jan 01 11:01:13 2012 +1030 @@ -0,0 +1,122 @@ +/* + * Example code (I think) + * ~/projects/STM32Strive/奋斗STM32开发板例程/奋斗STM32开发板例程/奋斗STM32开发板MINI/STM32奋斗版ucOS II V2.86 uCGUI 3.9 DEMO-V2/STM32奋斗版ucOS II V2.86 uCGUI 3.9 DEMO + * + * Schematics + * Main board ~/Downloads/Strive\ Mini\ STM32\ Schematic.pdf + * LCD board ~/Downloads/Strive Mini LCD STM32 Schematic.pdf + * MCU reference manual + * ~/Downloads/CD00171190.pdf + * MCU Data sheet (pinout) + * ~/Downloads/CD00191185.pdf + * LCD data sheet + * + */ +/* LCD board MCU + 1 VCC + 2 TC_SCK PA5/SPI1_SCK + 3 GND + 4 TC_CS PB7/SPI1_CS3 + 5 RST PE1 FSMC_NBL1? (unlikely) + 6 TC_DIN PA7/SPI1_MOSI + 7 nOE PD4/FSMC_nOE + 8 TC_DOUT PA6/SPI1_MISO + 9 nWR PD5/FSMC_nWE + 10 TC_INT PB6 + 11 CS PD7/FSMC_NE1/FSMC_NCE2 + 12 NC + 13 RS PD11/FSMC_A16 + 14 NC + 15 D7 PE10/FSMC_D7 + 16 NC + 17 D6 PE9/FSMC_D6 + 18 NC + 19 D3 PD1/FSMC_D3 + 20 D13 PD8/FSMC_D13 + 21 D5 PE8/FSMC_D5 + 22 D12 PE15/FSMC_D12 + 23 D4 PE7/FSMC_D4 + 24 GND + 25 NC + 26 D11 PE14/FSMC_D11 + 27 D2 PD0/FSMC_D2 + 28 D10 PE13/FSMC_D10 + 29 D1 PD15/FSMC_D1 + 30 D9 PE12/FSMC_D9 + 31 D0 PD14/FSMC_D0 + 32 D14 PD9/FSMC_D9 + 33 NC + 34 D8 PE11/FSMC_D8 + 35 NC + 36 NC + 37 NC + 38 LCD_PWM PD13/TIM4_CH2 + 39 NC + 40 D15 PD10/FSMC_D15 +*/ + +#include "stm32f10x.h" +#include "lcd.h" + +void +LCD_init(void) { + GPIO_InitTypeDef GPIO_InitStructure; + FSMC_NORSRAMInitTypeDef FSMC_NORSRAMInitStructure; + FSMC_NORSRAMTimingInitTypeDef p; + + /* Configures LCD Control lines (FSMC Pins) in alternate function Push-Pull mode. + * + * PD0(D2), PD1(D3), PD4(NOE), PD5(NWE), PD7(NE1/CS), PD8(D13), PD9(D14), + * PD10(D15), PD11(A16/RS) PD14(D0), PD15(D1) + */ + GPIO_InitStructure.GPIO_Pin = (GPIO_Pin_0 | GPIO_Pin_1 | GPIO_Pin_4 | GPIO_Pin_5 | GPIO_Pin_7 | + GPIO_Pin_8 | GPIO_Pin_9 | GPIO_Pin_10 | GPIO_Pin_11 | GPIO_Pin_14 | GPIO_Pin_15); + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP; + GPIO_Init(GPIOD, &GPIO_InitStructure); + + /* PE7(D4), PE8(D5), PE9(D6), PE10(D7), PE11(D8), PE12(D9), PE13(D10), + * PE14(D11), PE15(D12) + */ + GPIO_InitStructure.GPIO_Pin = GPIO_Pin_7 | GPIO_Pin_8 | GPIO_Pin_9 | GPIO_Pin_10 | + GPIO_Pin_11 | GPIO_Pin_12 | GPIO_Pin_13 | GPIO_Pin_14 | GPIO_Pin_15; + GPIO_Init(GPIOE, &GPIO_InitStructure); + + /* Configures the Parallel interface (FSMC) for LCD (Parallel mode) */ + /* FSMC_Bank1_NORSRAM4 timing configuration */ + p.FSMC_AddressSetupTime = 1; + p.FSMC_AddressHoldTime = 0; + p.FSMC_DataSetupTime = 2; + p.FSMC_BusTurnAroundDuration = 0; + p.FSMC_CLKDivision = 0; + p.FSMC_DataLatency = 0; + p.FSMC_AccessMode = FSMC_AccessMode_A; + + /* FSMC_Bank1_NORSRAM4 configured as follows: + - Data/Address MUX = Disable + - Memory Type = SRAM + - Data Width = 16bit + - Write Operation = Enable + - Extended Mode = Disable + - Asynchronous Wait = Disable */ + FSMC_NORSRAMInitStructure.FSMC_Bank = FSMC_Bank1_NORSRAM4; + FSMC_NORSRAMInitStructure.FSMC_DataAddressMux = FSMC_DataAddressMux_Disable; + FSMC_NORSRAMInitStructure.FSMC_MemoryType = FSMC_MemoryType_SRAM; + FSMC_NORSRAMInitStructure.FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_16b; + FSMC_NORSRAMInitStructure.FSMC_BurstAccessMode = FSMC_BurstAccessMode_Disable; + FSMC_NORSRAMInitStructure.FSMC_AsynchronousWait = FSMC_AsynchronousWait_Disable; + FSMC_NORSRAMInitStructure.FSMC_WaitSignalPolarity = FSMC_WaitSignalPolarity_Low; + FSMC_NORSRAMInitStructure.FSMC_WrapMode = FSMC_WrapMode_Disable; + FSMC_NORSRAMInitStructure.FSMC_WaitSignalActive = FSMC_WaitSignalActive_BeforeWaitState; + FSMC_NORSRAMInitStructure.FSMC_WriteOperation = FSMC_WriteOperation_Enable; + FSMC_NORSRAMInitStructure.FSMC_WaitSignal = FSMC_WaitSignal_Disable; + FSMC_NORSRAMInitStructure.FSMC_ExtendedMode = FSMC_ExtendedMode_Disable; + FSMC_NORSRAMInitStructure.FSMC_WriteBurst = FSMC_WriteBurst_Disable; + FSMC_NORSRAMInitStructure.FSMC_ReadWriteTimingStruct = &p; + FSMC_NORSRAMInitStructure.FSMC_WriteTimingStruct = &p; + + FSMC_NORSRAMInit(&FSMC_NORSRAMInitStructure); + + /* Enable FSMC_Bank1_NORSRAM4 */ + FSMC_NORSRAMCmd(FSMC_Bank1_NORSRAM4, ENABLE); +} diff -r 274e01fa5a4c -r 74e9b3baac1e lcd.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/lcd.h Sun Jan 01 11:01:13 2012 +1030 @@ -0,0 +1,7 @@ +#ifndef LCD_H_ +#define LCD_H_ + +void LCD_init(void); + +#endif + diff -r 274e01fa5a4c -r 74e9b3baac1e main.c --- a/main.c Sat Oct 08 20:35:34 2011 +1030 +++ b/main.c Sun Jan 01 11:01:13 2012 +1030 @@ -1,25 +1,43 @@ #include +#include #include #include +#include +#include +#include +#include + #include "stm32f10x.h" +#include "lcd.h" #include "main.h" #include "comm.h" -typedef volatile struct { - char buf[40]; - uint8_t state; - uint8_t len; +typedef struct { + char buf[40]; + volatile uint8_t state; + uint8_t len; } consbuf_t; void Setup_HW(void); void NVIC_Configuration(void); -/* Called every millisecond */ + +/* Called every 1 / TICK_FREQ */ +#define TICK_FREQ 10000 RAMFUNC void SysTick_Handler(void) { static uint32_t tick = 0; - + static int led = 0; + tick++; + if (tick % 10000 == 0) { + led = !led; + if (led) + GPIO_SetBits(GPIOB, GPIO_Pin_5); + else + GPIO_ResetBits(GPIOB, GPIO_Pin_5); + } + } consbuf_t cmd; @@ -81,6 +99,10 @@ int main(void) { + char buf[40]; + struct tm nowtm; + time_t now; + cmd.state = cmd.len = 0; /* Setup USART etc */ @@ -89,27 +111,54 @@ /* NVIC configuration */ NVIC_Configuration(); - /* Setup SysTick Timer for 1 millisecond interrupts, also enables Systick and Systick-Interrupt */ - if (SysTick_Config(SystemCoreClock / 1000)) { + /* Setup SysTick Timer rate, also enables Systick and Systick-Interrupt */ + if (SysTick_Config(SystemCoreClock / TICK_FREQ)) { /* Capture error */ comm_puts("Can't setup SysTick\r\n"); while (1) ; } + /* Init LCD interface */ + LCD_init(); + + /* Set stdout to unbuffered */ setvbuf(stdout, NULL, _IONBF, 0); /* Say hello */ fputs("\r\nHello world\r\n", stdout); +#define Bank1_LCD_D ((uint32_t)0x60020000) //disp Data ADDR +#define Bank1_LCD_C ((uint32_t)0x60000000) //disp Reg ADDR + while (1) { fputs("> ", stdout); while (cmd.state != 255) ; - if (cmd.len > 0) - printf("Got command '%s'\r\n", cmd.buf); + if (cmd.len > 0) { + if (!strncmp("gc", cmd.buf, 2)) { + now = time(NULL); + gmtime_r(&now, &nowtm); + strftime(buf, sizeof(buf) - 1, "Time is %Y/%m/%d %H:%M:%S UTC", &nowtm); + printf("Time is %s (%d)\r\n", buf, (int)now); + } else if (!strncmp("sc ", cmd.buf, 3)) { + struct timeval tv; + tv.tv_sec = atoi(cmd.buf + 3); + tv.tv_usec = 0; + settimeofday(&tv, NULL); + } else if (!strncmp("lcd", cmd.buf, 3)) { + *(__IO uint16_t *) (Bank1_LCD_C) = 0x00; + printf("LCD ID = %hx\r\n", *(__IO uint16_t *) (Bank1_LCD_D)); + } else if (!strncmp("read", cmd.buf, 4)) { + printf("PB5 = %d\r\n", GPIO_ReadInputDataBit(GPIOB, GPIO_Pin_15)); + } else if (!strncmp("zz", cmd.buf, 2)) { + NVIC_SystemReset(); + } else { + printf("Unknown command\r\n"); + } + } cmd.state = 0; } } @@ -120,15 +169,54 @@ GPIO_InitTypeDef GPIO_InitStructure; USART_InitTypeDef USART_InitStructure; - /* Enable USART1, GPIOA, GPIOD and AFIO clocks */ - RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1 | RCC_APB2Periph_GPIOA |RCC_APB2Periph_GPIOD - | RCC_APB2Periph_AFIO, ENABLE); - /* Enable USART2 clock */ - RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE); + /* RTC stuff */ + /* Enable PWR and BKP clocks */ + RCC_APB1PeriphClockCmd(RCC_APB1Periph_PWR | RCC_APB1Periph_BKP, ENABLE); + + /* Allow access to BKP Domain */ + PWR_BackupAccessCmd(ENABLE); + + /* Reset Backup Domain + * + * This resets the RTC etc back to 0 so probably only useful under user command + BKP_DeInit(); + */ + + /* Enable LSE */ + RCC_LSEConfig(RCC_LSE_ON); + + /* Wait till LSE is ready */ + while (RCC_GetFlagStatus(RCC_FLAG_LSERDY) == RESET) + ; + + /* Select LSE as RTC Clock Source */ + RCC_RTCCLKConfig(RCC_RTCCLKSource_LSE); - /* DMA1 clock enable */ - RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE); + /* Enable RTC Clock */ + RCC_RTCCLKCmd(ENABLE); + + /* Wait for RTC registers synchronization */ + RTC_WaitForSynchro(); + + /* Wait until last write operation on RTC registers has finished */ + RTC_WaitForLastTask(); + + /* Wait until last write operation on RTC registers has finished */ + RTC_WaitForLastTask(); + /* Set RTC prescaler: set RTC period to 1sec */ + RTC_SetPrescaler(32767); /* RTC period = RTCCLK/RTC_PR = (32.768 KHz)/(32767+1) */ + + /* Wait until last write operation on RTC registers has finished */ + RTC_WaitForLastTask(); + + /* Clock setup */ + /* Enable clocks we need */ + RCC_AHBPeriphClockCmd(RCC_AHBPeriph_FSMC, ENABLE); + RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1 | RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB | + RCC_APB2Periph_GPIOD | RCC_APB2Periph_GPIOE | RCC_APB2Periph_AFIO, ENABLE); + + /* Port configuration */ /* Configure USART1 TX (PA.09) as alternate function push-pull */ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_9; GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; @@ -140,21 +228,32 @@ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING; GPIO_Init(GPIOA, &GPIO_InitStructure); - /* Init UART1 - 115200 8n1, no flow control TX & RX enabled */ + /* Configure PB5 as output push-pull */ + GPIO_InitStructure.GPIO_Pin = GPIO_Pin_5; + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP; + GPIO_Init(GPIOB, &GPIO_InitStructure); + + /* Configure PB15 as input pull-up push-pull */ + GPIO_InitStructure.GPIO_Pin = GPIO_Pin_15; + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPU; + GPIO_Init(GPIOB, &GPIO_InitStructure); + + /* USART configuration */ + /* USART1 - 115200 8n1, no flow control TX & RX enabled */ USART_InitStructure.USART_BaudRate = 115200; USART_InitStructure.USART_WordLength = USART_WordLength_8b; USART_InitStructure.USART_StopBits = USART_StopBits_1; USART_InitStructure.USART_Parity = USART_Parity_No; USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None; USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx; - - /* Configure USART1 */ USART_Init(USART1, &USART_InitStructure); /* Enable interrupts on receive data */ USART_ITConfig(USART1, USART_IT_RXNE, ENABLE); - /* Enable the USART1 */ + /* Enable USART */ USART_Cmd(USART1, ENABLE); } diff -r 274e01fa5a4c -r 74e9b3baac1e startup_stm32f10x_md_mthomas.c --- a/startup_stm32f10x_md_mthomas.c Sat Oct 08 20:35:34 2011 +1030 +++ b/startup_stm32f10x_md_mthomas.c Sun Jan 01 11:01:13 2012 +1030 @@ -161,7 +161,7 @@ void (* const g_pfnVectorsStartup[])(void) = { (intfunc)((unsigned long)&_estack), /* The initial stack pointer during startup */ - Reset_Handler, /* The reset handler during startup */ + Reset_Handler, /* The reset handler during startup */ HardFault_Handler, /* Hard Fault Handler */ MemManage_Handler, /* MPU Fault Handler */ BusFault_Handler, /* Bus Fault Handler */ @@ -262,10 +262,7 @@ /* Call CTORS of static objects, not needed for "pure C": */ /* __libc_init_array(); */ - /* if ( __libc_init_array ) - __libc_init_array() - } */ - + /* Setup the microcontroller system. Initialize the Embedded Flash Interface, initialize the PLL and update the SystemFrequency variable. */ SystemInit(); @@ -273,7 +270,8 @@ /* Call the application's entry point.*/ main(); - while(1) { ; } + while(1) { + } } /** @@ -282,25 +280,22 @@ * @retval : None */ -void __Init_Data_and_BSS(void) -{ - unsigned long *pulSrc, *pulDest; +void +__Init_Data_and_BSS(void) { + unsigned long *pulSrc, *pulDest; - /* Copy the data segment initializers from flash to SRAM */ - pulSrc = &_sidata; - pulDest = &_sdata; - if ( pulSrc != pulDest ) - { - for(; pulDest < &_edata; ) - { - *(pulDest++) = *(pulSrc++); + /* Copy the data segment initializers from flash to SRAM */ + pulSrc = &_sidata; + pulDest = &_sdata; + if (pulSrc != pulDest) { + for(; pulDest < &_edata; ) { + *(pulDest++) = *(pulSrc++); + } } - } - /* Zero fill the bss segment. */ - for(pulDest = &_sbss; pulDest < &_ebss; ) - { - *(pulDest++) = 0; - } + /* Zero fill the bss segment. */ + for(pulDest = &_sbss; pulDest < &_ebss; ) { + *(pulDest++) = 0; + } } /******************************************************************************* @@ -371,11 +366,10 @@ * @retval : None */ -void Default_Handler(void) -{ +void +Default_Handler(void) { /* Go into an infinite loop. */ - while (1) - { + while (1) { } } diff -r 274e01fa5a4c -r 74e9b3baac1e stm32f10x_conf.h --- a/stm32f10x_conf.h Sat Oct 08 20:35:34 2011 +1030 +++ b/stm32f10x_conf.h Sun Jan 01 11:01:13 2012 +1030 @@ -1,22 +1,4 @@ -/** - ****************************************************************************** - * @file USART/Polling/stm32f10x_conf.h - * @author MCD Application Team, mod. Martin Thomas for this project - * @version V3.0.0 - * @date 04/18/2009 - * @brief Library configuration file. - ****************************************************************************** - * @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. - * - *

© COPYRIGHT 2009 STMicroelectronics

- */ +/* Used to control which peripheral code is used */ /* Define to prevent recursive inclusion -------------------------------------*/ #ifndef __STM32F10x_CONF_H @@ -24,29 +6,73 @@ /* Includes ------------------------------------------------------------------*/ /* Uncomment the line below to enable peripheral header file inclusion */ -/* #include "stm32f10x_adc.h" */ +#ifdef STM32F10X_ADC_EN +#include "stm32f10x_adc.h" +#endif +#ifdef STM32F10X_BKP_EN #include "stm32f10x_bkp.h" -/* #include "stm32f10x_can.h" */ -/* #include "stm32f10x_crc.h" */ -/* #include "stm32f10x_dac.h" */ -/* #include "stm32f10x_dbgmcu.h" */ +#endif +#ifdef STM32F10X_CAN_EN +#include "stm32f10x_can.h" +#endif +#ifdef STM32F10X_CRC_EN +#include "stm32f10x_crc.h" +#endif +#ifdef STM32F10X_DAC_EN +#include "stm32f10x_dac.h" +#endif +#ifdef STM32F10X_DBGMCU_EN +#include "stm32f10x_dbgmcu.h" +#endif +#ifdef STM32F10X_DMA_EN #include "stm32f10x_dma.h" -/* #include "stm32f10x_exti.h" */ +#endif +#ifdef STM32F10X_EXTI_EN +#include "stm32f10x_exti.h" +#endif +#ifdef STM32F10X_FLASH_EN #include "stm32f10x_flash.h" -/* #include "stm32f10x_fsmc.h" */ +#endif +#ifdef STM32F10X_FSMC_EN +#include "stm32f10x_fsmc.h" +#endif +#ifdef STM32F10X_GPIO_EN #include "stm32f10x_gpio.h" -/* #include "stm32f10x_i2c.h" */ -/* #include "stm32f10x_iwdg.h" */ +#endif +#ifdef STM32F10X_I2C_EN +#include "stm32f10x_i2c.h" +#endif +#ifdef STM32F10X_IWDG_EN +#include "stm32f10x_iwdg.h" +#endif +#ifdef STM32F10X_PWR_EN #include "stm32f10x_pwr.h" +#endif +#ifdef STM32F10X_RCC_EN #include "stm32f10x_rcc.h" +#endif +#ifdef STM32F10X_RTC_EN #include "stm32f10x_rtc.h" -/* #include "stm32f10x_sdio.h" */ +#endif +#ifdef STM32F10X_SDIO_EN +#include "stm32f10x_sdio.h" +#endif +#ifdef STM32F10X_SPI_EN #include "stm32f10x_spi.h" +#endif +#ifdef STM32F10X_TIM_EN #include "stm32f10x_tim.h" +#endif +#ifdef STM32F10X_USART_EN #include "stm32f10x_usart.h" -/* #include "stm32f10x_wwdg.h" */ +#endif +#ifdef STM32F10X_WWDG_EN +#include "stm32f10x_wwdg.h" +#endif + #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 diff -r 274e01fa5a4c -r 74e9b3baac1e syscalls.c --- a/syscalls.c Sat Oct 08 20:35:34 2011 +1030 +++ b/syscalls.c Sun Jan 01 11:01:13 2012 +1030 @@ -5,14 +5,13 @@ * Author: Martin Thomas, 3BSD license */ -//#define SBRK_VERBOSE 1 - #include #include #include #include /* abort */ #include #include +#include #include "comm.h" #include "stm32f10x.h" /* for _get_PSP() from core_cm3.h*/ @@ -27,7 +26,8 @@ return -1; } -void _exit(int status) { +void +_exit(int status) { printf("_exit called with parameter %d\n", status); while(1) ; @@ -38,7 +38,6 @@ return 1; } - extern char _end; /* Defined by the linker */ static char *heap_end; @@ -49,26 +48,24 @@ char * get_stack_top(void) { + /* Use MSP (vs PSP) - the processor is in Thread mode out of reset */ return (char*) __get_MSP(); - //return (char*) __get_PSP(); } caddr_t _sbrk(int incr) { char *prev_heap_end; -#if SBRK_VERBOSE - printf("_sbrk called with incr %d\n", incr); -#endif + if (heap_end == 0) { heap_end = &_end; } prev_heap_end = heap_end; -#if 1 + if (heap_end + incr > get_stack_top()) { printf("Heap and stack collision\n"); abort(); } -#endif + heap_end += incr; return (caddr_t) prev_heap_end; } @@ -118,3 +115,49 @@ } return len; } + +int +_gettimeofday_r(struct _reent *reent __attribute__((unused)), struct timeval *tp, void *tzp __attribute__((unused))) { + tp->tv_sec = RTC_GetCounter(); + tp->tv_usec = 0; + + return 0; +} + +int +settimeofday(const struct timeval *tp, const struct timezone *tzp __attribute__((unused))) { + RTC_SetCounter(tp->tv_sec); + + return 0; +} + +clock_t +_clock (void) { + return RTC_GetCounter(); +} + +void +__tz_lock (void) { +} + + +void +__tz_unlock (void) { +} + +static __tzinfo_type tzinfo = {1, 0, + { {'J', 0, 0, 0, 0, (time_t)0, 0L }, + {'J', 0, 0, 0, 0, (time_t)0, 0L } + } +}; + +__tzinfo_type * +__gettzinfo (void) { + return &tzinfo; +} + +/* Stub, required for strftime?! */ +int +_open(const char *name __attribute__((unused)), int mode __attribute__((unused)), ...) { + return -1; +}