From 6fc223d80b2c5183a68d2863073cfddb15b7f893 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Tue, 1 Mar 2022 12:52:25 +0000 Subject: [PATCH] Timer stuff with incomplete teensy --- CommandStation-EX.ino | 2 +- DCCEX.h | 4 +- DCCEXParser.cpp | 4 +- DCCTimer.h | 57 ++++++++++-- DCCTimerAVR.cpp | 113 +++++++++++++++++++++++ DCCTimer.cpp => DCCTimerMEGAAVR.cpp | 134 +++------------------------- DCCTimerTEENSY.cpp | 122 +++++++++++++++++++++++++ DCCWaveform.cpp | 4 +- MotorDriver.cpp | 3 - TrackManager.cpp | 3 +- freeMemory.cpp | 112 ----------------------- freeMemory.h | 25 ------ 12 files changed, 305 insertions(+), 278 deletions(-) create mode 100644 DCCTimerAVR.cpp rename DCCTimer.cpp => DCCTimerMEGAAVR.cpp (50%) create mode 100644 DCCTimerTEENSY.cpp delete mode 100644 freeMemory.cpp delete mode 100644 freeMemory.h diff --git a/CommandStation-EX.ino b/CommandStation-EX.ino index 52cf822..8d650f9 100644 --- a/CommandStation-EX.ino +++ b/CommandStation-EX.ino @@ -147,7 +147,7 @@ void loop() // Report any decrease in memory (will automatically trigger on first call) static int ramLowWatermark = __INT_MAX__; // replaced on first loop - int freeNow = minimumFreeMemory(); + int freeNow = DCCTimer::getMinimumFreeMemory(); if (freeNow < ramLowWatermark) { ramLowWatermark = freeNow; LCD(3,F("Free RAM=%5db"), ramLowWatermark); diff --git a/DCCEX.h b/DCCEX.h index a78c6c1..9c0b130 100644 --- a/DCCEX.h +++ b/DCCEX.h @@ -38,12 +38,12 @@ #endif #include "LCD_Implementation.h" #include "LCN.h" -#include "freeMemory.h" #include "IODevice.h" #include "Turnouts.h" #include "Sensors.h" #include "Outputs.h" #include "EXRAIL.h" #include "CommandDistributor.h" -#include "TrackManager.h" +#include "TrackManager.h" +#include "DCCTimer.h" #endif diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 7c32c13..ae2a109 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -30,7 +30,6 @@ #include "Turnouts.h" #include "Outputs.h" #include "Sensors.h" -#include "freeMemory.h" #include "GITHUB_SHA.h" #include "version.h" #include "defines.h" @@ -38,6 +37,7 @@ #include "EEStore.h" #include "DIAG.h" #include "TrackManager.h" +#include "DCCTimer.h" #include //////////////////////////////////////////////////////////////////////////////// @@ -732,7 +732,7 @@ bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[]) return true; case HASH_KEYWORD_RAM: // - StringFormatter::send(stream, F("Free memory=%d\n"), minimumFreeMemory()); + StringFormatter::send(stream, F("Free memory=%d\n"), DCCTimer::getMinimumFreeMemory()); break; case HASH_KEYWORD_ACK: // diff --git a/DCCTimer.h b/DCCTimer.h index 8f8f5bc..e4ebf5e 100644 --- a/DCCTimer.h +++ b/DCCTimer.h @@ -20,6 +20,34 @@ * along with CommandStation. If not, see . */ +/* There are several different implementations of this class which the compiler will select + according to the hardware. + */ + +/* This timer class is used to manage the single timer required to handle the DCC waveform. + * All timer access comes through this class so that it can be compiled for + * various hardware CPU types. + * + * DCCEX works on a single timer interrupt at a regular 58uS interval. + * The DCCWaveform class generates the signals to the motor shield + * based on this timer. + * + * If the motor drivers are BOTH configured to use the correct 2 pins for the architecture, + * (see isPWMPin() function. ) + * then this allows us to use a hardware driven pin switching arrangement which is + * achieved by setting the duty cycle of the NEXT clock interrupt to 0% or 100% depending on + * the required pin state. (see setPWM()) + * This is more accurate than the software interrupt but at the expense of + * limiting the choice of available pins. + * Fortunately, a standard motor shield on a Mega uses pins that qualify for PWM... + * Other shields may be jumpered to PWM pins or run directly using the software interrupt. + * + * Because the PWM-based waveform is effectively set half a cycle after the software version, + * it is not acceptable to drive the two tracks on different methiods or it would cause + * problems for <1 JOIN> etc. + * + */ + #ifndef DCCTimer_h #define DCCTimer_h #include "Arduino.h" @@ -32,11 +60,30 @@ class DCCTimer { static void getSimulatedMacAddress(byte mac[6]); static bool isPWMPin(byte pin); static void setPWM(byte pin, bool high); -#if (defined(TEENSYDUINO) && !defined(__IMXRT1062__)) - static void read_mac(byte mac[6]); - static void read(uint8_t word, uint8_t *mac, uint8_t offset); -#endif - private: + +// Update low ram level. Allow for extra bytes to be specified +// by estimation or inspection, that may be used by other +// called subroutines. Must be called with interrupts disabled. +// +// Although __brkval may go up and down as heap memory is allocated +// and freed, this function records only the worst case encountered. +// So even if all of the heap is freed, the reported minimum free +// memory will not increase. +// +static void inline updateMinimumFreeMemoryISR(unsigned char extraBytes=0) { + int spare = freeMemory()-extraBytes; + if (spare < 0) spare = 0; + if (spare < minimum_free_memory) minimum_free_memory = spare; +} + + static int getMinimumFreeMemory(); + +private: + static int freeMemory(); + static volatile int minimum_free_memory; + static const int DCC_SIGNAL_TIME=58; // this is the 58uS DCC 1-bit waveform half-cycle + static const long CLOCK_CYCLES=(F_CPU / 1000000 * DCC_SIGNAL_TIME) >>1; + }; #endif diff --git a/DCCTimerAVR.cpp b/DCCTimerAVR.cpp new file mode 100644 index 0000000..ff0143b --- /dev/null +++ b/DCCTimerAVR.cpp @@ -0,0 +1,113 @@ +/* + * © 2021 Mike S + * © 2021 Harald Barth + * © 2021 Fred Decker + * © 2021 Chris Harlow + * © 2021 David Cutting + * All rights reserved. + * + * This file is part of Asbelos DCC API + * + * This 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. + * + * It 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 CommandStation. If not, see . + */ + +// ATTENTION: this file only compiles on a UNO or MEGA +// Please refer to DCCTimer.h for general comments about how this class works +// This is to avoid repetition and duplication. +#ifdef ARDUINO_ARCH_AVR + +#include +#include "DCCTimer.h" +INTERRUPT_CALLBACK interruptHandler=0; + + // Arduino nano, uno, mega etc +#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) + #define TIMER1_A_PIN 11 + #define TIMER1_B_PIN 12 + #define TIMER1_C_PIN 13 +#else + #define TIMER1_A_PIN 9 + #define TIMER1_B_PIN 10 +#endif + +void DCCTimer::begin(INTERRUPT_CALLBACK callback) { + interruptHandler=callback; + noInterrupts(); + ADCSRA = (ADCSRA & 0b11111000) | 0b00000100; // speed up analogRead sample time + TCCR1A = 0; + ICR1 = CLOCK_CYCLES; + TCNT1 = 0; + TCCR1B = _BV(WGM13) | _BV(CS10); // Mode 8, clock select 1 + TIMSK1 = _BV(TOIE1); // Enable Software interrupt + interrupts(); + } + +// ISR called by timer interrupt every 58uS + ISR(TIMER1_OVF_vect){ interruptHandler(); } + +// Alternative pin manipulation via PWM control. + bool DCCTimer::isPWMPin(byte pin) { + return pin==TIMER1_A_PIN + || pin==TIMER1_B_PIN + #ifdef TIMER1_C_PIN + || pin==TIMER1_C_PIN + #endif + ; + } + + void DCCTimer::setPWM(byte pin, bool high) { + if (pin==TIMER1_A_PIN) { + TCCR1A |= _BV(COM1A1); + OCR1A= high?1024:0; + } + else if (pin==TIMER1_B_PIN) { + TCCR1A |= _BV(COM1B1); + OCR1B= high?1024:0; + } + #ifdef TIMER1_C_PIN + else if (pin==TIMER1_C_PIN) { + TCCR1A |= _BV(COM1C1); + OCR1C= high?1024:0; + } + #endif + } + + void DCCTimer::getSimulatedMacAddress(byte mac[6]) { + for (byte i=0; i<6; i++) { + mac[i]=boot_signature_byte_get(0x0E + i); + } + mac[0] &= 0xFE; + mac[0] |= 0x02; + } + + +volatile int DCCTimer::minimum_free_memory=__INT_MAX__; + +// Return low memory value... +int DCCTimer::getMinimumFreeMemory() { + noInterrupts(); // Disable interrupts to get volatile value + int retval = minimum_free_memory; + interrupts(); + return retval; +} + +extern char *__brkval; +extern char *__malloc_heap_start; + +int DCCTimer::freeMemory() { + char top; + return __brkval ? &top - __brkval : &top - __malloc_heap_start; +} + +#endif diff --git a/DCCTimer.cpp b/DCCTimerMEGAAVR.cpp similarity index 50% rename from DCCTimer.cpp rename to DCCTimerMEGAAVR.cpp index cd35293..624008a 100644 --- a/DCCTimer.cpp +++ b/DCCTimerMEGAAVR.cpp @@ -47,14 +47,17 @@ * */ +// ATTENTION: this file only compiles on a UnoWifiRev3 or NanoEvery +// Please refer to DCCTimer.h for general comments about how this class works +// This is to avoid repetition and duplication. +#ifdef ARDUINO_ARCH_MEGAAVR + #include "DCCTimer.h" -const int DCC_SIGNAL_TIME=58; // this is the 58uS DCC 1-bit waveform half-cycle -const long CLOCK_CYCLES=(F_CPU / 1000000 * DCC_SIGNAL_TIME) >>1; INTERRUPT_CALLBACK interruptHandler=0; +extern char *__brkval; +extern char *__malloc_heap_start; -#ifdef ARDUINO_ARCH_MEGAAVR - // Arduino unoWifi Rev2 and nanoEvery architectire void DCCTimer::begin(INTERRUPT_CALLBACK callback) { interruptHandler=callback; @@ -93,126 +96,9 @@ INTERRUPT_CALLBACK interruptHandler=0; mac[0] |= 0x02; } -#elif defined(TEENSYDUINO) - IntervalTimer myDCCTimer; - - void DCCTimer::begin(INTERRUPT_CALLBACK callback) { - interruptHandler=callback; - - myDCCTimer.begin(interruptHandler, DCC_SIGNAL_TIME); - - } - - bool DCCTimer::isPWMPin(byte pin) { - //Teensy: digitalPinHasPWM, todo - (void) pin; - return false; // TODO what are the relevant pins? - } - - void DCCTimer::setPWM(byte pin, bool high) { - // TODO what are the relevant pins? - (void) pin; - (void) high; +int DCCTimer::freeMemory() { + char top; + return __brkval ? &top - __brkval : &top - __malloc_heap_start; } - void DCCTimer::getSimulatedMacAddress(byte mac[6]) { -#if defined(__IMXRT1062__) //Teensy 4.0 and Teensy 4.1 - uint32_t m1 = HW_OCOTP_MAC1; - uint32_t m2 = HW_OCOTP_MAC0; - mac[0] = m1 >> 8; - mac[1] = m1 >> 0; - mac[2] = m2 >> 24; - mac[3] = m2 >> 16; - mac[4] = m2 >> 8; - mac[5] = m2 >> 0; -#else - read_mac(mac); -#endif - } - -#if !defined(__IMXRT1062__) - void DCCTimer::read_mac(byte mac[6]) { - read(0xe,mac,0); - read(0xf,mac,3); - } - -// http://forum.pjrc.com/threads/91-teensy-3-MAC-address -void DCCTimer::read(uint8_t word, uint8_t *mac, uint8_t offset) { - FTFL_FCCOB0 = 0x41; // Selects the READONCE command - FTFL_FCCOB1 = word; // read the given word of read once area - - // launch command and wait until complete - FTFL_FSTAT = FTFL_FSTAT_CCIF; - while(!(FTFL_FSTAT & FTFL_FSTAT_CCIF)); - - *(mac+offset) = FTFL_FCCOB5; // collect only the top three bytes, - *(mac+offset+1) = FTFL_FCCOB6; // in the right orientation (big endian). - *(mac+offset+2) = FTFL_FCCOB7; // Skip FTFL_FCCOB4 as it's always 0. -} -#endif - -#else - // Arduino nano, uno, mega etc -#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) - #define TIMER1_A_PIN 11 - #define TIMER1_B_PIN 12 - #define TIMER1_C_PIN 13 -#else - #define TIMER1_A_PIN 9 - #define TIMER1_B_PIN 10 -#endif - - void DCCTimer::begin(INTERRUPT_CALLBACK callback) { - interruptHandler=callback; - noInterrupts(); - ADCSRA = (ADCSRA & 0b11111000) | 0b00000100; // speed up analogRead sample time - TCCR1A = 0; - ICR1 = CLOCK_CYCLES; - TCNT1 = 0; - TCCR1B = _BV(WGM13) | _BV(CS10); // Mode 8, clock select 1 - TIMSK1 = _BV(TOIE1); // Enable Software interrupt - interrupts(); - } - -// ISR called by timer interrupt every 58uS - ISR(TIMER1_OVF_vect){ interruptHandler(); } - -// Alternative pin manipulation via PWM control. - bool DCCTimer::isPWMPin(byte pin) { - return pin==TIMER1_A_PIN - || pin==TIMER1_B_PIN - #ifdef TIMER1_C_PIN - || pin==TIMER1_C_PIN - #endif - ; - } - - void DCCTimer::setPWM(byte pin, bool high) { - if (pin==TIMER1_A_PIN) { - TCCR1A |= _BV(COM1A1); - OCR1A= high?1024:0; - } - else if (pin==TIMER1_B_PIN) { - TCCR1A |= _BV(COM1B1); - OCR1B= high?1024:0; - } - #ifdef TIMER1_C_PIN - else if (pin==TIMER1_C_PIN) { - TCCR1A |= _BV(COM1C1); - OCR1C= high?1024:0; - } - #endif - } - - - #include - void DCCTimer::getSimulatedMacAddress(byte mac[6]) { - for (byte i=0; i<6; i++) { - mac[i]=boot_signature_byte_get(0x0E + i); - } - mac[0] &= 0xFE; - mac[0] |= 0x02; - - } - #endif diff --git a/DCCTimerTEENSY.cpp b/DCCTimerTEENSY.cpp new file mode 100644 index 0000000..99b147a --- /dev/null +++ b/DCCTimerTEENSY.cpp @@ -0,0 +1,122 @@ +/* + * © 2021 Mike S + * © 2021 Harald Barth + * © 2021 Fred Decker + * © 2021 Chris Harlow + * © 2021 David Cutting + * All rights reserved. + * + * This file is part of Asbelos DCC API + * + * This 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. + * + * It 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 CommandStation. If not, see . + */ + +// ATTENTION: this file only compiles on a TEENSY +// Please refer to DCCTimer.h for general comments about how this class works +// This is to avoid repetition and duplication. +#ifdef TEENSYDUINO + +#include "DCCTimer.h" + +INTERRUPT_CALLBACK interruptHandler=0; + +IntervalTimer myDCCTimer; + +void DCCTimer::begin(INTERRUPT_CALLBACK callback) { + interruptHandler=callback; + myDCCTimer.begin(interruptHandler, DCC_SIGNAL_TIME); + } + +bool DCCTimer::isPWMPin(byte pin) { + //Teensy: digitalPinHasPWM, todo + (void) pin; + return false; // TODO what are the relevant pins? + } + +void DCCTimer::setPWM(byte pin, bool high) { + // TODO what are the relevant pins? + (void) pin; + (void) high; +} + +#if defined(__IMXRT1062__) //Teensy 4.0 and Teensy 4.1 +void DCCTimer::getSimulatedMacAddress(byte mac[6]) { + uint32_t m1 = HW_OCOTP_MAC1; + uint32_t m2 = HW_OCOTP_MAC0; + mac[0] = m1 >> 8; + mac[1] = m1 >> 0; + mac[2] = m2 >> 24; + mac[3] = m2 >> 16; + mac[4] = m2 >> 8; + mac[5] = m2 >> 0; + } + +#else + +// http://forum.pjrc.com/threads/91-teensy-3-MAC-address +void teensyRead(uint8_t word, uint8_t *mac, uint8_t offset) { + FTFL_FCCOB0 = 0x41; // Selects the READONCE command + FTFL_FCCOB1 = word; // read the given word of read once area + + // launch command and wait until complete + FTFL_FSTAT = FTFL_FSTAT_CCIF; + while(!(FTFL_FSTAT & FTFL_FSTAT_CCIF)); + + *(mac+offset) = FTFL_FCCOB5; // collect only the top three bytes, + *(mac+offset+1) = FTFL_FCCOB6; // in the right orientation (big endian). + *(mac+offset+2) = FTFL_FCCOB7; // Skip FTFL_FCCOB4 as it's always 0. +} + +void DCCTimer::getSimulatedMacAddress(byte mac[6]) { + teensyRead(0xe,mac,0); + teensyRead(0xf,mac,3); + } +#endif + +#if !defined(__IMXRT1062__) +static inline int freeMemory() { + char top; + return &top - reinterpret_cast(sbrk(0)); +} + +#else +#if defined(ARDUINO_TEENSY40) + static const unsigned DTCM_START = 0x20000000UL; + static const unsigned OCRAM_START = 0x20200000UL; + static const unsigned OCRAM_SIZE = 512; + static const unsigned FLASH_SIZE = 1984; +#elif defined(ARDUINO_TEENSY41) + static const unsigned DTCM_START = 0x20000000UL; + static const unsigned OCRAM_START = 0x20200000UL; + static const unsigned OCRAM_SIZE = 512; + static const unsigned FLASH_SIZE = 7936; +#if TEENSYDUINO>151 + extern "C" uint8_t external_psram_size; +#endif +#endif + +static inline int freeMemory() { + extern unsigned long _ebss; + extern unsigned long _sdata; + extern unsigned long _estack; + const unsigned DTCM_START = 0x20000000UL; + unsigned dtcm = (unsigned)&_estack - DTCM_START; + unsigned stackinuse = (unsigned) &_estack - (unsigned) __builtin_frame_address(0); + unsigned varsinuse = (unsigned)&_ebss - (unsigned)&_sdata; + unsigned freemem = dtcm - (stackinuse + varsinuse); + return freemem; +} + +#endif +#endif \ No newline at end of file diff --git a/DCCWaveform.cpp b/DCCWaveform.cpp index 79c8c97..c51a18e 100644 --- a/DCCWaveform.cpp +++ b/DCCWaveform.cpp @@ -29,7 +29,7 @@ #include "DCCTimer.h" #include "DCCACK.h" #include "DIAG.h" -#include "freeMemory.h" + DCCWaveform DCCWaveform::mainTrack(PREAMBLE_BITS_MAIN, true); DCCWaveform DCCWaveform::progTrack(PREAMBLE_BITS_PROG, false); @@ -140,7 +140,7 @@ void DCCWaveform::interrupt2() { remainingPreambles--; // Update free memory diagnostic as we don't have anything else to do this time. // Allow for checkAck and its called functions using 22 bytes more. - updateMinimumFreeMemory(22); + DCCTimer::updateMinimumFreeMemoryISR(22); return; } diff --git a/MotorDriver.cpp b/MotorDriver.cpp index 7f2d3e1..a20bf0d 100644 --- a/MotorDriver.cpp +++ b/MotorDriver.cpp @@ -138,9 +138,6 @@ void MotorDriver::setSignal( bool high) { } } -#if defined(ARDUINO_TEENSY32) || defined(ARDUINO_TEENSY35)|| defined(ARDUINO_TEENSY36) -volatile unsigned int overflow_count=0; -#endif bool MotorDriver::canMeasureCurrent() { return currentPin!=UNUSED_PIN; diff --git a/TrackManager.cpp b/TrackManager.cpp index bfb6199..69fcf78 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -46,8 +46,7 @@ byte TrackManager::lastTrack=0; void TrackManager::Setup(const FSH * shieldname, MotorDriver * track0, MotorDriver * track1, MotorDriver * track2, MotorDriver * track3, MotorDriver * track4, MotorDriver * track5, - MotorDriver * track6, MotorDriver * track7 ) { - (void) shieldname; // TODO + MotorDriver * track6, MotorDriver * track7 ) { addTrack(0,track0); addTrack(1,track1); addTrack(2,track2); diff --git a/freeMemory.cpp b/freeMemory.cpp deleted file mode 100644 index df5ab8a..0000000 --- a/freeMemory.cpp +++ /dev/null @@ -1,112 +0,0 @@ -/* - * © 2021 Neil McKechnie - * © 2021 Mike S - * © 2020 Harald Barth - * - * This file is part of Asbelos DCC-EX - * - * This 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. - * - * It 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 CommandStation. If not, see . - */ - -#include -#include "freeMemory.h" - -// thanks go to https://github.com/mpflaga/Arduino-MemoryFree -#if defined(__arm__) -extern "C" char* sbrk(int); -#elif defined(__AVR__) -extern char *__brkval; -extern char *__malloc_heap_start; -#else -#error Unsupported board type -#endif - - -static volatile int minimum_free_memory = __INT_MAX__; - -#if !defined(__IMXRT1062__) -static inline int freeMemory() { - char top; -#if defined(__arm__) - return &top - reinterpret_cast(sbrk(0)); -#elif defined(__AVR__) - return __brkval ? &top - __brkval : &top - __malloc_heap_start; -#else -#error bailed out already above -#endif -} - -// Return low memory value. -int minimumFreeMemory() { - byte sreg_save = SREG; - noInterrupts(); // Disable interrupts - int retval = minimum_free_memory; - SREG = sreg_save; // Restore interrupt state - return retval; -} - -#else -#if defined(ARDUINO_TEENSY40) - static const unsigned DTCM_START = 0x20000000UL; - static const unsigned OCRAM_START = 0x20200000UL; - static const unsigned OCRAM_SIZE = 512; - static const unsigned FLASH_SIZE = 1984; -#elif defined(ARDUINO_TEENSY41) - static const unsigned DTCM_START = 0x20000000UL; - static const unsigned OCRAM_START = 0x20200000UL; - static const unsigned OCRAM_SIZE = 512; - static const unsigned FLASH_SIZE = 7936; -#if TEENSYDUINO>151 - extern "C" uint8_t external_psram_size; -#endif -#endif - -static inline int freeMemory() { - extern unsigned long _ebss; - extern unsigned long _sdata; - extern unsigned long _estack; - const unsigned DTCM_START = 0x20000000UL; - unsigned dtcm = (unsigned)&_estack - DTCM_START; - unsigned stackinuse = (unsigned) &_estack - (unsigned) __builtin_frame_address(0); - unsigned varsinuse = (unsigned)&_ebss - (unsigned)&_sdata; - unsigned freemem = dtcm - (stackinuse + varsinuse); - return freemem; -} - -// Return low memory value. -int minimumFreeMemory() { - //byte sreg_save = SREG; - //noInterrupts(); // Disable interrupts - int retval = minimum_free_memory; - //SREG = sreg_save; // Restore interrupt state - return retval; -} -#endif - - -// Update low ram level. Allow for extra bytes to be specified -// by estimation or inspection, that may be used by other -// called subroutines. Must be called with interrupts disabled. -// -// Although __brkval may go up and down as heap memory is allocated -// and freed, this function records only the worst case encountered. -// So even if all of the heap is freed, the reported minimum free -// memory will not increase. -// -void updateMinimumFreeMemory(unsigned char extraBytes) { - int spare = freeMemory()-extraBytes; - if (spare < 0) spare = 0; - if (spare < minimum_free_memory) minimum_free_memory = spare; -} - diff --git a/freeMemory.h b/freeMemory.h deleted file mode 100644 index af93566..0000000 --- a/freeMemory.h +++ /dev/null @@ -1,25 +0,0 @@ -/* - * © 2021 Neil McKechnie - * © 2020 Harald Barth - * - * This file is part of DCC-EX - * - * This 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. - * - * It 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 CommandStation. If not, see . - */ - -#ifndef freeMemory_h -#define freeMemory_h -void updateMinimumFreeMemory(unsigned char extraBytes=0); -int minimumFreeMemory(); -#endif