diff --git a/platformio.ini b/platformio.ini index 1e71bca4..df226088 100644 --- a/platformio.ini +++ b/platformio.ini @@ -62,13 +62,6 @@ lib_deps = EEPROM, FlexCAN_T4, Time test_build_src = yes test_ignore = test_table3d_native -;Not currently working -;[env:LaunchPad_tm4c1294ncpdt] -;platform = titiva -;framework = energia -;board = lptm4c1294ncpdt -;lib_deps = EEPROM - ;STM32 Official core [env:black_F407VE] platform = ststm32 @@ -148,15 +141,6 @@ board = adafruit_feather_m4_can build_flags = -DUSE_LIBDIVIDE -fpermissive -std=gnu++11 upload_protocol = sam-ba - -;Support for the stm32f407 doesn't look ready in platformio yet -;[env:genericSTM32F407VE] -;platform = https://github.com/maichaell/platform-ststm32 -;framework = arduino -;board = disco_f407vg -;lib_deps = EEPROM -;build_flags = -DUSE_LIBDIVIDE -fpermissive -std=gnu++11 -DUSE_STM32GENERIC -DMENU_USB_SERIAL - [env:custom_monitor_speedrate] monitor_speed = 115200 @@ -170,7 +154,6 @@ default_envs = megaatmega2560 ;env_default = LaunchPad_tm4c1294ncpdt ;env_default = genericSTM32F103RB ;env_default = bluepill_f103c8 -;env_default = black_F401CC [env:native] platform = native diff --git a/speeduino/board_stm32_generic.cpp b/speeduino/board_stm32_generic.cpp deleted file mode 100644 index 18500de1..00000000 --- a/speeduino/board_stm32_generic.cpp +++ /dev/null @@ -1,205 +0,0 @@ -#if defined(CORE_STM32_GENERIC) -#include "board_stm32_generic.h" -#include "globals.h" -#include "auxiliaries.h" -#include "idle.h" -#include "scheduler.h" -#include "HardwareTimer.h" - - #if defined(FRAM_AS_EEPROM) - #if defined(STM32F407xx) - FramClass EEPROM(PB5, PB4, PB3, PB0); /*(mosi, miso, sclk, ssel, clockspeed) 31/01/2020*/ - #else - FramClass EEPROM(PB15, PB14, PB13, PB12); //Blue/Black Pills - #endif - #endif - -void initBoard() -{ - /* - *********************************************************************************************************** - * General - */ - #ifndef FLASH_LENGTH - #define FLASH_LENGTH 8192 - #endif - delay(10); - /* - *********************************************************************************************************** - * Idle - */ - if( (configPage6.iacAlgorithm == IAC_ALGORITHM_PWM_OL) || (configPage6.iacAlgorithm == IAC_ALGORITHM_PWM_CL) ) - { - idle_pwm_max_count = 1000000L / (TIMER_RESOLUTION * configPage6.idleFreq * 2); //Converts the frequency in Hz to the number of ticks (at 2uS) it takes to complete 1 cycle. Note that the frequency is divided by 2 coming from TS to allow for up to 5KHz - } - - //This must happen at the end of the idle init - Timer1.setMode(4, TIMER_OUTPUT_COMPARE); - Timer1.attachInterrupt(4, idleInterrupt); //on first flash the configPage4.iacAlgorithm is invalid - - - /* - *********************************************************************************************************** - * Timers - */ - #if defined(ARDUINO_BLUEPILL_F103C8) || defined(ARDUINO_BLUEPILL_F103CB) - Timer4.setPeriod(1000); // Set up period - Timer4.setMode(1, TIMER_OUTPUT_COMPARE); - Timer4.attachInterrupt(1, oneMSInterval); - Timer4.resume(); //Start Timer - #else - Timer11.setPeriod(1000); // Set up period - Timer11.setMode(1, TIMER_OUTPUT_COMPARE); - Timer11.attachInterrupt(1, oneMSInterval); - Timer11.resume(); //Start Timer - #endif - pinMode(LED_BUILTIN, OUTPUT); //Visual WDT - - /* - *********************************************************************************************************** - * Auxiliaries - */ - //2uS resolution Min 8Hz, Max 5KHz - boost_pwm_max_count = 1000000L / (TIMER_RESOLUTION * configPage6.boostFreq * 2); //Converts the frequency in Hz to the number of ticks (at 2uS) it takes to complete 1 cycle. The x2 is there because the frequency is stored at half value (in a byte) to allow frequencies up to 511Hz - vvt_pwm_max_count = 1000000L / (TIMER_RESOLUTION * configPage6.vvtFreq * 2); //Converts the frequency in Hz to the number of ticks (at 2uS) it takes to complete 1 cycle - fan_pwm_max_count = 1000000L / (TIMER_RESOLUTION * configPage6.fanFreq * 2); //Converts the frequency in Hz to the number of ticks (at 4uS) it takes to complete 1 cycle - - //Need to be initialised last due to instant interrupt - Timer1.setMode(1, TIMER_OUTPUT_COMPARE); - Timer1.setMode(2, TIMER_OUTPUT_COMPARE); - Timer1.setMode(3, TIMER_OUTPUT_COMPARE); - Timer1.attachInterrupt(1, fanInterrupt); - Timer1.attachInterrupt(2, boostInterrupt); - Timer1.attachInterrupt(3, vvtInterrupt); - - /* - *********************************************************************************************************** - * Schedules - */ - #if defined(ARDUINO_BLUEPILL_F103C8) || defined(ARDUINO_BLUEPILL_F103CB) - //(CYCLES_PER_MICROSECOND == 72, APB2 at 72MHz, APB1 at 36MHz). - //Timer2 to 4 is on APB1, Timer1 on APB2. www.st.com/resource/en/datasheet/stm32f103cb.pdf sheet 12 - Timer1.setPrescaleFactor(((Timer1.getBaseFrequency()/1000000) * TIMER_RESOLUTION)-1); //2us resolution - Timer2.setPrescaleFactor(((Timer2.getBaseFrequency()/1000000) * TIMER_RESOLUTION)-1); //2us resolution - Timer3.setPrescaleFactor(((Timer3.getBaseFrequency()/1000000) * TIMER_RESOLUTION)-1); //2us resolution - #else - //(CYCLES_PER_MICROSECOND == 168, APB2 at 84MHz, APB1 at 42MHz). - //Timer2 to 14 is on APB1, Timers 1, 8, 9 and 10 on APB2. www.st.com/resource/en/datasheet/stm32f407vg.pdf sheet 120 - Timer1.setPrescaleFactor(((Timer1.getBaseFrequency()/1000000) * TIMER_RESOLUTION)-1); //2us resolution - Timer2.setPrescaleFactor(((Timer2.getBaseFrequency()/1000000) * TIMER_RESOLUTION)-1); //2us resolution - Timer3.setPrescaleFactor(((Timer3.getBaseFrequency()/1000000) * TIMER_RESOLUTION)-1); //2us resolution - Timer4.setPrescaleFactor(((Timer4.getBaseFrequency()/1000000) * TIMER_RESOLUTION)-1); //2us resolution - Timer5.setPrescaleFactor(((Timer5.getBaseFrequency()/1000000) * TIMER_RESOLUTION)-1); //2us resolution - #endif - Timer2.setMode(1, TIMER_OUTPUT_COMPARE); - Timer2.setMode(2, TIMER_OUTPUT_COMPARE); - Timer2.setMode(3, TIMER_OUTPUT_COMPARE); - Timer2.setMode(4, TIMER_OUTPUT_COMPARE); - - Timer3.setMode(1, TIMER_OUTPUT_COMPARE); - Timer3.setMode(2, TIMER_OUTPUT_COMPARE); - Timer3.setMode(3, TIMER_OUTPUT_COMPARE); - Timer3.setMode(4, TIMER_OUTPUT_COMPARE); - - //Attach interrupt functions - //Injection - Timer2.attachInterrupt(1, fuelSchedule1Interrupt); - Timer2.attachInterrupt(2, fuelSchedule2Interrupt); - Timer2.attachInterrupt(3, fuelSchedule3Interrupt); - Timer2.attachInterrupt(4, fuelSchedule4Interrupt); - #if (INJ_CHANNELS >= 5) - Timer5.setMode(1, TIMER_OUTPUT_COMPARE); - Timer5.attachInterrupt(1, fuelSchedule5Interrupt); - #endif - #if (INJ_CHANNELS >= 6) - Timer5.setMode(2, TIMER_OUTPUT_COMPARE); - Timer5.attachInterrupt(2, fuelSchedule6Interrupt); - #endif - #if (INJ_CHANNELS >= 7) - Timer5.setMode(3, TIMER_OUTPUT_COMPARE); - Timer5.attachInterrupt(3, fuelSchedule7Interrupt); - #endif - #if (INJ_CHANNELS >= 8) - Timer5.setMode(4, TIMER_OUTPUT_COMPARE); - Timer5.attachInterrupt(4, fuelSchedule8Interrupt); - #endif - - //Ignition - Timer3.attachInterrupt(1, ignitionSchedule1Interrupt); - Timer3.attachInterrupt(2, ignitionSchedule2Interrupt); - Timer3.attachInterrupt(3, ignitionSchedule3Interrupt); - Timer3.attachInterrupt(4, ignitionSchedule4Interrupt); - #if (IGN_CHANNELS >= 5) - Timer4.setMode(1, TIMER_OUTPUT_COMPARE); - Timer4.attachInterrupt(1, ignitionSchedule5Interrupt); - #endif - #if (IGN_CHANNELS >= 6) - Timer4.setMode(2, TIMER_OUTPUT_COMPARE); - Timer4.attachInterrupt(2, ignitionSchedule6Interrupt); - #endif - #if (IGN_CHANNELS >= 7) - Timer4.setMode(3, TIMER_OUTPUT_COMPARE); - Timer4.attachInterrupt(3, ignitionSchedule7Interrupt); - #endif - #if (IGN_CHANNELS >= 8) - Timer4.setMode(4, TIMER_OUTPUT_COMPARE); - Timer4.attachInterrupt(4, ignitionSchedule8Interrupt); - #endif - - Timer1.setOverflow(0xFFFF); - Timer1.resume(); - Timer2.setOverflow(0xFFFF); - Timer2.resume(); - Timer3.setOverflow(0xFFFF); - Timer3.resume(); - #if (IGN_CHANNELS >= 5) - Timer4.setOverflow(0xFFFF); - Timer4.resume(); - #endif - #if (INJ_CHANNELS >= 5) - Timer5.setOverflow(0xFFFF); - Timer5.resume(); - #endif -} - -uint16_t freeRam() -{ - char top = 't'; - return &top - reinterpret_cast(sbrk(0)); -} - -void doSystemReset( void ) -{ - __disable_irq(); - NVIC_SystemReset(); -} - -void jumpToBootloader( void ) // https://github.com/3devo/Arduino_Core_STM32/blob/jumpSysBL/libraries/SrcWrapper/src/stm32/bootloader.c -{ // https://github.com/markusgritsch/SilF4ware/blob/master/SilF4ware/drv_reset.c - HAL_RCC_DeInit(); - HAL_DeInit(); - SysTick->VAL = SysTick->LOAD = SysTick->CTRL = 0; - SYSCFG->MEMRMP = 0x01; - - #if defined(STM32F7xx) || defined(STM32H7xx) - const uint32_t DFU_addr = 0x1FF00000; // From AN2606 - #else - const uint32_t DFU_addr = 0x1FFF0000; // Default for STM32F10xxx and STM32F40xxx/STM32F41xxx from AN2606 - #endif - // This is assembly to prevent modifying the stack pointer after - // loading it, and to ensure a jump (not call) to the bootloader. - // Not sure if the barriers are really needed, they were taken from - // https://github.com/GrumpyOldPizza/arduino-STM32L4/blob/ac659033eadd50cfe001ba1590a1362b2d87bb76/system/STM32L4xx/Source/boot_stm32l4xx.c#L159-L165 - asm volatile ( - "ldr r0, [%[DFU_addr], #0] \n\t" // get address of stack pointer - "msr msp, r0 \n\t" // set stack pointer - "ldr r0, [%[DFU_addr], #4] \n\t" // get address of reset handler - "dsb \n\t" // data sync barrier - "isb \n\t" // instruction sync barrier - "bx r0 \n\t" // branch to bootloader - : : [DFU_addr] "l" (DFU_addr) : "r0" - ); - __builtin_unreachable(); -} - -#endif diff --git a/speeduino/board_stm32_generic.h b/speeduino/board_stm32_generic.h deleted file mode 100644 index e1250c1d..00000000 --- a/speeduino/board_stm32_generic.h +++ /dev/null @@ -1,228 +0,0 @@ -#ifndef STM32_H -#define STM32_H -#if defined(CORE_STM32_GENERIC) - -/* -*********************************************************************************************************** -* General -*/ - #define PORT_TYPE uint32_t - #define PINMASK_TYPE uint32_t - #define COMPARE_TYPE uint16_t - #define COUNTER_TYPE uint16_t - #define SERIAL_BUFFER_SIZE 517 //Size of the serial buffer used by new comms protocol. For SD transfers this must be at least 512 + 1 (flag) + 4 (sector) - #define FPU_MAX_SIZE 32 //Size of the FPU buffer. 0 means no FPU. - #define TIMER_RESOLUTION 2 - #define micros_safe() micros() //timer5 method is not used on anything but AVR, the micros_safe() macro is simply an alias for the normal micros() - #if defined(SRAM_AS_EEPROM) - #define EEPROM_LIB_H "src/BackupSram/BackupSramAsEEPROM.h" - #elif defined(FRAM_AS_EEPROM) //https://github.com/VitorBoss/FRAM - #define EEPROM_LIB_H - typedef uint16_t eeprom_address_t; - #else - #define EEPROM_LIB_H "src/SPIAsEEPROM/SPIAsEEPROM.h" - typedef uint16_t eeprom_address_t; - #endif - - #ifndef USE_SERIAL3 - #define USE_SERIAL3 - #endif - void initBoard(); - uint16_t freeRam(); - void doSystemReset(); - void jumpToBootloader(); - - #define pinIsReserved(pin) ( ((pin) == PA11) || ((pin) == PA12) ) //Forbidden pins like USB - - #ifndef Serial - #define Serial Serial1 - #endif - - #if defined(FRAM_AS_EEPROM) - #include - #if defined(STM32F407xx) - extern FramClass EEPROM; /*(mosi, miso, sclk, ssel, clockspeed) 31/01/2020*/ - #else - extern FramClass EEPROM; //Blue/Black Pills - #endif - #endif - - #if !defined (A0) - #define A0 PA0 - #define A1 PA1 - #define A2 PA2 - #define A3 PA3 - #define A4 PA4 - #define A5 PA5 - #define A6 PA6 - #define A7 PA7 - #define A8 PB0 - #define A9 PB1 - #endif - //STM32F1 have only 10 12bit adc - #if !defined (A10) - #define A10 PA0 - #define A11 PA1 - #define A12 PA2 - #define A13 PA3 - #define A14 PA4 - #define A15 PA5 - #endif - - #ifndef PB11 //Hack for F4 BlackPills - #define PB11 PB10 - #endif -#define PWM_FAN_AVAILABLE - -/* -*********************************************************************************************************** -* Schedules -* Timers Table for STM32F1 -* TIMER1 TIMER2 TIMER3 TIMER4 -* 1 - FAN 1 - INJ1 1 - IGN1 1 - oneMSInterval -* 2 - BOOST 2 - INJ2 2 - IGN2 2 - -* 3 - VVT 3 - INJ3 3 - IGN3 3 - -* 4 - IDLE 4 - INJ4 4 - IGN4 4 - -* -* Timers Table for STM32F4 -* TIMER1 TIMER2 TIMER3 TIMER4 TIMER5 TIMER11 -* 1 - FAN 1 - INJ1 1 - IGN1 1 - IGN5 1 - INJ5 1 - oneMSInterval -* 2 - BOOST 2 - INJ2 2 - IGN2 2 - IGN6 2 - INJ6 2 - -* 3 - VVT 3 - INJ3 3 - IGN3 3 - IGN7 3 - INJ7 3 - -* 4 - IDLE 4 - INJ4 4 - IGN4 4 - IGN8 4 - INJ8 4 - -* -*/ - #define MAX_TIMER_PERIOD 65535*2 //The longest period of time (in uS) that the timer can permit (IN this case it is 65535 * 2, as each timer tick is 2uS) - #define uS_TO_TIMER_COMPARE(uS) (uS >> 1) //Converts a given number of uS into the required number of timer ticks until that time has passed. - - #define FUEL1_COUNTER (TIM2)->CNT - #define FUEL2_COUNTER (TIM2)->CNT - #define FUEL3_COUNTER (TIM2)->CNT - #define FUEL4_COUNTER (TIM2)->CNT - - #define FUEL1_COMPARE (TIM2)->CCR1 - #define FUEL2_COMPARE (TIM2)->CCR2 - #define FUEL3_COMPARE (TIM2)->CCR3 - #define FUEL4_COMPARE (TIM2)->CCR4 - - #define IGN1_COUNTER (TIM3)->CNT - #define IGN2_COUNTER (TIM3)->CNT - #define IGN3_COUNTER (TIM3)->CNT - #define IGN4_COUNTER (TIM3)->CNT - - #define IGN1_COMPARE (TIM3)->CCR1 - #define IGN2_COMPARE (TIM3)->CCR2 - #define IGN3_COMPARE (TIM3)->CCR3 - #define IGN4_COMPARE (TIM3)->CCR4 - - #ifndef SMALL_FLASH_MODE - #define FUEL5_COUNTER (TIM5)->CNT - #define FUEL6_COUNTER (TIM5)->CNT - #define FUEL7_COUNTER (TIM5)->CNT - #define FUEL8_COUNTER (TIM5)->CNT - - #define FUEL5_COMPARE (TIM5)->CCR1 - #define FUEL6_COMPARE (TIM5)->CCR2 - #define FUEL7_COMPARE (TIM5)->CCR3 - #define FUEL8_COMPARE (TIM5)->CCR4 - - #define IGN5_COUNTER (TIM4)->CNT - #define IGN6_COUNTER (TIM4)->CNT - #define IGN7_COUNTER (TIM4)->CNT - #define IGN8_COUNTER (TIM4)->CNT - - #define IGN5_COMPARE (TIM4)->CCR1 - #define IGN6_COMPARE (TIM4)->CCR2 - #define IGN7_COMPARE (TIM4)->CCR3 - #define IGN8_COMPARE (TIM4)->CCR4 - #endif - //github.com/rogerclarkmelbourne/Arduino_STM32/blob/754bc2969921f1ef262bd69e7faca80b19db7524/STM32F1/system/libmaple/include/libmaple/timer.h#L444 - static inline void FUEL1_TIMER_ENABLE(void) {(TIM3)->SR = ~TIM_FLAG_CC1; (TIM3)->DIER |= TIM_DIER_CC1IE;} - static inline void FUEL2_TIMER_ENABLE(void) {(TIM3)->SR = ~TIM_FLAG_CC2; (TIM3)->DIER |= TIM_DIER_CC2IE;} - static inline void FUEL3_TIMER_ENABLE(void) {(TIM3)->SR = ~TIM_FLAG_CC3; (TIM3)->DIER |= TIM_DIER_CC3IE;} - static inline void FUEL4_TIMER_ENABLE(void) {(TIM3)->SR = ~TIM_FLAG_CC4; (TIM3)->DIER |= TIM_DIER_CC4IE;} - - static inline void FUEL1_TIMER_DISABLE(void) {(TIM3)->DIER &= ~TIM_DIER_CC1IE;} - static inline void FUEL2_TIMER_DISABLE(void) {(TIM3)->DIER &= ~TIM_DIER_CC2IE;} - static inline void FUEL3_TIMER_DISABLE(void) {(TIM3)->DIER &= ~TIM_DIER_CC3IE;} - static inline void FUEL4_TIMER_DISABLE(void) {(TIM3)->DIER &= ~TIM_DIER_CC4IE;} - - static inline void IGN1_TIMER_ENABLE(void) {(TIM2)->SR = ~TIM_FLAG_CC1; (TIM2)->DIER |= TIM_DIER_CC1IE;} - static inline void IGN2_TIMER_ENABLE(void) {(TIM2)->SR = ~TIM_FLAG_CC2; (TIM2)->DIER |= TIM_DIER_CC2IE;} - static inline void IGN3_TIMER_ENABLE(void) {(TIM2)->SR = ~TIM_FLAG_CC3; (TIM2)->DIER |= TIM_DIER_CC3IE;} - static inline void IGN4_TIMER_ENABLE(void) {(TIM2)->SR = ~TIM_FLAG_CC4; (TIM2)->DIER |= TIM_DIER_CC4IE;} - - static inline void IGN1_TIMER_DISABLE(void) {(TIM2)->DIER &= ~TIM_DIER_CC1IE;} - static inline void IGN2_TIMER_DISABLE(void) {(TIM2)->DIER &= ~TIM_DIER_CC2IE;} - static inline void IGN3_TIMER_DISABLE(void) {(TIM2)->DIER &= ~TIM_DIER_CC3IE;} - static inline void IGN4_TIMER_DISABLE(void) {(TIM2)->DIER &= ~TIM_DIER_CC4IE;} - - #ifndef SMALL_FLASH_MODE - static inline void FUEL5_TIMER_ENABLE(void) {(TIM5)->SR = ~TIM_FLAG_CC1; (TIM5)->DIER |= TIM_DIER_CC1IE;} - static inline void FUEL6_TIMER_ENABLE(void) {(TIM5)->SR = ~TIM_FLAG_CC2; (TIM5)->DIER |= TIM_DIER_CC2IE;} - static inline void FUEL7_TIMER_ENABLE(void) {(TIM5)->SR = ~TIM_FLAG_CC3; (TIM5)->DIER |= TIM_DIER_CC3IE;} - static inline void FUEL8_TIMER_ENABLE(void) {(TIM5)->SR = ~TIM_FLAG_CC4; (TIM5)->DIER |= TIM_DIER_CC4IE;} - - static inline void FUEL5_TIMER_DISABLE(void) {(TIM5)->DIER &= ~TIM_DIER_CC1IE;} - static inline void FUEL6_TIMER_DISABLE(void) {(TIM5)->DIER &= ~TIM_DIER_CC2IE;} - static inline void FUEL7_TIMER_DISABLE(void) {(TIM5)->DIER &= ~TIM_DIER_CC3IE;} - static inline void FUEL8_TIMER_DISABLE(void) {(TIM5)->DIER &= ~TIM_DIER_CC4IE;} - - static inline void IGN5_TIMER_ENABLE(void) {(TIM4)->SR = ~TIM_FLAG_CC1; (TIM4)->DIER |= TIM_DIER_CC1IE;} - static inline void IGN6_TIMER_ENABLE(void) {(TIM4)->SR = ~TIM_FLAG_CC2; (TIM4)->DIER |= TIM_DIER_CC2IE;} - static inline void IGN7_TIMER_ENABLE(void) {(TIM4)->SR = ~TIM_FLAG_CC3; (TIM4)->DIER |= TIM_DIER_CC3IE;} - static inline void IGN8_TIMER_ENABLE(void) {(TIM4)->SR = ~TIM_FLAG_CC4; (TIM4)->DIER |= TIM_DIER_CC4IE;} - - static inline void IGN5_TIMER_DISABLE(void) {(TIM4)->DIER &= ~TIM_DIER_CC1IE;} - static inline void IGN6_TIMER_DISABLE(void) {(TIM4)->DIER &= ~TIM_DIER_CC2IE;} - static inline void IGN7_TIMER_DISABLE(void) {(TIM4)->DIER &= ~TIM_DIER_CC3IE;} - static inline void IGN8_TIMER_DISABLE(void) {(TIM4)->DIER &= ~TIM_DIER_CC4IE;} - #endif - -/* -*********************************************************************************************************** -* Auxiliaries -*/ - #define ENABLE_BOOST_TIMER() (TIM1)->SR = ~TIM_FLAG_CC2; (TIM1)->DIER |= TIM_DIER_CC2IE - #define DISABLE_BOOST_TIMER() (TIM1)->DIER &= ~TIM_DIER_CC2IE - - #define ENABLE_VVT_TIMER() (TIM1)->SR = ~TIM_FLAG_CC3; (TIM1)->DIER |= TIM_DIER_CC3IE - #define DISABLE_VVT_TIMER() (TIM1)->DIER &= ~TIM_DIER_CC3IE - - #define ENABLE_FAN_TIMER() (TIM1)->SR = ~TIM_FLAG_CC1; (TIM1)->DIER |= TIM_DIER_CC1IE - #define DISABLE_FAN_TIMER() (TIM1)->DIER &= ~TIM_DIER_CC1IE - - #define BOOST_TIMER_COMPARE (TIM1)->CCR2 - #define BOOST_TIMER_COUNTER (TIM1)->CNT - #define VVT_TIMER_COMPARE (TIM1)->CCR3 - #define VVT_TIMER_COUNTER (TIM1)->CNT - #define FAN_TIMER_COMPARE (TIM1)->CCR1 - #define FAN_TIMER_COUNTER (TIM1)->CNT - -/* -*********************************************************************************************************** -* Idle -*/ - #define IDLE_COUNTER (TIM1)->CNT - #define IDLE_COMPARE (TIM1)->CCR4 - - #define IDLE_TIMER_ENABLE() (TIM1)->SR = ~TIM_FLAG_CC4; (TIM1)->DIER |= TIM_DIER_CC4IE - #define IDLE_TIMER_DISABLE() (TIM1)->DIER &= ~TIM_DIER_CC4IE -/* -*********************************************************************************************************** -* Timers -*/ - - -/* -*********************************************************************************************************** -* CAN / Second serial -*/ -#if defined(STM32GENERIC) // STM32GENERIC core - SerialUART &secondarySerial = Serial2; -#else //libmaple core aka STM32DUINO - HardwareSerial &secondarySerial = Serial2; -#endif - -#endif //CORE_STM32 -#endif //STM32_H diff --git a/speeduino/board_stm32_official.h b/speeduino/board_stm32_official.h index a4c1bed9..b4ed4de6 100644 --- a/speeduino/board_stm32_official.h +++ b/speeduino/board_stm32_official.h @@ -29,6 +29,44 @@ #define micros_safe() micros() //timer5 method is not used on anything but AVR, the micros_safe() macro is simply an alias for the normal micros() #define TIMER_RESOLUTION 4 +//Select one for EEPROM,the default is EEPROM emulation on internal flash. +//#define SRAM_AS_EEPROM /*Use 4K battery backed SRAM, requires a 3V continuous source (like battery) connected to Vbat pin */ +//#define USE_SPI_EEPROM PB0 /*Use M25Qxx SPI flash on BlackF407VE*/ +//#define FRAM_AS_EEPROM /*Use FRAM like FM25xxx, MB85RSxxx or any SPI compatible */ + +#ifndef word + #define word(h, l) ((h << 8) | l) //word() function not defined for this platform in the main library +#endif + +#if defined(ARDUINO_BLUEPILL_F103C8) || defined(ARDUINO_BLUEPILL_F103CB) \ + || defined(ARDUINO_BLACKPILL_F401CC) || defined(ARDUINO_BLACKPILL_F411CE) + //STM32 Pill boards + #ifndef NUM_DIGITAL_PINS + #define NUM_DIGITAL_PINS 35 + #endif + #ifndef LED_BUILTIN + #define LED_BUILTIN PB1 //Maple Mini + #endif +#elif defined(STM32F407xx) + #ifndef NUM_DIGITAL_PINS + #define NUM_DIGITAL_PINS 75 + #endif +#endif + +//Specific mode for Bluepill due to its small flash size. This disables a number of strings from being compiled into the flash +#if defined(MCU_STM32F103C8) || defined(MCU_STM32F103CB) + #define SMALL_FLASH_MODE +#endif + +#define BOARD_MAX_DIGITAL_PINS NUM_DIGITAL_PINS +#define BOARD_MAX_IO_PINS NUM_DIGITAL_PINS +#if __GNUC__ < 7 //Already included on GCC 7 +extern "C" char* sbrk(int incr); //Used to freeRam +#endif +#ifndef digitalPinToInterrupt +inline uint32_t digitalPinToInterrupt(uint32_t Interrupt_pin) { return Interrupt_pin; } //This isn't included in the stm32duino libs (yet) +#endif + #if defined(USER_BTN) #define EEPROM_RESET_PIN USER_BTN //onboard key0 for black STM32F407 boards and blackpills, keep pressed during boot to reset eeprom #endif @@ -59,7 +97,6 @@ void initBoard(); uint16_t freeRam(); void doSystemReset(); void jumpToBootloader(); -extern "C" char* sbrk(int incr); #if defined(ARDUINO_BLUEPILL_F103C8) || defined(ARDUINO_BLUEPILL_F103CB) \ || defined(ARDUINO_BLACKPILL_F401CC) || defined(ARDUINO_BLACKPILL_F411CE) diff --git a/speeduino/globals.h b/speeduino/globals.h index a60515e1..823de024 100644 --- a/speeduino/globals.h +++ b/speeduino/globals.h @@ -75,61 +75,17 @@ #define IGN_CHANNELS 8 #elif defined(STM32_MCU_SERIES) || defined(ARDUINO_ARCH_STM32) || defined(STM32) + #define BOARD_H "board_stm32_official.h" #define CORE_STM32 + #define BOARD_MAX_ADC_PINS NUM_ANALOG_INPUTS-1 //Number of analog pins from core. - #if defined(STM32F407xx) //F407 can do 8x8 STM32F401/STM32F411 not + #if defined(STM32F407xx) //F407 can do 8x8 STM32F401/STM32F411 don't #define INJ_CHANNELS 8 #define IGN_CHANNELS 8 #else #define INJ_CHANNELS 4 #define IGN_CHANNELS 5 #endif - -//Select one for EEPROM,the default is EEPROM emulation on internal flash. -//#define SRAM_AS_EEPROM /*Use 4K battery backed SRAM, requires a 3V continuous source (like battery) connected to Vbat pin */ -//#define USE_SPI_EEPROM PB0 /*Use M25Qxx SPI flash */ -//#define FRAM_AS_EEPROM /*Use FRAM like FM25xxx, MB85RSxxx or any SPI compatible */ - - #ifndef word - #define word(h, l) ((h << 8) | l) //word() function not defined for this platform in the main library - #endif - - - #if defined(ARDUINO_BLUEPILL_F103C8) || defined(ARDUINO_BLUEPILL_F103CB) \ - || defined(ARDUINO_BLACKPILL_F401CC) || defined(ARDUINO_BLACKPILL_F411CE) - //STM32 Pill boards - #ifndef NUM_DIGITAL_PINS - #define NUM_DIGITAL_PINS 35 - #endif - #ifndef LED_BUILTIN - #define LED_BUILTIN PB1 //Maple Mini - #endif - #elif defined(STM32F407xx) - #ifndef NUM_DIGITAL_PINS - #define NUM_DIGITAL_PINS 75 - #endif - #endif - - #if defined(STM32_CORE_VERSION) - #define BOARD_H "board_stm32_official.h" - #else - #define CORE_STM32_GENERIC - #define BOARD_H "board_stm32_generic.h" - #endif - - //Specific mode for Bluepill due to its small flash size. This disables a number of strings from being compiled into the flash - #if defined(MCU_STM32F103C8) || defined(MCU_STM32F103CB) - #define SMALL_FLASH_MODE - #endif - - #define BOARD_MAX_DIGITAL_PINS NUM_DIGITAL_PINS - #define BOARD_MAX_IO_PINS NUM_DIGITAL_PINS - #if __GNUC__ < 7 //Already included on GCC 7 - extern "C" char* sbrk(int incr); //Used to freeRam - #endif - #ifndef digitalPinToInterrupt - inline uint32_t digitalPinToInterrupt(uint32_t Interrupt_pin) { return Interrupt_pin; } //This isn't included in the stm32duino libs (yet) - #endif #elif defined(__SAMD21G18A__) #define BOARD_H "board_samd21.h" #define CORE_SAMD21