From 029e6df4b9827b429340599c42b34d37f59c8e64 Mon Sep 17 00:00:00 2001 From: Jonathan Naylor Date: Thu, 9 Nov 2023 19:08:15 +0000 Subject: [PATCH] Remove support for STM32F1* boards, they're just too slow. --- .gitmodules | 3 - Config.h | 15 +- Globals.h | 7 +- IOSTM_CMSIS.cpp | 500 ------------------------- MMDVM.cpp | 2 +- Makefile.CMSIS | 165 -------- README.md | 2 +- RingBuff.h | 47 --- RingBuffer.h | 7 +- STM32F10X_Lib | 1 - SerialSTM_CMSIS.cpp | 170 --------- Utils.h | 3 - mmdvmmenu.sh | 98 ----- system_stm32f1xx/gcc.ld | 187 --------- system_stm32f1xx/startup_stm32f105xc.S | 427 --------------------- system_stm32f1xx/system_stm32f1xx.c | 227 ----------- 16 files changed, 8 insertions(+), 1853 deletions(-) delete mode 100644 IOSTM_CMSIS.cpp delete mode 100644 Makefile.CMSIS delete mode 100644 RingBuff.h delete mode 160000 STM32F10X_Lib delete mode 100644 SerialSTM_CMSIS.cpp delete mode 100755 mmdvmmenu.sh delete mode 100644 system_stm32f1xx/gcc.ld delete mode 100644 system_stm32f1xx/startup_stm32f105xc.S delete mode 100644 system_stm32f1xx/system_stm32f1xx.c diff --git a/.gitmodules b/.gitmodules index 6e7071e..78686ee 100644 --- a/.gitmodules +++ b/.gitmodules @@ -4,6 +4,3 @@ [submodule "STM32F7XX_Lib"] path = STM32F7XX_Lib url = https://github.com/juribeparada/STM32F7XX_Lib.git -[submodule "STM32F10X_Lib"] - path = STM32F10X_Lib - url = https://github.com/shawnchain/STM32F10X_Lib.git diff --git a/Config.h b/Config.h index 43e5f8b..0dea844 100644 --- a/Config.h +++ b/Config.h @@ -20,7 +20,7 @@ #define CONFIG_H // Allow for the selection of which modes to compile into the firmware. This is particularly useful for processors -// which have limited code space and processing power like the STM32F103, which is found on older/cheaper boards. +// which have limited code space and processing power. // Enable D-Star support. #define MODE_DSTAR @@ -67,7 +67,7 @@ // #define EXTERNAL_OSC 19200000 // Select a baud rate for host communication. The faster speeds are needed for external FM to work. -// #define SERIAL_SPEED 115200 // Suitable for most older boards (Arduino Due, STM32F1_POG, etc). External FM will NOT work with this! +// #define SERIAL_SPEED 115200 // Suitable for most older boards (Arduino Due, etc). External FM will NOT work with this! // #define SERIAL_SPEED 230400 // Only works on newer boards like fast M4, M7, Teensy 3.x. External FM might work with this #define SERIAL_SPEED 460800 // Only works on newer boards like fast M4, M7, Teensy 3.x. External FM should work with this //#define SERIAL_SPEED 500000 // Used with newer boards and Armbian on AllWinner SOCs (H2, H3) that do not support 460800 @@ -78,13 +78,8 @@ // For the original Arduino Due pin layout // #define ARDUINO_DUE_PAPA -#if defined(STM32F1) -// For the SQ6POG board -#define STM32F1_POG -#else // For the ZUM V1.0 and V1.0.1 boards pin layout // #define ARDUINO_DUE_ZUM_V10 -#endif // For the SP8NTH board // #define ARDUINO_DUE_NTH @@ -127,11 +122,5 @@ // Use the D-Star and YSF LEDs for FM #define USE_ALTERNATE_FM_LEDS -#if defined(STM32F1_POG) -// Slower boards need to run their serial at 115200 baud -#undef SERIAL_SPEED -#define SERIAL_SPEED 115200 -#endif - #endif diff --git a/Globals.h b/Globals.h index 38515a2..33b7334 100644 --- a/Globals.h +++ b/Globals.h @@ -23,15 +23,12 @@ #include "stm32f4xx.h" #elif defined(STM32F7XX) #include "stm32f7xx.h" -#elif defined(STM32F105xC) -#include "stm32f1xx.h" -#include "STM32Utils.h" #else #include #undef PI //Undefine PI to get rid of annoying warning as it is also defined in arm_math.h. #endif -#if defined(__SAM3X8E__) || defined(STM32F105xC) +#if defined(__SAM3X8E__) #define ARM_MATH_CM3 #elif defined(STM32F7XX) #define ARM_MATH_CM7 @@ -118,7 +115,7 @@ const uint16_t RX_BLOCK_SIZE = 2U; const uint16_t TX_RINGBUFFER_SIZE = 500U; const uint16_t RX_RINGBUFFER_SIZE = 600U; -#if defined(STM32F105xC) || defined(__MK20DX256__) +#if defined(__MK20DX256__) const uint16_t TX_BUFFER_LEN = 2000U; #else const uint16_t TX_BUFFER_LEN = 4000U; diff --git a/IOSTM_CMSIS.cpp b/IOSTM_CMSIS.cpp deleted file mode 100644 index 300a88a..0000000 --- a/IOSTM_CMSIS.cpp +++ /dev/null @@ -1,500 +0,0 @@ -/* - * Copyright (C) 2016 by Jim McLaughlin KI6ZUM - * Copyright (C) 2016, 2017 by Andy Uribe CA6JAU - * Copyright (C) 2017,2018,2020 by Jonathan Naylor G4KLX - * Copyright (C) 2017 by Wojciech Krutnik N0CALL - * - * 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 2 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., 675 Mass Ave, Cambridge, MA 02139, USA. - */ - -#include "Config.h" -#include "Globals.h" -#include "IO.h" - -#if defined(STM32F1) - -#if defined(STM32F1_POG) -/* -Pin definitions for STM32F1 POG Board: - -PTT PB12 output -COSLED PB5 output -LED PB4 output -COS PB13 input/PD - -DSTAR PB7 output -DMR PB6 output -YSF PB8 output -P25 PB9 output -NXDN PB10 output -POCSAG PB11 output - -RX PB0 analog input (ADC1_8) -RSSI PB1 analog input (ADC2_9) -TX PA4 analog output (DAC_OUT1) - -EXT_CLK PA15 input (AF: TIM2_CH1_ETR) - -USART1_TXD PA9 output (AF) -USART1_RXD PA10 input (AF) - -*/ - -#define PIN_PTT 12 -#define PORT_PTT GPIOB -#define BB_PTT *((bitband_t)BITBAND_PERIPH(&PORT_PTT->ODR, PIN_PTT)) -#define PIN_COSLED 5 -#define PORT_COSLED GPIOB -#define BB_COSLED *((bitband_t)BITBAND_PERIPH(&PORT_COSLED->ODR, PIN_COSLED)) -#define PIN_LED 4 -#define PORT_LED GPIOB -#define BB_LED *((bitband_t)BITBAND_PERIPH(&PORT_LED->ODR, PIN_LED)) -#define PIN_COS 13 -#define PORT_COS GPIOB -#define BB_COS *((bitband_t)BITBAND_PERIPH(&PORT_COS->IDR, PIN_COS)) - -#define PIN_DSTAR 7 -#define PORT_DSTAR GPIOB -#define BB_DSTAR *((bitband_t)BITBAND_PERIPH(&PORT_DSTAR->ODR, PIN_DSTAR)) -#define PIN_DMR 6 -#define PORT_DMR GPIOB -#define BB_DMR *((bitband_t)BITBAND_PERIPH(&PORT_DMR->ODR, PIN_DMR)) -#define PIN_YSF 8 -#define PORT_YSF GPIOB -#define BB_YSF *((bitband_t)BITBAND_PERIPH(&PORT_YSF->ODR, PIN_YSF)) -#define PIN_P25 9 -#define PORT_P25 GPIOB -#define BB_P25 *((bitband_t)BITBAND_PERIPH(&PORT_P25->ODR, PIN_P25)) -#define PIN_NXDN 10 -#define PORT_NXDN GPIOB -#define BB_NXDN *((bitband_t)BITBAND_PERIPH(&PORT_NXDN->ODR, PIN_NXDN)) -#define PIN_POCSAG 11 -#define PORT_POCSAG GPIOB -#define BB_POCSAG *((bitband_t)BITBAND_PERIPH(&PORT_POCSAG->ODR, PIN_POCSAG)) - -#define PIN_RX 0 -#define PIN_RX_ADC_CH 8 -#define PORT_RX GPIOB -#define PIN_RSSI 1 -#define PIN_RSSI_ADC_CH 9 -#define PORT_RSSI GPIOB -#define PIN_TX 4 -#define PIN_TX_DAC_CH 1 -#define PORT_TX GPIOA - -#define PIN_EXT_CLK 15 -#define SRC_EXT_CLK 15 -#define PORT_EXT_CLK GPIOA - -#define PIN_USART1_TXD 9 -#define PORT_USART1_TXD GPIOA -#define PIN_USART1_RXD 10 -#define PORT_USART1_RXD GPIOA - -#else // defined(STM32F1_POG) -#error "Either STM32F1_POG, or sth need to be defined" -#endif // defined(STM32F1_POG) - -const uint16_t DC_OFFSET = 2048U; - -// Sampling frequency -#define SAMP_FREQ 24000 - -extern "C" { - void TIM2_IRQHandler() { - if ((TIM2->SR & TIM_SR_UIF) == TIM_SR_UIF) { - TIM2->SR = ~TIM_SR_UIF; // clear UI flag - io.interrupt(); - } - } -} - - -void delay(uint32_t cnt) -{ - while(cnt--) - asm("nop"); -} - -// source: http://www.freddiechopin.info/ -void GPIOConfigPin(GPIO_TypeDef *port_ptr, uint32_t pin, uint32_t mode_cnf_value) -{ - volatile uint32_t *cr_ptr; - uint32_t cr_value; - - cr_ptr = &port_ptr->CRL; // configuration of pins [0,7] is in CRL - - if (pin >= 8) // is pin in [8; 15]? - { // configuration of pins [8,15] is in CRH - cr_ptr++; // advance to next struct element CRL -> CRH - pin -= 8; // crop the pin number - } - - cr_value = *cr_ptr; // localize the CRL / CRH value - - cr_value &= ~(0xF << (pin * 4)); // clear the MODE and CNF fields (now that pin is an analog input) - cr_value |= (mode_cnf_value << (pin * 4)); // save new MODE and CNF value for desired pin - - *cr_ptr = cr_value; // save localized value to CRL / CRL -} - -#if defined(STM32F1_POG) -void FancyLEDEffect() -{ - bitband_t foo[] = {&BB_LED, &BB_COSLED, &BB_PTT, &BB_DMR, &BB_DSTAR, &BB_YSF, &BB_P25}; - - for(int i=0; i<7; i++){ - *foo[i] = 0x01; - } - GPIOConfigPin(PORT_USART1_TXD, PIN_USART1_TXD, GPIO_CRL_MODE0_1); - *((bitband_t)BITBAND_PERIPH(&PORT_USART1_TXD->ODR, PIN_USART1_TXD)) = 0x00; - delay(SystemCoreClock/1000*100); - for(int i=0; i<7; i++){ - *foo[i] = 0x00; - } - *((bitband_t)BITBAND_PERIPH(&PORT_USART1_TXD->ODR, PIN_USART1_TXD)) = 0x01; - delay(SystemCoreClock/1000*20); - *((bitband_t)BITBAND_PERIPH(&PORT_USART1_TXD->ODR, PIN_USART1_TXD)) = 0x00; - delay(SystemCoreClock/1000*10); - *((bitband_t)BITBAND_PERIPH(&PORT_USART1_TXD->ODR, PIN_USART1_TXD)) = 0x01; - - *foo[0] = 0x01; - for(int i=1; i<7; i++){ - delay(SystemCoreClock/1000*10); - *foo[i-1] = 0x00; - *foo[i] = 0x01; - } - for(int i=5; i>=0; i--){ - delay(SystemCoreClock/1000*10); - *foo[i+1] = 0x00; - *foo[i] = 0x01; - } - delay(SystemCoreClock/1000*10); - *foo[5+1-6] = 0x00; - *((bitband_t)BITBAND_PERIPH(&PORT_USART1_TXD->ODR, PIN_USART1_TXD)) = 0x00; - delay(SystemCoreClock/1000*10); - *((bitband_t)BITBAND_PERIPH(&PORT_USART1_TXD->ODR, PIN_USART1_TXD)) = 0x01; - GPIOConfigPin(PORT_USART1_TXD, PIN_USART1_TXD, GPIO_CRL_MODE0_1|GPIO_CRL_CNF0_1); - delay(SystemCoreClock/1000*50); -} -#endif - -static inline void GPIOInit() -{ - RCC->APB2ENR |= RCC_APB2ENR_IOPAEN | RCC_APB2ENR_IOPBEN - | RCC_APB2ENR_IOPCEN | RCC_APB2ENR_IOPDEN - | RCC_APB2ENR_AFIOEN; // enable all GPIOs - - // set all ports to input with pull-down - GPIOA->CRL = 0x88888888; - GPIOA->CRH = 0x88888888; - GPIOA->ODR = 0; - GPIOB->CRL = 0x88888888; - GPIOB->CRH = 0x88888888; - GPIOB->ODR = 0; - GPIOC->CRL = 0x88888888; - GPIOC->CRH = 0x88888888; - GPIOC->ODR = 0; - GPIOD->CRL = 0x88888888; - GPIOD->CRH = 0x88888888; - GPIOD->ODR = 0; - - // configure ports - GPIOConfigPin(PORT_PTT, PIN_PTT, GPIO_CRL_MODE0_1); - GPIOConfigPin(PORT_COSLED, PIN_COSLED, GPIO_CRL_MODE0_1); - GPIOConfigPin(PORT_LED, PIN_LED, GPIO_CRL_MODE0_1); - GPIOConfigPin(PORT_COS, PIN_COS, GPIO_CRL_CNF0_1); - - GPIOConfigPin(PORT_DSTAR, PIN_DSTAR, GPIO_CRL_MODE0_1); - GPIOConfigPin(PORT_DMR, PIN_DMR, GPIO_CRL_MODE0_1); - GPIOConfigPin(PORT_YSF, PIN_YSF, GPIO_CRL_MODE0_1); - GPIOConfigPin(PORT_P25, PIN_P25, GPIO_CRL_MODE0_1); -#if !defined(USE_ALTERNATE_NXDN_LEDS) - GPIOConfigPin(PORT_NXDN, PIN_NXDN, GPIO_CRL_MODE0_1); -#endif -#if !defined(USE_ALTERNATE_M17_LEDS) - GPIOConfigPin(PORT_M17, PIN_M17, GPIO_CRL_MODE0_1); -#endif -#if !defined(USE_ALTERNATE_POCSAG_LEDS) - GPIOConfigPin(PORT_POCSAG, PIN_POCSAG, GPIO_CRL_MODE0_1); -#endif - - GPIOConfigPin(PORT_RX, PIN_RX, 0); -#if defined(SEND_RSSI_DATA) - GPIOConfigPin(PORT_RSSI, PIN_RSSI, 0); -#endif - GPIOConfigPin(PORT_TX, PIN_TX, 0); - -#if defined(EXTERNAL_OSC) -#if defined(STM32F1_POG) - GPIOConfigPin(PORT_EXT_CLK, PIN_EXT_CLK, GPIO_CRL_CNF0_0); - AFIO->MAPR = (AFIO->MAPR & ~AFIO_MAPR_TIM2_REMAP) | AFIO_MAPR_TIM2_REMAP_0; -#endif -#endif - - GPIOConfigPin(PORT_USART1_TXD, PIN_USART1_TXD, GPIO_CRL_MODE0_1|GPIO_CRL_CNF0_1); - GPIOConfigPin(PORT_USART1_RXD, PIN_USART1_RXD, GPIO_CRL_CNF0_0); - - AFIO->MAPR = (AFIO->MAPR & ~AFIO_MAPR_SWJ_CFG) | AFIO_MAPR_SWJ_CFG_1; -} - - -static inline void ADCInit() -{ - RCC->CFGR = (RCC->CFGR & ~RCC_CFGR_ADCPRE_Msk) - | RCC_CFGR_ADCPRE_DIV6; // ADC clock divided by 6 (72MHz/6 = 12MHz) - RCC->APB2ENR |= RCC_APB2ENR_ADC1EN; -#if defined(SEND_RSSI_DATA) - RCC->APB2ENR |= RCC_APB2ENR_ADC2EN; -#endif - - // Init ADCs in dual mode (RSSI) -#if defined(SEND_RSSI_DATA) - ADC1->CR1 = ADC_CR1_DUALMOD_1|ADC_CR1_DUALMOD_2; // Regular simultaneous mode -#endif - - // Set sampling time to 7.5 cycles - if (PIN_RX_ADC_CH < 10) { - ADC1->SMPR2 = ADC_SMPR2_SMP0_0 << (3*PIN_RX_ADC_CH); - } else { - ADC1->SMPR1 = ADC_SMPR1_SMP10_0 << (3*PIN_RX_ADC_CH); - } -#if defined(SEND_RSSI_DATA) - if (PIN_RSSI_ADC_CH < 10) { - ADC2->SMPR2 = ADC_SMPR2_SMP0_0 << (3*PIN_RSSI_ADC_CH); - } else { - ADC2->SMPR1 = ADC_SMPR1_SMP10_0 << (3*PIN_RSSI_ADC_CH); - } -#endif - - // Set conversion channel (single conversion) - ADC1->SQR3 = PIN_RX_ADC_CH; -#if defined(SEND_RSSI_DATA) - ADC2->SQR3 = PIN_RSSI_ADC_CH; -#endif - - // Enable ADC - ADC1->CR2 |= ADC_CR2_ADON; - -#if defined(SEND_RSSI_DATA) - // Enable ADC2 - ADC2->CR2 |= ADC_CR2_ADON; -#endif - - // Start calibration - delay(6*2); - ADC1->CR2 |= ADC_CR2_CAL; - while((ADC1->CR2 & ADC_CR2_CAL) == ADC_CR2_CAL) - ; -#if defined(SEND_RSSI_DATA) - ADC2->CR2 |= ADC_CR2_CAL; - while((ADC2->CR2 & ADC_CR2_CAL) == ADC_CR2_CAL) - ; -#endif - - // Trigger first conversion - ADC1->CR2 |= ADC_CR2_ADON; -#if defined(SEND_RSSI_DATA) - ADC2->CR2 |= ADC_CR2_ADON; -#endif -} - - -static inline void DACInit() -{ - RCC->APB1ENR |= RCC_APB1ENR_DACEN; - - DAC->CR = DAC_CR_EN1; -} - - -static inline void TimerInit() -{ - RCC->APB1ENR |= RCC_APB1ENR_TIM2EN; - -#if defined(EXTERNAL_OSC) - // Enable external clock, prescaler /4 - TIM2->SMCR = TIM_SMCR_ECE | TIM_SMCR_ETPS_1; -#endif - - // TIM2 output frequency - TIM2->PSC = 0; -#if defined(EXTERNAL_OSC) - // TimerCount = ExternalOsc - // /4 (external clock prescaler) - // /SAMP_FREQ - TIM2->ARR = (uint16_t) ((EXTERNAL_OSC/(4*SAMP_FREQ)) - 1); -#else - TIM2->ARR = (uint16_t) ((SystemCoreClock/(SAMP_FREQ)) - 1); -#endif - - // Enable TIse 1%-tolerance comM2 interrupt - TIM2->DIER = TIM_DIER_UIE; - NVIC_EnableIRQ(TIM2_IRQn); - - // Enable TIM2 - TIM2->CR1 |= TIM_CR1_CEN; -} - - -void CIO::initInt() -{ - GPIOInit(); - ADCInit(); - DACInit(); -#if defined(STM32F1_POG) - FancyLEDEffect(); -#endif -} - -void CIO::startInt() -{ - TimerInit(); - - BB_COSLED = 0; - BB_LED = 1; -} - -void CIO::interrupt() -{ - TSample sample = {DC_OFFSET, MARK_NONE}; -#if defined(SEND_RSSI_DATA) - uint16_t rawRSSI = 0U; -#endif - bitband_t eoc = (bitband_t)BITBAND_PERIPH(&ADC1->SR, ADC_SR_EOS_Pos); - bitband_t adon = (bitband_t)BITBAND_PERIPH(&ADC1->CR2, ADC_CR2_ADON_Pos); -#if defined(SEND_RSSI_DATA) - bitband_t rssi_adon = (bitband_t)BITBAND_PERIPH(&ADC2->CR2, ADC_CR2_ADON_Pos); -#endif - - if (*eoc) { - // trigger next conversion - *adon = 1; -#if defined(SEND_RSSI_DATA) - *rssi_adon = 1; -#endif - - m_txBuffer.get(sample); - DAC->DHR12R1 = sample.sample; // Send the value to the DAC - - // Read value from ADC1 and ADC2 - sample.sample = ADC1->DR; // read conversion result; EOC is cleared by this read - m_rxBuffer.put(sample); -#if defined(SEND_RSSI_DATA) - rawRSSI = ADC2->DR; - m_rssiBuffer.put(rawRSSI); -#endif - - m_watchdog++; - } -} - -bool CIO::getCOSInt() -{ - return BB_COS; -} - -void CIO::setLEDInt(bool on) -{ - BB_LED = !!on; -} - -void CIO::setPTTInt(bool on) -{ - BB_PTT = !!on; -} - -void CIO::setCOSInt(bool on) -{ - BB_COSLED = !!on; -} - -void CIO::setDStarInt(bool on) -{ - BB_DSTAR = !!on; -} - -void CIO::setDMRInt(bool on) -{ - BB_DMR = !!on; -} - -void CIO::setYSFInt(bool on) -{ - BB_YSF = !!on; -} - -void CIO::setP25Int(bool on) -{ - BB_P25 = !!on; -} - -void CIO::setNXDNInt(bool on) -{ -#if defined(USE_ALTERNATE_NXDN_LEDS) - BB_YSF = !!on; - BB_P25 = !!on; -#else - BB_NXDN = !!on; -#endif -} - -void CIO::setM17Int(bool on) -{ -#if defined(USE_ALTERNATE_M17_LEDS) - BB_DSTAR = !!on; - BB_P25 = !!on; -#else - BB_M17 = !!on; -#endif -} - -void CIO::setPOCSAGInt(bool on) -{ -#if defined(USE_ALTERNATE_POCSAG_LEDS) - BB_DSTAR = !!on; - BB_DMR = !!on; -#else - BB_POCSAG = !!on; -#endif -} - -void CIO::setFMInt(bool on) -{ -#if defined(USE_ALTERNATE_FM_LEDS) - BB_DSTAR = !!on; - BB_YSF = !!on; -#endif -} - -void CIO::delayInt(unsigned int dly) -{ - delay(dly); -} - -uint8_t CIO::getCPU() const -{ - return 2U; -} - -void CIO::getUDID(uint8_t* buffer) -{ -#if defined(STM32F105xC) - ::memcpy(buffer, (void *)0x1FFFF7E8, 12U); -#endif -} - -#endif - diff --git a/MMDVM.cpp b/MMDVM.cpp index 5267c63..abc755b 100644 --- a/MMDVM.cpp +++ b/MMDVM.cpp @@ -18,7 +18,7 @@ * Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA. */ -#if defined(STM32F4XX) || defined(STM32F7XX) || defined(STM32F105xC) +#if defined(STM32F4XX) || defined(STM32F7XX) #include "Config.h" #include "Globals.h" diff --git a/Makefile.CMSIS b/Makefile.CMSIS deleted file mode 100644 index 2bce2ab..0000000 --- a/Makefile.CMSIS +++ /dev/null @@ -1,165 +0,0 @@ -# The name for the project -TARGET:=mmdvm - -# The CPU architecture (will be used for -mcpu) -MCPU:=cortex-m3 -MCU:=STM32F105xC - -# The source files of the project -CSRC:= -CXXSRC:=$(wildcard *.cpp) - -# Include directory for the system include files and system source file -SYSDIR:=system_stm32f1xx -SYSSRC:=$(SYSDIR)/system_stm32f1xx.c - -# Other include directories -INCDIR:= - -# Definitions -CDEFS:= -CXXDEFS:= - -# The name of the startup file which matches to the architecture (MCPU) -STARTUP:=$(SYSDIR)/startup_stm32f105xc.S -STARTUP_DEFS= - -# Include directory for CMSIS -CMSISDIR:=STM32F10X_Lib/CMSIS - -# Libraries -LIBDIR:= -LIBS:=-larm_cortexM3l_math - -# Name of the linker script -LDSCRIPT:=$(SYSDIR)/gcc.ld - -# Target objects and binaries directory -OBJDIR:=obj -BINDIR:=bin - -# Port definition for programming via bootloader (using stm32flash) -BL_PORT:=ttyUSB0 - - - -# Internal Variables -ELF:=$(BINDIR)/$(TARGET).elf -HEX:=$(BINDIR)/$(TARGET).hex -DIS:=$(BINDIR)/$(TARGET).dis -MAP:=$(BINDIR)/$(TARGET).map -OBJ:=$(CSRC:%.c=$(OBJDIR)/%.o) $(CXXSRC:%.cpp=$(OBJDIR)/%.o) -OBJ+=$(SYSSRC:$(SYSDIR)/%.c=$(OBJDIR)/%.o) $(STARTUP:$(SYSDIR)/%.S=$(OBJDIR)/%.o) - -# Replace standard build tools by arm tools -CC:=arm-none-eabi-gcc -CXX:=arm-none-eabi-g++ -AS:=arm-none-eabi-gcc -LD:=arm-none-eabi-g++ -OBJCOPY:=arm-none-eabi-objcopy -OBJDUMP:=arm-none-eabi-objdump -SIZE:=arm-none-eabi-size - -# Common flags -COMMON_FLAGS =-mthumb -mlittle-endian -mcpu=$(MCPU) -COMMON_FLAGS+= -Wall -COMMON_FLAGS+= -I. -I$(CMSISDIR)/Include -I$(CMSISDIR)/Device/ST/STM32F1xx/Include -I$(SYSDIR) -COMMON_FLAGS+= $(addprefix -I,$(INCDIR)) -COMMON_FLAGS+= -D$(MCU) -DMADEBYMAKEFILE -DSTM32F1 -COMMON_FLAGS+= -Os -flto -ffunction-sections -fdata-sections -COMMON_FLAGS+= -g -# Assembler flags -ASFLAGS:=$(COMMON_FLAGS) -# C flags -CFLAGS:=$(COMMON_FLAGS) $(addprefix -D,$(CDEFS)) -CFLAGS+= -std=gnu11 -nostdlib -# CXX flags -CXXFLAGS:=$(COMMON_FLAGS) $(addprefix -D,$(CXXDEFS)) -CXXFLAGS+= -nostdlib -fno-exceptions -fno-rtti -# LD flags -LDFLAGS:=$(COMMON_FLAGS) -Wl,--gc-sections -Wl,-Map=$(MAP) -Wl,--no-wchar-size-warning -LDFLAGS+= --specs=nosys.specs --specs=nano.specs -LDFLAGS+= -L$(CMSISDIR)/Lib/GCC/ $(addprefix -L,$(LIBDIR)) -LDLIBS:=-T$(LDSCRIPT) $(LIBS) - -# Dependecies -DEPENDS:=$(CSRC:%.c=$(OBJDIR)/%.d) $(CXXSRC:%.cpp=$(OBJDIR)/%.d) - - -# Additional Suffixes -.SUFFIXES: .elf .hex - -# Targets -.PHONY: all -all: GitVersion.h $(DIS) $(HEX) - $(SIZE) $(ELF) - -.PHONY: program -program: $(HEX) $(ELF) - openocd -f openocd.cfg \ - -c "program $(HEX) verify reset exit" - $(SIZE) $(ELF) - -.PHONY: program_bl -program_bl: $(HEX) $(ELF) - stm32flash -w $(HEX) -v /dev/$(BL_PORT) - $(SIZE) $(ELF) - -.PHONY: run -run: $(HEX) $(ELF) - openocd -f openocd.cfg \ - -c "init" -c "reset" -c "exit" - -.PHONY: debug -debug: $(ELF) - ./debug.sh $(ELF) - -.PHONY: clean -clean: - $(RM) $(OBJ) $(HEX) $(ELF) $(DIS) $(MAP) $(DEPENDS) GitVersion.h - -# implicit rules -.elf.hex: - $(OBJCOPY) -O ihex $< $@ - -$(OBJDIR)/%.o: %.c - $(CC) -MMD $(CFLAGS) -c $< -o $@ - -$(OBJDIR)/%.o: %.cpp - $(CXX) -MMD $(CXXFLAGS) -c $< -o $@ - -$(OBJDIR)/%.o: $(SYSDIR)/%.c - $(CC) $(CFLAGS) -c $< -o $@ - -$(OBJDIR)/%.o: $(SYSDIR)/%.S - $(AS) $(ASFLAGS) -c $< -o $@ - -# explicit rules -$(OBJDIR): - mkdir -p $(OBJDIR) - -$(BINDIR): - mkdir -p $(BINDIR) - -$(ELF): $(OBJDIR) $(BINDIR) $(OBJ) - $(LD) $(OBJ) $(LDFLAGS) $(LDLIBS) -o $@ - -$(DIS): $(ELF) - $(OBJDUMP) -S $< > $@ - -# include dependecies --include $(DEPENDS) - -# Export the current git version if the index file exists, else 000... -GitVersion.h: -ifdef SYSTEMROOT - echo #define GITVERSION "0000000" > $@ -else ifdef SystemRoot - echo #define GITVERSION "0000000" > $@ -else -ifneq ("$(wildcard .git/index)","") - echo "#define GITVERSION \"$(shell git rev-parse --short HEAD)\"" > $@ -else - echo "#define GITVERSION \"0000000\"" > $@ -endif -endif diff --git a/README.md b/README.md index 31c7997..535ab8f 100644 --- a/README.md +++ b/README.md @@ -1,6 +1,6 @@ This is the source code of the MMDVM firmware that supports D-Star, DMR, System Fusion, P25, NXDN, M17, POCSAG, AX.25, and FM modes. -It runs on the Arduino Due, the ST-Micro STM32F1xxx, STM32F4xxx and STM32F7xxx processors, as well as the Teensy 3.1/3.2/3.5/3.6. What these platforms have in common is the use of an ARM Cortex-M3, M4, or M7 processors with a minimum clock speed greater of 70 MHz, and access to at least one analogue to digital converter, one digital to analogue converter, as well as a number of GPIO pins. +It runs on the Arduino Due, the ST-Micro STM32F4xxx and STM32F7xxx processors, as well as the Teensy 3.5/3.6. What these platforms have in common is the use of an ARM Cortex-M3, M4, or M7 processors with a minimum clock speed greater of 80 MHz, and access to at least one analogue to digital converter, one digital to analogue converter, as well as a number of GPIO pins. In order to build this software for the Arduino Due, you will need to edit a file within the Arduino GUI and that is detailed in the BUILD.txt file. The STM32 support is supplied via the ARM GCC compiler. The Teensy support uses Teensyduino. diff --git a/RingBuff.h b/RingBuff.h deleted file mode 100644 index c85a6bf..0000000 --- a/RingBuff.h +++ /dev/null @@ -1,47 +0,0 @@ -/* - * Copyright (C) 2017 Wojciech Krutnik N0CALL - * - * 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, see . - * - * FIFO ring buffer - * source: - * http://stackoverflow.com/questions/6822548/correct-way-of-implementing-a-uart-receive-buffer-in-a-small-arm-microcontroller - * (modified) - * - */ - -#if !defined(RINGBUFF_H) -#define RINGBUFF_H - -#define RINGBUFF_SIZE(ringBuff) (ringBuff.size) /* serial buffer in bytes (power 2) */ -#define RINGBUFF_MASK(ringBuff) (ringBuff.size-1U) /* buffer size mask */ - -/* Buffer read / write macros */ -#define RINGBUFF_RESET(ringBuff) (ringBuff).rdIdx = ringBuff.wrIdx = 0 -#define RINGBUFF_WRITE(ringBuff, dataIn) (ringBuff).data[RINGBUFF_MASK(ringBuff) & ringBuff.wrIdx++] = (dataIn) -#define RINGBUFF_READ(ringBuff) ((ringBuff).data[RINGBUFF_MASK(ringBuff) & ((ringBuff).rdIdx++)]) -#define RINGBUFF_EMPTY(ringBuff) ((ringBuff).rdIdx == (ringBuff).wrIdx) -#define RINGBUFF_FULL(ringBuff) ((RINGBUFF_MASK(ringBuff) & ringBuff.rdIdx) == (RINGBUFF_MASK(ringBuff) & ringBuff.wrIdx)) -#define RINGBUFF_COUNT(ringBuff) (RINGBUFF_MASK(ringBuff) & ((ringBuff).wrIdx - (ringBuff).rdIdx)) - -/* Buffer type */ -#define DECLARE_RINGBUFFER_TYPE(name, _size) \ - typedef struct{ \ - uint32_t size; \ - uint32_t wrIdx; \ - uint32_t rdIdx; \ - uint8_t data[_size]; \ - }name##_t - -#endif diff --git a/RingBuffer.h b/RingBuffer.h index 79f7814..a76caf0 100644 --- a/RingBuffer.h +++ b/RingBuffer.h @@ -24,15 +24,12 @@ #include "stm32f4xx.h" #elif defined(STM32F7XX) #include "stm32f7xx.h" -#elif defined(STM32F105xC) -#include "stm32f1xx.h" -#include #else #include #undef PI #endif -#if defined(__SAM3X8E__) || defined(STM32F105xC) +#if defined(__SAM3X8E__) #define ARM_MATH_CM3 #elif defined(STM32F7XX) #define ARM_MATH_CM7 @@ -74,4 +71,4 @@ private: #include "RingBuffer.impl.h" -#endif \ No newline at end of file +#endif diff --git a/STM32F10X_Lib b/STM32F10X_Lib deleted file mode 160000 index 417e0c2..0000000 --- a/STM32F10X_Lib +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 417e0c2f4a4571ff836d2705d7551bd07ebbf777 diff --git a/SerialSTM_CMSIS.cpp b/SerialSTM_CMSIS.cpp deleted file mode 100644 index 2ca6070..0000000 --- a/SerialSTM_CMSIS.cpp +++ /dev/null @@ -1,170 +0,0 @@ -/* - * Copyright (C) 2017 by Wojciech Krutnik N0CALL - * - * 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 2 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., 675 Mass Ave, Cambridge, MA 02139, USA. - */ - -#include "Config.h" -#include "Globals.h" -#include "RingBuff.h" - -#include "SerialPort.h" - -/* -Pin definitions (configuration in IOSTM_CMSIS.c): - -- Host communication: -USART1 - TXD PA9 - RXD PA10 - -*/ - - -#if defined(STM32F1) - -// BaudRate calculator macro -// source: STM32 HAL Library (stm32f1xx_hal_usart.h) -#define USART_DIV(__PCLK__, __BAUD__) (((__PCLK__)*25)/(4*(__BAUD__))) -#define USART_DIVMANT(__PCLK__, __BAUD__) (USART_DIV((__PCLK__), (__BAUD__))/100) -#define USART_DIVFRAQ(__PCLK__, __BAUD__) (((USART_DIV((__PCLK__), (__BAUD__)) - (USART_DIVMANT((__PCLK__), (__BAUD__)) * 100)) * 16 + 50) / 100) -#define USART_BRR(__PCLK__, __BAUD__) ((USART_DIVMANT((__PCLK__), (__BAUD__)) << 4)|(USART_DIVFRAQ((__PCLK__), (__BAUD__)) & 0x0F)) - -#define USART_BUFFER_SIZE 256U -DECLARE_RINGBUFFER_TYPE(USARTBuffer, USART_BUFFER_SIZE); - -/* ************* USART1 ***************** */ -static volatile USARTBuffer_t txBuffer1={.size=USART_BUFFER_SIZE}; -static volatile USARTBuffer_t rxBuffer1={.size=USART_BUFFER_SIZE}; - - -extern "C" { - bitband_t txe = (bitband_t)BITBAND_PERIPH(&USART1->SR, USART_SR_TXE_Pos); - bitband_t rxne = (bitband_t)BITBAND_PERIPH(&USART1->SR, USART_SR_RXNE_Pos); - bitband_t txeie = (bitband_t)BITBAND_PERIPH(&USART1->CR1, USART_CR1_TXEIE_Pos); - - RAMFUNC void USART1_IRQHandler() - { - /* Transmitting data */ - if(*txe){ - if(!(RINGBUFF_EMPTY(txBuffer1))){ - USART1->DR = RINGBUFF_READ(txBuffer1); - }else{ /* Buffer empty */ - *txeie = 0; /* Don't send further data */ - } - } - - /* Receiving data */ - if(*rxne){ - RINGBUFF_WRITE(rxBuffer1, USART1->DR); - } - } -} - - -void USART1Init(int speed) -{ - RCC->APB2ENR |= RCC_APB2ENR_USART1EN; - - USART1->BRR = USART_BRR(72000000UL, speed); - - USART1->CR1 = USART_CR1_UE | USART_CR1_TE | - USART_CR1_RE | USART_CR1_RXNEIE; // Enable USART and RX interrupt - NVIC_EnableIRQ(USART1_IRQn); -} - -RAMFUNC void USART1TxData(const uint8_t* data, uint16_t length) -{ - NVIC_DisableIRQ(USART1_IRQn); - - /* Check remaining space in buffer */ - if(RINGBUFF_COUNT(txBuffer1) + length > RINGBUFF_SIZE(txBuffer1)){ - NVIC_EnableIRQ(USART1_IRQn); - return; - } - - /* Append data to buffer */ - while(length--){ - RINGBUFF_WRITE(txBuffer1, *(data++)); - } - - /* Start sending data */ - USART1->CR1 |= USART_CR1_TXEIE; - - NVIC_EnableIRQ(USART1_IRQn); -} - - -///////////////////////////////////////////////////////////////// - -void CSerialPort::beginInt(uint8_t n, int speed) -{ - switch (n) { - case 1U: - USART1Init(speed); - break; - default: - break; - } -} - -int CSerialPort::availableForReadInt(uint8_t n) -{ - switch (n) { - case 1U: - return !RINGBUFF_EMPTY(rxBuffer1); - default: - return false; - } -} - -int CSerialPort::availableForWriteInt(uint8_t n) -{ - switch (n) { - case 1U: - return !RINGBUFF_FULL(txBuffer1); - default: - return false; - } -} - -uint8_t CSerialPort::readInt(uint8_t n) -{ - switch (n) { - case 1U: - return RINGBUFF_READ(rxBuffer1); - default: - return 0U; - } -} - -void CSerialPort::writeInt(uint8_t n, const uint8_t* data, uint16_t length, bool flush) -{ - bitband_t tc = (bitband_t)BITBAND_PERIPH(&USART1->SR, USART_SR_TC_Pos); - - switch (n) { - case 1U: - USART1TxData(data, length); - *tc = 0; - - if (flush) { - while (!RINGBUFF_EMPTY(txBuffer1) || !tc) - ; - } - break; - default: - break; - } -} - -#endif diff --git a/Utils.h b/Utils.h index d8ebdd2..a3c30b7 100644 --- a/Utils.h +++ b/Utils.h @@ -23,9 +23,6 @@ #include "stm32f4xx.h" #elif defined(STM32F7XX) #include "stm32f7xx.h" -#elif defined(STM32F105xC) -#include "stm32f1xx.h" -#include #else #include #endif diff --git a/mmdvmmenu.sh b/mmdvmmenu.sh deleted file mode 100755 index 7c31b4a..0000000 --- a/mmdvmmenu.sh +++ /dev/null @@ -1,98 +0,0 @@ -#!/bin/bash - -############################################################################### -# -# mmdvmmenu.sh -# -# Copyright (C) 2016 by Paul Nannery KC2VRJ -# -# 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 2 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., 675 Mass Ave, Cambridge, MA 02139, USA. -# -############################################################################### -# -# On a Linux based system, such as a Raspberry Pi, this script will perform -# Modification of the Config.h file for most options. It makes a Back up when -# you start the script if none is present. You must recompile and load firmware -# onto the Arduino Due if changes are made. -# -############################################################################### -# -# CONFIGURATION -# -# Location of Config.h -conf=Config.h -#Location of backup file -confbak=Config.h.bak - -################################################################################ -# -# Do not edit below here -# -############################################################################### - - - -# Check for backup file and make one if not present - -if [ ! -f $confbak ];then - -cp -f $conf $confbak - -fi - -while : -do - clear - cat< $conf.tmp && mv -f $conf.tmp $conf && echo "12.000 MHz clock enabled";; - "2") sed -e 's/\/\/ #define EXTERNAL_OSC 12288000/#define EXTERNAL_OSC 12288000/' $conf > $conf.tmp && mv -f $conf.tmp $conf && echo "12.288 MHz clock enabled";; - "3") sed -e 's/\/\/ #define EXTERNAL_OSC 14400000/#define EXTERNAL_OSC 14400000/' $conf > $conf.tmp && mv -f $conf.tmp $conf && echo "14.400 MHz clock enabled";; - "4") sed -e 's/\/\/ #define EXTERNAL_OSC 19200000/#define EXTERNAL_OSC 19200000/' $conf > $conf.tmp && mv -f $conf.tmp $conf && echo "19.200 MHz clock enabled";; - "5") sed -e 's/\/\/ #define USE_COS_AS_LOCKOUT /#define USE_COS_AS_LOCKOUT/' $conf > $conf.tmp && mv -f $conf.tmp $conf && echo "COS as Lockout enabled";; - "6") sed -e 's/\/\/ #define MODE_LEDS/#define MODE_LEDS/' $conf > $conf.tmp && mv -f $conf.tmp $conf && echo "Mode pins enabled";; - "7") sed -e 's/\/\/ #define ARDUINO_DUE_PAPA/#define ARDUINO_DUE_PAPA/' $conf > $conf.tmp && mv -f $conf.tmp $conf && echo "Layout for the PAPA board enabled";; - "8") sed -e 's/\/\/ #define ARDUINO_DUE_ZUM_V10/#define ARDUINO_DUE_ZUM_V10/' $conf > $conf.tmp && mv -f $conf.tmp $conf && echo "Layout for ZUM V1.0 and V1.0.1 boards enabled";; - "9") sed -e 's/\/\/ #define ARDUINO_DUE_NTH/#define ARDUINO_DUE_NTH/' $conf > $conf.tmp && mv -f $conf.tmp $conf && echo "Layout for SP8NTH board enabled";; - "0") sed -e 's/\/\/ #define SERIAL_REPEATER/#define SERIAL_REPEATER/' $conf > $conf.tmp && mv -f $conf.tmp $conf && echo "Modem display driver enabled";; - "A") mv -f $confbak $conf ;; - "a") mv -f $confbak $conf ;; - "Q") echo "If any changes are made you need to (re-)upload the firmware to MMDVM" && exit;; - "q") echo "If any changes are made you need to (re-)upload the firmware to MMDVM" && exit;; - * ) echo "invalid option" ;; - esac - sleep 1 -done diff --git a/system_stm32f1xx/gcc.ld b/system_stm32f1xx/gcc.ld deleted file mode 100644 index 0beee5e..0000000 --- a/system_stm32f1xx/gcc.ld +++ /dev/null @@ -1,187 +0,0 @@ -/* Linker script to configure memory regions. - * STM32F105RB - */ -MEMORY -{ - FLASH (rx) : ORIGIN = 0x8000000, LENGTH = 128K - RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -/* Linker script to place sections and symbol values. Should be used together - * with other linker script that defines memory regions FLASH and RAM. - * It references following symbols, which must be defined in code: - * Reset_Handler : Entry of reset handler - * - * It defines following symbols, which code can use without definition: - * __exidx_start - * __exidx_end - * __copy_table_start__ - * __copy_table_end__ - * __zero_table_start__ - * __zero_table_end__ - * __etext - * __data_start__ - * __preinit_array_start - * __preinit_array_end - * __init_array_start - * __init_array_end - * __fini_array_start - * __fini_array_end - * __data_end__ - * __bss_start__ - * __bss_end__ - * __end__ - * end - * __HeapLimit - * __StackLimit - * __StackTop - * __stack - */ -ENTRY(Reset_Handler) - -SECTIONS -{ - .text : - { - KEEP(*(.isr_vector)) - *(.text*) - - KEEP(*(.init)) - KEEP(*(.fini)) - - /* .ctors */ - *crtbegin.o(.ctors) - *crtbegin?.o(.ctors) - *(EXCLUDE_FILE(*crtend?.o *crtend.o) .ctors) - *(SORT(.ctors.*)) - *(.ctors) - - /* .dtors */ - *crtbegin.o(.dtors) - *crtbegin?.o(.dtors) - *(EXCLUDE_FILE(*crtend?.o *crtend.o) .dtors) - *(SORT(.dtors.*)) - *(.dtors) - - *(.rodata*) - - KEEP(*(.eh_frame*)) - } > FLASH - - .ARM.extab : - { - *(.ARM.extab* .gnu.linkonce.armextab.*) - } > FLASH - - __exidx_start = .; - .ARM.exidx : - { - *(.ARM.exidx* .gnu.linkonce.armexidx.*) - } > FLASH - __exidx_end = .; - - /* To copy multiple ROM to RAM sections, - * uncomment .copy.table section and, - * define __STARTUP_COPY_MULTIPLE in startup_ARMCMx.S */ - /* - .copy.table : - { - . = ALIGN(4); - __copy_table_start__ = .; - LONG (__etext) - LONG (__data_start__) - LONG (__data_end__ - __data_start__) - LONG (__etext2) - LONG (__data2_start__) - LONG (__data2_end__ - __data2_start__) - __copy_table_end__ = .; - } > FLASH - */ - - /* To clear multiple BSS sections, - * uncomment .zero.table section and, - * define __STARTUP_CLEAR_BSS_MULTIPLE in startup_ARMCMx.S */ - /* - .zero.table : - { - . = ALIGN(4); - __zero_table_start__ = .; - LONG (__bss_start__) - LONG (__bss_end__ - __bss_start__) - LONG (__bss2_start__) - LONG (__bss2_end__ - __bss2_start__) - __zero_table_end__ = .; - } > FLASH - */ - - __etext = .; - - .data : AT (__etext) - { - __data_start__ = .; - *(vtable) - *(.data*) - - . = ALIGN(4); - /* preinit data */ - PROVIDE_HIDDEN (__preinit_array_start = .); - KEEP(*(.preinit_array)) - PROVIDE_HIDDEN (__preinit_array_end = .); - - . = ALIGN(4); - /* init data */ - PROVIDE_HIDDEN (__init_array_start = .); - KEEP(*(SORT(.init_array.*))) - KEEP(*(.init_array)) - PROVIDE_HIDDEN (__init_array_end = .); - - - . = ALIGN(4); - /* finit data */ - PROVIDE_HIDDEN (__fini_array_start = .); - KEEP(*(SORT(.fini_array.*))) - KEEP(*(.fini_array)) - PROVIDE_HIDDEN (__fini_array_end = .); - - KEEP(*(.jcr*)) - . = ALIGN(4); - /* All data end */ - __data_end__ = .; - - } > RAM - - .bss : - { - . = ALIGN(4); - __bss_start__ = .; - *(.bss*) - *(COMMON) - . = ALIGN(4); - __bss_end__ = .; - } > RAM - - .heap (COPY): - { - __end__ = .; - PROVIDE(end = .); - *(.heap*) - __HeapLimit = .; - } > RAM - - /* .stack_dummy section doesn't contains any symbols. It is only - * used for linker to calculate size of stack sections, and assign - * values to stack symbols later */ - .stack_dummy (COPY): - { - *(.stack*) - } > RAM - - /* Set stack top to end of RAM, and stack limit move down by - * size of stack_dummy section */ - __StackTop = ORIGIN(RAM) + LENGTH(RAM); - __StackLimit = __StackTop - SIZEOF(.stack_dummy); - PROVIDE(__stack = __StackTop); - - /* Check if data + heap + stack exceeds RAM limit */ - ASSERT(__StackLimit >= __HeapLimit, "region RAM overflowed with stack") -} diff --git a/system_stm32f1xx/startup_stm32f105xc.S b/system_stm32f1xx/startup_stm32f105xc.S deleted file mode 100644 index 72acb22..0000000 --- a/system_stm32f1xx/startup_stm32f105xc.S +++ /dev/null @@ -1,427 +0,0 @@ -/* File: startup_ARMCM3.S - * Purpose: startup file for Cortex-M3 devices. Should use with - * GCC for ARM Embedded Processors - * Version: V2.0 - * Date: 16 August 2013 - */ -/* Copyright (c) 2011 - 2013 ARM LIMITED - - All rights reserved. - Redistribution and use in source and binary forms, with or without - modification, are permitted provided that the following conditions are met: - - Redistributions of source code must retain the above copyright - notice, this list of conditions and the following disclaimer. - - Redistributions in binary form must reproduce the above copyright - notice, this list of conditions and the following disclaimer in the - documentation and/or other materials provided with the distribution. - - Neither the name of ARM nor the names of its contributors may be used - to endorse or promote products derived from this software without - specific prior written permission. - * - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE - LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - POSSIBILITY OF SUCH DAMAGE. - ---------------------------------------------------------------------------*/ -#if defined(STM32F105xC) - - .syntax unified - .arch armv7-m - - .section .stack - .align 3 -#ifdef __STACK_SIZE - .equ Stack_Size, __STACK_SIZE -#else - .equ Stack_Size, 0xc00 -#endif - .globl __StackTop - .globl __StackLimit -__StackLimit: - .space Stack_Size - .size __StackLimit, . - __StackLimit -__StackTop: - .size __StackTop, . - __StackTop - - .section .heap - .align 3 -#ifdef __HEAP_SIZE - .equ Heap_Size, __HEAP_SIZE -#else - .equ Heap_Size, 0 -#endif - .globl __HeapBase - .globl __HeapLimit -__HeapBase: - .if Heap_Size - .space Heap_Size - .endif - .size __HeapBase, . - __HeapBase -__HeapLimit: - .size __HeapLimit, . - __HeapLimit - - -.equ BootRAM, 0xF1E0F85F - - .section .isr_vector - .align 2 - .globl __isr_vector -__isr_vector: - .long __StackTop /* Top of Stack */ - .long Reset_Handler /* Reset Handler */ - .long NMI_Handler /* NMI Handler */ - .long HardFault_Handler /* Hard Fault Handler */ - .long MemManage_Handler /* MPU Fault Handler */ - .long BusFault_Handler /* Bus Fault Handler */ - .long UsageFault_Handler /* Usage Fault Handler */ - .long 0 /* Reserved */ - .long 0 /* Reserved */ - .long 0 /* Reserved */ - .long 0 /* Reserved */ - .long SVC_Handler /* SVCall Handler */ - .long DebugMon_Handler /* Debug Monitor Handler */ - .long 0 /* Reserved */ - .long PendSV_Handler /* PendSV Handler */ - .long SysTick_Handler /* SysTick Handler */ - - /* External interrupts */ - .long WWDG_IRQHandler - .long PVD_IRQHandler - .long TAMPER_IRQHandler - .long RTC_IRQHandler - .long FLASH_IRQHandler - .long RCC_IRQHandler - .long EXTI0_IRQHandler - .long EXTI1_IRQHandler - .long EXTI2_IRQHandler - .long EXTI3_IRQHandler - .long EXTI4_IRQHandler - .long DMA1_Channel1_IRQHandler - .long DMA1_Channel2_IRQHandler - .long DMA1_Channel3_IRQHandler - .long DMA1_Channel4_IRQHandler - .long DMA1_Channel5_IRQHandler - .long DMA1_Channel6_IRQHandler - .long DMA1_Channel7_IRQHandler - .long ADC1_2_IRQHandler - .long CAN1_TX_IRQHandler - .long CAN1_RX0_IRQHandler - .long CAN1_RX1_IRQHandler - .long CAN1_SCE_IRQHandler - .long EXTI9_5_IRQHandler - .long TIM1_BRK_IRQHandler - .long TIM1_UP_IRQHandler - .long TIM1_TRG_COM_IRQHandler - .long TIM1_CC_IRQHandler - .long TIM2_IRQHandler - .long TIM3_IRQHandler - .long TIM4_IRQHandler - .long I2C1_EV_IRQHandler - .long I2C1_ER_IRQHandler - .long I2C2_EV_IRQHandler - .long I2C2_ER_IRQHandler - .long SPI1_IRQHandler - .long SPI2_IRQHandler - .long USART1_IRQHandler - .long USART2_IRQHandler - .long USART3_IRQHandler - .long EXTI15_10_IRQHandler - .long RTC_Alarm_IRQHandler - .long OTG_FS_WKUP_IRQHandler - .long 0 - .long 0 - .long 0 - .long 0 - .long 0 - .long 0 - .long 0 - .long TIM5_IRQHandler - .long SPI3_IRQHandler - .long UART4_IRQHandler - .long UART5_IRQHandler - .long TIM6_IRQHandler - .long TIM7_IRQHandler - .long DMA2_Channel1_IRQHandler - .long DMA2_Channel2_IRQHandler - .long DMA2_Channel3_IRQHandler - .long DMA2_Channel4_IRQHandler - .long DMA2_Channel5_IRQHandler - .long 0 - .long 0 - .long CAN2_TX_IRQHandler - .long CAN2_RX0_IRQHandler - .long CAN2_RX1_IRQHandler - .long CAN2_SCE_IRQHandler - .long OTG_FS_IRQHandler - .long 0 - .long 0 - .long 0 - .long 0 - .long 0 - .long 0 - .long 0 - .long 0 - .long 0 - .long 0 - .long 0 - .long 0 - .long 0 - .long 0 - .long 0 - .long 0 - .long 0 - .long 0 - .long 0 - .long 0 - .long 0 - .long 0 - .long 0 - .long 0 - .long 0 - .long 0 - .long 0 - .long 0 - .long 0 - .long 0 - .long 0 - .long 0 - .long 0 - .long 0 - .long 0 - .long 0 - .long BootRAM /* @0x1E0. This is for boot in RAM mode for - STM32F10x Connectivity line Devices. */ - - .size __isr_vector, . - __isr_vector - - .text - .thumb - .thumb_func - .align 2 - .globl Reset_Handler - .type Reset_Handler, %function -Reset_Handler: -/* Firstly it copies data from read only memory to RAM. There are two schemes - * to copy. One can copy more than one sections. Another can only copy - * one section. The former scheme needs more instructions and read-only - * data to implement than the latter. - * Macro __STARTUP_COPY_MULTIPLE is used to choose between two schemes. */ - -#ifdef __STARTUP_COPY_MULTIPLE -/* Multiple sections scheme. - * - * Between symbol address __copy_table_start__ and __copy_table_end__, - * there are array of triplets, each of which specify: - * offset 0: LMA of start of a section to copy from - * offset 4: VMA of start of a section to copy to - * offset 8: size of the section to copy. Must be multiply of 4 - * - * All addresses must be aligned to 4 bytes boundary. - */ - ldr r4, =__copy_table_start__ - ldr r5, =__copy_table_end__ - -.L_loop0: - cmp r4, r5 - bge .L_loop0_done - ldr r1, [r4] - ldr r2, [r4, #4] - ldr r3, [r4, #8] - -.L_loop0_0: - subs r3, #4 - ittt ge - ldrge r0, [r1, r3] - strge r0, [r2, r3] - bge .L_loop0_0 - - adds r4, #12 - b .L_loop0 - -.L_loop0_done: -#else -/* Single section scheme. - * - * The ranges of copy from/to are specified by following symbols - * __etext: LMA of start of the section to copy from. Usually end of text - * __data_start__: VMA of start of the section to copy to - * __data_end__: VMA of end of the section to copy to - * - * All addresses must be aligned to 4 bytes boundary. - */ - ldr r1, =__etext - ldr r2, =__data_start__ - ldr r3, =__data_end__ - -.L_loop1: - cmp r2, r3 - ittt lt - ldrlt r0, [r1], #4 - strlt r0, [r2], #4 - blt .L_loop1 -#endif /*__STARTUP_COPY_MULTIPLE */ - -/* This part of work usually is done in C library startup code. Otherwise, - * define this macro to enable it in this startup. - * - * There are two schemes too. One can clear multiple BSS sections. Another - * can only clear one section. The former is more size expensive than the - * latter. - * - * Define macro __STARTUP_CLEAR_BSS_MULTIPLE to choose the former. - * Otherwise efine macro __STARTUP_CLEAR_BSS to choose the later. - */ -#ifdef __STARTUP_CLEAR_BSS_MULTIPLE -/* Multiple sections scheme. - * - * Between symbol address __copy_table_start__ and __copy_table_end__, - * there are array of tuples specifying: - * offset 0: Start of a BSS section - * offset 4: Size of this BSS section. Must be multiply of 4 - */ - ldr r3, =__zero_table_start__ - ldr r4, =__zero_table_end__ - -.L_loop2: - cmp r3, r4 - bge .L_loop2_done - ldr r1, [r3] - ldr r2, [r3, #4] - movs r0, 0 - -.L_loop2_0: - subs r2, #4 - itt ge - strge r0, [r1, r2] - bge .L_loop2_0 - - adds r3, #8 - b .L_loop2 -.L_loop2_done: -#elif defined (__STARTUP_CLEAR_BSS) -/* Single BSS section scheme. - * - * The BSS section is specified by following symbols - * __bss_start__: start of the BSS section. - * __bss_end__: end of the BSS section. - * - * Both addresses must be aligned to 4 bytes boundary. - */ - ldr r1, =__bss_start__ - ldr r2, =__bss_end__ - - movs r0, 0 -.L_loop3: - cmp r1, r2 - itt lt - strlt r0, [r1], #4 - blt .L_loop3 -#endif /* __STARTUP_CLEAR_BSS_MULTIPLE || __STARTUP_CLEAR_BSS */ - -#ifndef __NO_SYSTEM_INIT - bl SystemInit -#endif - -#ifndef __START -#define __START _start -#endif - bl __START - - .pool - .size Reset_Handler, . - Reset_Handler - - .align 1 - .thumb_func - .weak Default_Handler - .type Default_Handler, %function -Default_Handler: - b . - .size Default_Handler, . - Default_Handler - -/* Macro to define default handlers. Default handler - * will be weak symbol and just dead loops. They can be - * overwritten by other handlers */ - .macro def_irq_handler handler_name - .weak \handler_name - .set \handler_name, Default_Handler - .endm - - def_irq_handler NMI_Handler - def_irq_handler HardFault_Handler - def_irq_handler MemManage_Handler - def_irq_handler BusFault_Handler - def_irq_handler UsageFault_Handler - def_irq_handler SVC_Handler - def_irq_handler DebugMon_Handler - def_irq_handler PendSV_Handler - def_irq_handler SysTick_Handler - def_irq_handler WWDG_IRQHandler - def_irq_handler PVD_IRQHandler - def_irq_handler TAMPER_IRQHandler - def_irq_handler RTC_IRQHandler - def_irq_handler FLASH_IRQHandler - def_irq_handler RCC_IRQHandler - def_irq_handler EXTI0_IRQHandler - def_irq_handler EXTI1_IRQHandler - def_irq_handler EXTI2_IRQHandler - def_irq_handler EXTI3_IRQHandler - def_irq_handler EXTI4_IRQHandler - def_irq_handler DMA1_Channel1_IRQHandler - def_irq_handler DMA1_Channel2_IRQHandler - def_irq_handler DMA1_Channel3_IRQHandler - def_irq_handler DMA1_Channel4_IRQHandler - def_irq_handler DMA1_Channel5_IRQHandler - def_irq_handler DMA1_Channel6_IRQHandler - def_irq_handler DMA1_Channel7_IRQHandler - def_irq_handler ADC1_2_IRQHandler - def_irq_handler CAN1_TX_IRQHandler - def_irq_handler CAN1_RX0_IRQHandler - def_irq_handler CAN1_RX1_IRQHandler - def_irq_handler CAN1_SCE_IRQHandler - def_irq_handler EXTI9_5_IRQHandler - def_irq_handler TIM1_BRK_IRQHandler - def_irq_handler TIM1_UP_IRQHandler - def_irq_handler TIM1_TRG_COM_IRQHandler - def_irq_handler TIM1_CC_IRQHandler - def_irq_handler TIM2_IRQHandler - def_irq_handler TIM3_IRQHandler - def_irq_handler TIM4_IRQHandler - def_irq_handler I2C1_EV_IRQHandler - def_irq_handler I2C1_ER_IRQHandler - def_irq_handler I2C2_EV_IRQHandler - def_irq_handler I2C2_ER_IRQHandler - def_irq_handler SPI1_IRQHandler - def_irq_handler SPI2_IRQHandler - def_irq_handler USART1_IRQHandler - def_irq_handler USART2_IRQHandler - def_irq_handler USART3_IRQHandler - def_irq_handler EXTI15_10_IRQHandler - def_irq_handler RTC_Alarm_IRQHandler - def_irq_handler OTG_FS_WKUP_IRQHandler - def_irq_handler TIM5_IRQHandler - def_irq_handler SPI3_IRQHandler - def_irq_handler UART4_IRQHandler - def_irq_handler UART5_IRQHandler - def_irq_handler TIM6_IRQHandler - def_irq_handler TIM7_IRQHandler - def_irq_handler DMA2_Channel1_IRQHandler - def_irq_handler DMA2_Channel2_IRQHandler - def_irq_handler DMA2_Channel3_IRQHandler - def_irq_handler DMA2_Channel4_IRQHandler - def_irq_handler DMA2_Channel5_IRQHandler - def_irq_handler CAN2_TX_IRQHandler - def_irq_handler CAN2_RX0_IRQHandler - def_irq_handler CAN2_RX1_IRQHandler - def_irq_handler CAN2_SCE_IRQHandler - def_irq_handler OTG_FS_IRQHandler - - .end - -#endif diff --git a/system_stm32f1xx/system_stm32f1xx.c b/system_stm32f1xx/system_stm32f1xx.c deleted file mode 100644 index b18e9bf..0000000 --- a/system_stm32f1xx/system_stm32f1xx.c +++ /dev/null @@ -1,227 +0,0 @@ -/** - ****************************************************************************** - * @file system_stm32f1xx.c - * @author MCD Application Team, Wojciech Krutnik - * @version V2.2.2 - * @date 26-June-2015 - * @brief CMSIS Cortex-M0 Device Peripheral Access Layer System Source File. - * - * 1. This file provides two functions and one global variable to be called from - * user application: - * - SystemInit(): This function is called at startup just after reset and - * before branch to main program. This call is made inside - * the "startup_stm32f1xx.s" file. - * - * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used - * by the user application to setup the SysTick - * timer or configure other parameters. - * - * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must - * be called whenever the core clock is changed - * during program execution. - * - * 2. After each device reset the HSI (8 MHz) is used as system clock source. - * Then SystemInit() function is called, in "startup_stm32f1xx.s" file, to - * configure the system clock before to branch to main program. - * - * 3. This file configures the system clock and flash as follows: - *============================================================================= - * Supported STM32F1xx device - *----------------------------------------------------------------------------- - * System Clock source | PLL - *----------------------------------------------------------------------------- - * SYSCLK | 72MHz - *----------------------------------------------------------------------------- - * HCLK | 72Mhz - *----------------------------------------------------------------------------- - * PCLK1 | 36MHz - *----------------------------------------------------------------------------- - * PCLK2 | 72MHz - *----------------------------------------------------------------------------- - * AHB Prescaler | 1 - *----------------------------------------------------------------------------- - * APB1 Prescaler | 2 - *----------------------------------------------------------------------------- - * APB2 Prescaler | 1 - *----------------------------------------------------------------------------- - * PLLSRC | HSE/1 - *----------------------------------------------------------------------------- - * PLLMUL | 9 - *----------------------------------------------------------------------------- - * HSE | 8MHz - *----------------------------------------------------------------------------- - * Flash Latency(WS) | 2 - *----------------------------------------------------------------------------- - * Prefetch Buffer | ON - *----------------------------------------------------------------------------- - *============================================================================= - ****************************************************************************** - * @attention - * - *

© COPYRIGHT(c) 2015 STMicroelectronics

- * - * Redistribution and use in source and binary forms, with or without modification, - * are permitted provided that the following conditions are met: - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR - * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, - * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE - * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************** - */ -#if defined(STM32F105xC) - -/** @addtogroup CMSIS - * @{ - */ - -/** @addtogroup stm32f1xx_system - * @{ - */ - -/** @addtogroup STM32F1xx_System_Private_Includes - * @{ - */ - -#include "stm32f1xx.h" - -/** - * @} - */ - -/** @addtogroup STM32F1xx_System_Private_TypesDefinitions - * @{ - */ - -/** - * @} - */ - -/** @addtogroup STM32F1xx_System_Private_Defines - * @{ - */ -#if !defined (HSE_VALUE) - #define HSE_VALUE ((uint32_t)8000000) /*!< Default value of the External oscillator in Hz. - This value can be provided and adapted by the user application. */ -#endif /* HSE_VALUE */ - -#if !defined (HSI_VALUE) - #define HSI_VALUE ((uint32_t)8000000) /*!< Default value of the Internal oscillator in Hz. - This value can be provided and adapted by the user application. */ -#endif /* HSI_VALUE */ -/** - * @} - */ - -/** @addtogroup STM32f1xx_System_Private_Macros - * @{ - */ - -/** - * @} - */ - -/** @addtogroup STM32F1xx_System_Private_Variables - * @{ - */ - -uint32_t SystemCoreClock = 48000000; - -/** - * @} - */ - -/** @addtogroup STM32F1xx_System_Private_FunctionPrototypes - * @{ - */ - -static void SetSysClock(void); - -/** - * @} - */ - -/** @addtogroup STM32F1xx_System_Private_Functions - * @{ - */ - -/** - * @brief Setup the microcontroller system. - * Initialize the default HSI clock source, vector table location and the PLL configuration is reset. - * @param None - * @retval None - */ -void SystemInit(void) -{ - /* Enable Prefetch Buffer, 2 wait states */ - FLASH->ACR = FLASH_ACR_PRFTBE | FLASH_ACR_LATENCY_1; - - /* Configure the System clock frequency, AHB/APBx prescalers */ - SetSysClock(); -} - - -/** - * @brief Configures the System clock frequency and AHB/APBx prescalers - * settings. - * @param None - * @retval None - */ -static void SetSysClock(void) -{ - /* Enable HSE and Clock Security System */ - RCC->CR |= RCC_CR_CSSON | RCC_CR_HSEON; - /* Wait for HSE startup */ - while((RCC->CR & RCC_CR_HSERDY) == 0) - ; - - /* Enable PLL with 9x multiplier and HSE clock source - * APB1 prescaler /2 */ - RCC->CFGR = (RCC->CFGR & (~RCC_CFGR_PLLMULL)) | RCC_CFGR_PLLMULL9 - | RCC_CFGR_PLLSRC; - RCC->CR |= RCC_CR_PLLON; - while((RCC->CR & RCC_CR_PLLRDY) == 0) - ; - - /* HCLK = SYSCLK */ - RCC->CFGR = (RCC->CFGR & ~RCC_CFGR_HPRE) | RCC_CFGR_HPRE_DIV1; - /* PCLK1 = HCLK/2; PCLK2 = HCLK */ - RCC->CFGR = (RCC->CFGR & ~(RCC_CFGR_PPRE1|RCC_CFGR_PPRE2)) - | RCC_CFGR_PPRE1_DIV2; - - /* Switch SYSCLK to PLL */ - RCC->CFGR |= RCC_CFGR_SW_PLL; - while((RCC->CFGR & RCC_CFGR_SWS) != RCC_CFGR_SWS_PLL) - ; -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ -