New HardwareTimer for STM32 5.7.0 (#15655)

This commit is contained in:
Lino Barreca
2019-11-13 02:23:02 +01:00
committed by Scott Lahteine
parent 4762dfe797
commit ac71cdc265
31 changed files with 1290 additions and 520 deletions

View File

@ -51,8 +51,8 @@ typedef uint64_t hal_timer_t;
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs // wrong would be 0.25
#else
#define STEPPER_TIMER_PRESCALE 40
#define STEPPER_TIMER_RATE (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) // frequency of stepper timer, 2MHz
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs
#define STEPPER_TIMER_RATE ((HAL_TIMER_RATE) / (STEPPER_TIMER_PRESCALE)) // frequency of stepper timer, 2MHz
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs
#endif
#define STEP_TIMER_MIN_INTERVAL 8 // minimum time in µs between stepper interrupts

View File

@ -99,7 +99,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
SYNC(tc->COUNT32.SYNCBUSY.bit.CTRLB);
// Set compare value
tc->COUNT32.COUNT.reg = tc->COUNT32.CC[0].reg = HAL_TIMER_RATE / frequency;
tc->COUNT32.COUNT.reg = tc->COUNT32.CC[0].reg = (HAL_TIMER_RATE) / frequency;
// And start timer
tc->COUNT32.CTRLA.bit.ENABLE = true;

View File

@ -28,6 +28,16 @@
#include "../../inc/MarlinConfig.h"
#include "../shared/Delay.h"
#if (__cplusplus == 201703L) && defined(__has_include)
#define HAS_SWSERIAL __has_include(<SoftwareSerial.h>)
#else
#define HAS_SWSERIAL HAS_TMC220x
#endif
#if HAS_SWSERIAL
#include "SoftwareSerial.h"
#endif
#if ENABLED(SRAM_EEPROM_EMULATION)
#if STM32F7xx
#include "stm32f7xx_ll_pwr.h"
@ -82,6 +92,10 @@ void HAL_init() {
// Wait until backup regulator is initialized
while (!LL_PWR_IsActiveFlag_BRR());
#endif // EEPROM_EMULATED_SRAM
#if HAS_SWSERIAL
SoftwareSerial::setInterruptPriority(SWSERIAL_TIMER_IRQ_PRIO, 0);
#endif
}
void HAL_clear_reset_source() { __HAL_RCC_CLEAR_RESET_FLAGS(); }

View File

@ -0,0 +1,391 @@
/*
* SoftwareSerial.cpp (formerly NewSoftSerial.cpp)
*
* Multi-instance software serial library for Arduino/Wiring
* -- Interrupt-driven receive and other improvements by ladyada
* (http://ladyada.net)
* -- Tuning, circular buffer, derivation from class Print/Stream,
* multi-instance support, porting to 8MHz processors,
* various optimizations, PROGMEM delay tables, inverse logic and
* direct port writing by Mikal Hart (http://www.arduiniana.org)
* -- Pin change interrupt macros by Paul Stoffregen (http://www.pjrc.com)
* -- 20MHz processor support by Garrett Mace (http://www.macetech.com)
* -- ATmega1280/2560 support by Brett Hagman (http://www.roguerobotics.com/)
* -- STM32 support by Armin van der Togt
*
* This library is free software; you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public
* License as published by the Free Software Foundation; either
* version 2.1 of the License, or (at your option) any later version.
*
* This library 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
* Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public
* License along with this library; if not, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* The latest version of this library can always be found at
* http://arduiniana.org.
*/
//
// Includes
//
#include "SoftwareSerial.h"
#include <timer.h>
#define OVERSAMPLE 3 // in RX, Timer will generate interruption OVERSAMPLE time during a bit. Thus OVERSAMPLE ticks in a bit. (interrupt not synchonized with edge).
// defined in bit-periods
#define HALFDUPLEX_SWITCH_DELAY 5
// It's best to define TIMER_SERIAL in variant.h. If not defined, we choose one here
// The order is based on (lack of) features and compare channels, we choose the simplest available
// because we only need an update interrupt
#if !defined(TIMER_SERIAL)
#if defined (TIM18_BASE)
#define TIMER_SERIAL TIM18
#elif defined (TIM7_BASE)
#define TIMER_SERIAL TIM7
#elif defined (TIM6_BASE)
#define TIMER_SERIAL TIM6
#elif defined (TIM22_BASE)
#define TIMER_SERIAL TIM22
#elif defined (TIM21_BASE)
#define TIMER_SERIAL TIM21
#elif defined (TIM17_BASE)
#define TIMER_SERIAL TIM17
#elif defined (TIM16_BASE)
#define TIMER_SERIAL TIM16
#elif defined (TIM15_BASE)
#define TIMER_SERIAL TIM15
#elif defined (TIM14_BASE)
#define TIMER_SERIAL TIM14
#elif defined (TIM13_BASE)
#define TIMER_SERIAL TIM13
#elif defined (TIM11_BASE)
#define TIMER_SERIAL TIM11
#elif defined (TIM10_BASE)
#define TIMER_SERIAL TIM10
#elif defined (TIM12_BASE)
#define TIMER_SERIAL TIM12
#elif defined (TIM19_BASE)
#define TIMER_SERIAL TIM19
#elif defined (TIM9_BASE)
#define TIMER_SERIAL TIM9
#elif defined (TIM5_BASE)
#define TIMER_SERIAL TIM5
#elif defined (TIM4_BASE)
#define TIMER_SERIAL TIM4
#elif defined (TIM3_BASE)
#define TIMER_SERIAL TIM3
#elif defined (TIM2_BASE)
#define TIMER_SERIAL TIM2
#elif defined (TIM20_BASE)
#define TIMER_SERIAL TIM20
#elif defined (TIM8_BASE)
#define TIMER_SERIAL TIM8
#elif defined (TIM1_BASE)
#define TIMER_SERIAL TIM1
#else
#error No suitable timer found for SoftwareSerial, define TIMER_SERIAL in variant.h
#endif
#endif
//
// Statics
//
HardwareTimer SoftwareSerial::timer(TIMER_SERIAL);
const IRQn_Type SoftwareSerial::timer_interrupt_number = static_cast<IRQn_Type>(getTimerUpIrq(TIMER_SERIAL));
uint32_t SoftwareSerial::timer_interrupt_priority = NVIC_EncodePriority(NVIC_GetPriorityGrouping(), TIM_IRQ_PRIO, TIM_IRQ_SUBPRIO);
SoftwareSerial *SoftwareSerial::active_listener = nullptr;
SoftwareSerial *volatile SoftwareSerial::active_out = nullptr;
SoftwareSerial *volatile SoftwareSerial::active_in = nullptr;
int32_t SoftwareSerial::tx_tick_cnt = 0; // OVERSAMPLE ticks needed for a bit
int32_t volatile SoftwareSerial::rx_tick_cnt = 0; // OVERSAMPLE ticks needed for a bit
uint32_t SoftwareSerial::tx_buffer = 0;
int32_t SoftwareSerial::tx_bit_cnt = 0;
uint32_t SoftwareSerial::rx_buffer = 0;
int32_t SoftwareSerial::rx_bit_cnt = -1; // rx_bit_cnt = -1 : waiting for start bit
uint32_t SoftwareSerial::cur_speed = 0;
void SoftwareSerial::setInterruptPriority(uint32_t preemptPriority, uint32_t subPriority) {
timer_interrupt_priority = NVIC_EncodePriority(NVIC_GetPriorityGrouping(), preemptPriority, subPriority);
}
//
// Private methods
//
void SoftwareSerial::setSpeed(uint32_t speed) {
if (speed != cur_speed) {
timer.pause();
if (speed != 0) {
// Disable the timer
uint32_t clock_rate, cmp_value;
// Get timer clock
clock_rate = timer.getTimerClkFreq();
int pre = 1;
// Calculate prescale an compare value
do {
cmp_value = clock_rate / (speed * OVERSAMPLE);
if (cmp_value >= UINT16_MAX) {
clock_rate /= 2;
pre *= 2;
}
} while (cmp_value >= UINT16_MAX);
timer.setPrescaleFactor(pre);
timer.setOverflow(cmp_value);
timer.setCount(0);
timer.attachInterrupt(&handleInterrupt);
timer.resume();
NVIC_SetPriority(timer_interrupt_number, timer_interrupt_priority);
}
else
timer.detachInterrupt();
cur_speed = speed;
}
}
// This function sets the current object as the "listening"
// one and returns true if it replaces another
bool SoftwareSerial::listen() {
if (active_listener != this) {
// wait for any transmit to complete as we may change speed
while (active_out);
active_listener->stopListening();
rx_tick_cnt = 1; // 1 : next interrupt will decrease rx_tick_cnt to 0 which means RX pin level will be considered.
rx_bit_cnt = -1; // rx_bit_cnt = -1 : waiting for start bit
setSpeed(_speed);
active_listener = this;
if (!_half_duplex) active_in = this;
return true;
}
return false;
}
// Stop listening. Returns true if we were actually listening.
bool SoftwareSerial::stopListening() {
if (active_listener == this) {
// wait for any output to complete
while (active_out);
if (_half_duplex) setRXTX(false);
active_listener = nullptr;
active_in = nullptr;
// turn off ints
setSpeed(0);
return true;
}
return false;
}
inline void SoftwareSerial::setTX() {
if (_inverse_logic)
LL_GPIO_ResetOutputPin(_transmitPinPort, _transmitPinNumber);
else
LL_GPIO_SetOutputPin(_transmitPinPort, _transmitPinNumber);
pinMode(_transmitPin, OUTPUT);
}
inline void SoftwareSerial::setRX() {
pinMode(_receivePin, _inverse_logic ? INPUT_PULLDOWN : INPUT_PULLUP); // pullup for normal logic!
}
inline void SoftwareSerial::setRXTX(bool input) {
if (_half_duplex) {
if (input) {
if (active_in != this) {
setRX();
rx_bit_cnt = -1; // rx_bit_cnt = -1 : waiting for start bit
rx_tick_cnt = 2; // 2 : next interrupt will be discarded. 2 interrupts required to consider RX pin level
active_in = this;
}
}
else {
if (active_in == this) {
setTX();
active_in = nullptr;
}
}
}
}
inline void SoftwareSerial::send() {
if (--tx_tick_cnt <= 0) { // if tx_tick_cnt > 0 interrupt is discarded. Only when tx_tick_cnt reaches 0 is TX pin set.
if (tx_bit_cnt++ < 10) { // tx_bit_cnt < 10 transmission is not finished (10 = 1 start +8 bits + 1 stop)
// Send data (including start and stop bits)
if (tx_buffer & 1)
LL_GPIO_SetOutputPin(_transmitPinPort, _transmitPinNumber);
else
LL_GPIO_ResetOutputPin(_transmitPinPort, _transmitPinNumber);
tx_buffer >>= 1;
tx_tick_cnt = OVERSAMPLE; // Wait OVERSAMPLE ticks to send next bit
}
else { // Transmission finished
tx_tick_cnt = 1;
if (_output_pending) {
active_out = nullptr;
// In half-duplex mode wait HALFDUPLEX_SWITCH_DELAY bit-periods after the byte has
// been transmitted before allowing the switch to RX mode
}
else if (tx_bit_cnt > 10 + OVERSAMPLE * HALFDUPLEX_SWITCH_DELAY) {
if (_half_duplex && active_listener == this) setRXTX(true);
active_out = nullptr;
}
}
}
}
//
// The receive routine called by the interrupt handler
//
inline void SoftwareSerial::recv() {
if (--rx_tick_cnt <= 0) { // if rx_tick_cnt > 0 interrupt is discarded. Only when rx_tick_cnt reaches 0 is RX pin considered
bool inbit = LL_GPIO_IsInputPinSet(_receivePinPort, _receivePinNumber) ^ _inverse_logic;
if (rx_bit_cnt == -1) { // rx_bit_cnt = -1 : waiting for start bit
if (!inbit) {
// got start bit
rx_bit_cnt = 0; // rx_bit_cnt == 0 : start bit received
rx_tick_cnt = OVERSAMPLE + 1; // Wait 1 bit (OVERSAMPLE ticks) + 1 tick in order to sample RX pin in the middle of the edge (and not too close to the edge)
rx_buffer = 0;
}
else
rx_tick_cnt = 1; // Waiting for start bit, but wrong level. Wait for next Interrupt to check RX pin level
}
else if (rx_bit_cnt >= 8) { // rx_bit_cnt >= 8 : waiting for stop bit
if (inbit) {
// Stop-bit read complete. Add to buffer.
uint8_t next = (_receive_buffer_tail + 1) % _SS_MAX_RX_BUFF;
if (next != _receive_buffer_head) {
// save new data in buffer: tail points to byte destination
_receive_buffer[_receive_buffer_tail] = rx_buffer; // save new byte
_receive_buffer_tail = next;
}
else // rx_bit_cnt = x with x = [0..7] correspond to new bit x received
_buffer_overflow = true;
}
// Full trame received. Restart waiting for start bit at next interrupt
rx_tick_cnt = 1;
rx_bit_cnt = -1;
}
else {
// data bits
rx_buffer >>= 1;
if (inbit) rx_buffer |= 0x80;
rx_bit_cnt++; // Prepare for next bit
rx_tick_cnt = OVERSAMPLE; // Wait OVERSAMPLE ticks before sampling next bit
}
}
}
//
// Interrupt handling
//
/* static */
inline void SoftwareSerial::handleInterrupt(HardwareTimer*) {
if (active_in) active_in->recv();
if (active_out) active_out->send();
}
//
// Constructor
//
SoftwareSerial::SoftwareSerial(uint16_t receivePin, uint16_t transmitPin, bool inverse_logic /* = false */) :
_receivePin(receivePin),
_transmitPin(transmitPin),
_receivePinPort(digitalPinToPort(receivePin)),
_receivePinNumber(STM_LL_GPIO_PIN(digitalPinToPinName(receivePin))),
_transmitPinPort(digitalPinToPort(transmitPin)),
_transmitPinNumber(STM_LL_GPIO_PIN(digitalPinToPinName(transmitPin))),
_speed(0),
_buffer_overflow(false),
_inverse_logic(inverse_logic),
_half_duplex(receivePin == transmitPin),
_output_pending(0),
_receive_buffer_tail(0),
_receive_buffer_head(0)
{
if ((receivePin < NUM_DIGITAL_PINS) || (transmitPin < NUM_DIGITAL_PINS)) {
/* Enable GPIO clock for tx and rx pin*/
set_GPIO_Port_Clock(STM_PORT(digitalPinToPinName(transmitPin)));
set_GPIO_Port_Clock(STM_PORT(digitalPinToPinName(receivePin)));
}
else
_Error_Handler("ERROR: invalid pin number\n", -1);
}
//
// Destructor
//
SoftwareSerial::~SoftwareSerial() { end(); }
//
// Public methods
//
void SoftwareSerial::begin(long speed) {
#ifdef FORCE_BAUD_RATE
speed = FORCE_BAUD_RATE;
#endif
_speed = speed;
if (!_half_duplex) {
setTX();
setRX();
listen();
}
else
setTX();
}
void SoftwareSerial::end() {
stopListening();
}
// Read data from buffer
int SoftwareSerial::read() {
// Empty buffer?
if (_receive_buffer_head == _receive_buffer_tail) return -1;
// Read from "head"
uint8_t d = _receive_buffer[_receive_buffer_head]; // grab next byte
_receive_buffer_head = (_receive_buffer_head + 1) % _SS_MAX_RX_BUFF;
return d;
}
int SoftwareSerial::available() {
return (_receive_buffer_tail + _SS_MAX_RX_BUFF - _receive_buffer_head) % _SS_MAX_RX_BUFF;
}
size_t SoftwareSerial::write(uint8_t b) {
// wait for previous transmit to complete
_output_pending = 1;
while (active_out) { /* nada */ }
// add start and stop bits.
tx_buffer = b << 1 | 0x200;
if (_inverse_logic) tx_buffer = ~tx_buffer;
tx_bit_cnt = 0;
tx_tick_cnt = OVERSAMPLE;
setSpeed(_speed);
if (_half_duplex) setRXTX(false);
_output_pending = 0;
// make us active
active_out = this;
return 1;
}
void SoftwareSerial::flush() {
noInterrupts();
_receive_buffer_head = _receive_buffer_tail = 0;
interrupts();
}
int SoftwareSerial::peek() {
// Empty buffer?
if (_receive_buffer_head == _receive_buffer_tail) return -1;
// Read from "head"
return _receive_buffer[_receive_buffer_head];
}

View File

@ -0,0 +1,119 @@
/**
* SoftwareSerial.h (formerly NewSoftSerial.h)
*
* Multi-instance software serial library for Arduino/Wiring
* -- Interrupt-driven receive and other improvements by ladyada
* (http://ladyada.net)
* -- Tuning, circular buffer, derivation from class Print/Stream,
* multi-instance support, porting to 8MHz processors,
* various optimizations, PROGMEM delay tables, inverse logic and
* direct port writing by Mikal Hart (http://www.arduiniana.org)
* -- Pin change interrupt macros by Paul Stoffregen (http://www.pjrc.com)
* -- 20MHz processor support by Garrett Mace (http://www.macetech.com)
* -- ATmega1280/2560 support by Brett Hagman (http://www.roguerobotics.com/)
*
* This library is free software; you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public
* License as published by the Free Software Foundation; either
* version 2.1 of the License, or (at your option) any later version.
*
* This library 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
* Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public
* License along with this library; if not, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* The latest version of this library can always be found at
* http://arduiniana.org.
*/
#ifndef SOFTWARESERIAL_H
#define SOFTWARESERIAL_H
#include <Arduino.h>
/******************************************************************************
* Definitions
******************************************************************************/
#define _SS_MAX_RX_BUFF 64 // RX buffer size
class SoftwareSerial : public Stream {
private:
// per object data
uint16_t _receivePin;
uint16_t _transmitPin;
GPIO_TypeDef *_receivePinPort;
uint32_t _receivePinNumber;
GPIO_TypeDef *_transmitPinPort;
uint32_t _transmitPinNumber;
uint32_t _speed;
uint16_t _buffer_overflow: 1;
uint16_t _inverse_logic: 1;
uint16_t _half_duplex: 1;
uint16_t _output_pending: 1;
unsigned char _receive_buffer[_SS_MAX_RX_BUFF];
volatile uint8_t _receive_buffer_tail;
volatile uint8_t _receive_buffer_head;
uint32_t delta_start = 0;
// static data
static bool initialised;
static HardwareTimer timer;
static const IRQn_Type timer_interrupt_number;
static uint32_t timer_interrupt_priority;
static SoftwareSerial *active_listener;
static SoftwareSerial *volatile active_out;
static SoftwareSerial *volatile active_in;
static int32_t tx_tick_cnt;
static volatile int32_t rx_tick_cnt;
static uint32_t tx_buffer;
static int32_t tx_bit_cnt;
static uint32_t rx_buffer;
static int32_t rx_bit_cnt;
static uint32_t cur_speed;
// private methods
void send();
void recv();
void setTX();
void setRX();
void setSpeed(uint32_t speed);
void setRXTX(bool input);
static void handleInterrupt(HardwareTimer *timer);
public:
// public methods
SoftwareSerial(uint16_t receivePin, uint16_t transmitPin, bool inverse_logic = false);
virtual ~SoftwareSerial();
void begin(long speed);
bool listen();
void end();
bool isListening() { return active_listener == this; }
bool stopListening();
bool overflow() {
bool ret = _buffer_overflow;
if (ret) _buffer_overflow = false;
return ret;
}
int peek();
virtual size_t write(uint8_t byte);
virtual int read();
virtual int available();
virtual void flush();
operator bool() { return true; }
static void setInterruptPriority(uint32_t preemptPriority, uint32_t subPriority);
using Print::write;
};
#endif // SOFTWARESERIAL_H

View File

@ -32,62 +32,108 @@
#define NUM_HARDWARE_TIMERS 2
#define __TIMER_DEV(X) TIM##X
#define _TIMER_DEV(X) __TIMER_DEV(X)
#define STEP_TIMER_DEV _TIMER_DEV(STEP_TIMER)
#define TEMP_TIMER_DEV _TIMER_DEV(TEMP_TIMER)
// ------------------------
// Private Variables
// ------------------------
stm32_timer_t TimerHandle[NUM_HARDWARE_TIMERS];
HardwareTimer *timer_instance[NUM_HARDWARE_TIMERS] = { NULL };
bool timer_enabled[NUM_HARDWARE_TIMERS] = { false };
// ------------------------
// Public functions
// ------------------------
bool timers_initialized[NUM_HARDWARE_TIMERS] = { false };
// frequency is in Hertz
void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
if (!timers_initialized[timer_num]) {
uint32_t step_prescaler = STEPPER_TIMER_PRESCALE - 1,
temp_prescaler = TEMP_TIMER_PRESCALE - 1;
if (!HAL_timer_initialized(timer_num)) {
switch (timer_num) {
case STEP_TIMER_NUM: // STEPPER TIMER - use a 32bit timer if possible
timer_instance[timer_num] = new HardwareTimer(STEP_TIMER_DEV);
/* Set the prescaler to the final desired value.
* This will change the effective ISR callback frequency but when
* HAL_timer_start(timer_num=0) is called in the core for the first time
* the real frequency isn't important as long as, after boot, the ISR
* gets called with the correct prescaler and count register. So here
* we set the prescaler to the correct, final value and ignore the frequency
* asked. We will call back the ISR in 1 second to start at full speed.
*
* The proper fix, however, would be a correct initialization OR a
* HAL_timer_change(const uint8_t timer_num, const uint32_t frequency)
* which changes the prescaler when an IRQ frequency change is needed
* (for example when steppers are turned on)
*/
timer_instance[timer_num]->setPrescaleFactor(STEPPER_TIMER_PRESCALE); //the -1 is done internally
timer_instance[timer_num]->setOverflow(_MIN(hal_timer_t(HAL_TIMER_TYPE_MAX), (HAL_TIMER_RATE) / (STEPPER_TIMER_PRESCALE) /* /frequency */), TICK_FORMAT);
break;
case TEMP_TIMER_NUM: // TEMP TIMER - any available 16bit timer
timer_instance[timer_num] = new HardwareTimer(TEMP_TIMER_DEV);
// The prescale factor is computed automatically for HERTZ_FORMAT
timer_instance[timer_num]->setOverflow(frequency, HERTZ_FORMAT);
break;
}
HAL_timer_enable_interrupt(timer_num);
/*
* Initializes (and unfortunately starts) the timer.
* This is needed to set correct IRQ priority at the moment but causes
* no harm since every call to HAL_timer_start() is actually followed by
* a call to HAL_timer_enable_interrupt() which means that there isn't
* a case in which you want the timer to run without a callback.
*/
timer_instance[timer_num]->resume(); // First call to resume() MUST follow the attachInterrupt()
// This is fixed in Arduino_Core_STM32 1.8.
// These calls can be removed and replaced with
// timer_instance[timer_num]->setInterruptPriority
switch (timer_num) {
case STEP_TIMER_NUM:
// STEPPER TIMER - use a 32bit timer if possible
TimerHandle[timer_num].timer = STEP_TIMER_DEV;
TimerHandle[timer_num].irqHandle = Step_Handler;
TimerHandleInit(&TimerHandle[timer_num], (((HAL_TIMER_RATE) / step_prescaler) / frequency) - 1, step_prescaler);
HAL_NVIC_SetPriority(STEP_TIMER_IRQ_NAME, STEP_TIMER_IRQ_PRIO, 0);
break;
case TEMP_TIMER_NUM:
// TEMP TIMER - any available 16bit Timer
TimerHandle[timer_num].timer = TEMP_TIMER_DEV;
TimerHandle[timer_num].irqHandle = Temp_Handler;
TimerHandleInit(&TimerHandle[timer_num], (((HAL_TIMER_RATE) / temp_prescaler) / frequency) - 1, temp_prescaler);
HAL_NVIC_SetPriority(TEMP_TIMER_IRQ_NAME, TEMP_TIMER_IRQ_PRIO, 0);
break;
}
timers_initialized[timer_num] = true;
}
}
void HAL_timer_enable_interrupt(const uint8_t timer_num) {
const IRQn_Type IRQ_Id = IRQn_Type(getTimerIrq(TimerHandle[timer_num].timer));
HAL_NVIC_EnableIRQ(IRQ_Id);
if (HAL_timer_initialized(timer_num) && !timer_enabled[timer_num]) {
timer_enabled[timer_num] = true;
switch (timer_num) {
case STEP_TIMER_NUM:
timer_instance[timer_num]->attachInterrupt(Step_Handler);
break;
case TEMP_TIMER_NUM:
timer_instance[timer_num]->attachInterrupt(Temp_Handler);
break;
}
}
}
void HAL_timer_disable_interrupt(const uint8_t timer_num) {
const IRQn_Type IRQ_Id = IRQn_Type(getTimerIrq(TimerHandle[timer_num].timer));
HAL_NVIC_DisableIRQ(IRQ_Id);
// We NEED memory barriers to ensure Interrupts are actually disabled!
// ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the )
__DSB();
__ISB();
if (HAL_timer_interrupt_enabled(timer_num)) {
timer_instance[timer_num]->detachInterrupt();
timer_enabled[timer_num] = false;
}
}
bool HAL_timer_interrupt_enabled(const uint8_t timer_num) {
const uint32_t IRQ_Id = getTimerIrq(TimerHandle[timer_num].timer);
return NVIC->ISER[IRQ_Id >> 5] & _BV32(IRQ_Id & 0x1F);
return HAL_timer_initialized(timer_num) && timer_enabled[timer_num];
}
// Only for use within the HAL
TIM_TypeDef * HAL_timer_device(const uint8_t timer_num) {
switch (timer_num) {
case STEP_TIMER_NUM: return STEP_TIMER_DEV;
case TEMP_TIMER_NUM: return TEMP_TIMER_DEV;
}
return nullptr;
}
#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC

View File

@ -33,6 +33,7 @@
#define hal_timer_t uint32_t
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFF // Timers can be 16 or 32 bit
#ifdef STM32F0xx
#define HAL_TIMER_RATE (F_CPU) // frequency of timer peripherals
@ -66,27 +67,30 @@
#endif
#ifndef TEMP_TIMER
#define TEMP_TIMER 7
#define TEMP_TIMER 14 // TIM7 is consumed by Software Serial if used.
#endif
#endif
#ifndef SWSERIAL_TIMER_IRQ_PRIO
#define SWSERIAL_TIMER_IRQ_PRIO 1
#endif
#ifndef STEP_TIMER_IRQ_PRIO
#define STEP_TIMER_IRQ_PRIO 1
#define STEP_TIMER_IRQ_PRIO 2
#endif
#ifndef TEMP_TIMER_IRQ_PRIO
#define TEMP_TIMER_IRQ_PRIO 2
#define TEMP_TIMER_IRQ_PRIO 14 //14 = after hardware ISRs
#endif
#define STEP_TIMER_NUM 0 // index of timer to use for stepper
#define TEMP_TIMER_NUM 1 // index of timer to use for temperature
#define PULSE_TIMER_NUM STEP_TIMER_NUM
#define TEMP_TIMER_RATE 72000 // 72 Khz
#define TEMP_TIMER_PRESCALE ((HAL_TIMER_RATE)/(TEMP_TIMER_RATE))
#define TEMP_TIMER_FREQUENCY 1000
#define TEMP_TIMER_FREQUENCY 1000 //Temperature::isr() is expected to be called at around 1kHz
//TODO: get rid of manual rate/prescale/ticks/cycles taken for procedures in stepper.cpp
#define STEPPER_TIMER_RATE 2000000 // 2 Mhz
#define STEPPER_TIMER_PRESCALE ((HAL_TIMER_RATE)/(STEPPER_TIMER_RATE))
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs
@ -95,17 +99,6 @@
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
#define __TIMER_DEV(X) TIM##X
#define _TIMER_DEV(X) __TIMER_DEV(X)
#define STEP_TIMER_DEV _TIMER_DEV(STEP_TIMER)
#define TEMP_TIMER_DEV _TIMER_DEV(TEMP_TIMER)
#define __TIMER_CALLBACK(X) TIM##X##_IRQHandler
#define _TIMER_CALLBACK(X) __TIMER_CALLBACK(X)
#define STEP_TIMER_CALLBACK _TIMER_CALLBACK(STEP_TIMER)
#define TEMP_TIMER_CALLBACK _TIMER_CALLBACK(TEMP_TIMER)
#define __TIMER_IRQ_NAME(X) TIM##X##_IRQn
#define _TIMER_IRQ_NAME(X) __TIMER_IRQ_NAME(X)
@ -119,22 +112,16 @@
#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM)
#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM)
extern void Step_Handler(stimer_t *htim);
extern void Temp_Handler(stimer_t *htim);
#define HAL_STEP_TIMER_ISR() void Step_Handler(stimer_t *htim)
#define HAL_TEMP_TIMER_ISR() void Temp_Handler(stimer_t *htim)
// ------------------------
// Types
// ------------------------
typedef stimer_t stm32_timer_t;
extern void Step_Handler(HardwareTimer *htim);
extern void Temp_Handler(HardwareTimer *htim);
#define HAL_STEP_TIMER_ISR() void Step_Handler(HardwareTimer *htim)
#define HAL_TEMP_TIMER_ISR() void Temp_Handler(HardwareTimer *htim)
// ------------------------
// Public Variables
// ------------------------
extern stm32_timer_t TimerHandle[];
extern HardwareTimer *timer_instance[];
// ------------------------
// Public functions
@ -145,18 +132,26 @@ void HAL_timer_enable_interrupt(const uint8_t timer_num);
void HAL_timer_disable_interrupt(const uint8_t timer_num);
bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
FORCE_INLINE static uint32_t HAL_timer_get_count(const uint8_t timer_num) {
return __HAL_TIM_GET_COUNTER(&TimerHandle[timer_num].handle);
//TIM_TypeDef* HAL_timer_device(const uint8_t timer_num); no need to be public for now. not public = not used externally
// FORCE_INLINE because these are used in performance-critical situations
FORCE_INLINE bool HAL_timer_initialized(const uint8_t timer_num) {
return timer_instance[timer_num] != NULL;
}
FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) {
return HAL_timer_initialized(timer_num) ? timer_instance[timer_num]->getCount() : 0;
}
FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const uint32_t compare) {
__HAL_TIM_SET_AUTORELOAD(&TimerHandle[timer_num].handle, compare);
if (HAL_timer_get_count(timer_num) >= compare)
TimerHandle[timer_num].handle.Instance->EGR |= TIM_EGR_UG; // Generate an immediate update interrupt
}
FORCE_INLINE static hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) {
return __HAL_TIM_GET_AUTORELOAD(&TimerHandle[timer_num].handle);
// NOTE: Method name may be misleading.
// STM32 has an Auto-Reload Register (ARR) as opposed to a "compare" register
FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t overflow) {
if (HAL_timer_initialized(timer_num)) {
timer_instance[timer_num]->setOverflow(overflow + 1, TICK_FORMAT); // Value decremented by setOverflow()
// wiki: "force all registers (Autoreload, prescaler, compare) to be taken into account"
// So, if the new overflow value is less than the count it will trigger a rollover interrupt.
if (overflow < timer_instance[timer_num]->getCount()) // Added 'if' here because reports say it won't boot without it
timer_instance[timer_num]->refresh();
}
}
#define HAL_timer_isr_prologue(TIMER_NUM)

View File

@ -82,7 +82,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
timer_set_prescaler(STEP_TIMER_DEV, (uint16_t)(STEPPER_TIMER_PRESCALE - 1));
timer_set_reload(STEP_TIMER_DEV, 0xFFFF);
timer_oc_set_mode(STEP_TIMER_DEV, STEP_TIMER_CHAN, TIMER_OC_MODE_FROZEN, TIMER_OC_NO_PRELOAD); // no output pin change
timer_set_compare(STEP_TIMER_DEV, STEP_TIMER_CHAN, _MIN(hal_timer_t(HAL_TIMER_TYPE_MAX), (STEPPER_TIMER_RATE / frequency)));
timer_set_compare(STEP_TIMER_DEV, STEP_TIMER_CHAN, _MIN(hal_timer_t(HAL_TIMER_TYPE_MAX), (STEPPER_TIMER_RATE) / frequency));
timer_no_ARR_preload_ARPE(STEP_TIMER_DEV); // Need to be sure no preload on ARR register
timer_attach_interrupt(STEP_TIMER_DEV, STEP_TIMER_CHAN, stepTC_Handler);
nvic_irq_set_priority(irq_num, STEP_TIMER_IRQ_PRIO);
@ -95,7 +95,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
timer_set_count(TEMP_TIMER_DEV, 0);
timer_set_prescaler(TEMP_TIMER_DEV, (uint16_t)(TEMP_TIMER_PRESCALE - 1));
timer_set_reload(TEMP_TIMER_DEV, 0xFFFF);
timer_set_compare(TEMP_TIMER_DEV, TEMP_TIMER_CHAN, _MIN(hal_timer_t(HAL_TIMER_TYPE_MAX), ((F_CPU / TEMP_TIMER_PRESCALE) / frequency)));
timer_set_compare(TEMP_TIMER_DEV, TEMP_TIMER_CHAN, _MIN(hal_timer_t(HAL_TIMER_TYPE_MAX), (F_CPU) / (TEMP_TIMER_PRESCALE) / frequency));
timer_attach_interrupt(TEMP_TIMER_DEV, TEMP_TIMER_CHAN, tempTC_Handler);
nvic_irq_set_priority(irq_num, TEMP_TIMER_IRQ_PRIO);
timer_generate_update(TEMP_TIMER_DEV);

View File

@ -24,16 +24,15 @@
#define CPU_32_BIT
#include "../../inc/MarlinConfigPre.h"
#include "../shared/Marduino.h"
#include "../shared/math_32bit.h"
#include "../shared/HAL_SPI.h"
#include "fastio.h"
#include "watchdog.h"
#include "timers.h"
#include "../../inc/MarlinConfigPre.h"
#include "watchdog.h"
#include <stdint.h>

View File

@ -53,7 +53,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
FTM0_SC = 0x00; // Set this to zero before changing the modulus
FTM0_CNT = 0x0000; // Reset the count to zero
FTM0_MOD = 0xFFFF; // max modulus = 65535
FTM0_C0V = FTM0_TIMER_RATE / frequency; // Initial FTM Channel 0 compare value
FTM0_C0V = (FTM0_TIMER_RATE) / frequency; // Initial FTM Channel 0 compare value
FTM0_SC = (FTM_SC_CLKS(0b1) & FTM_SC_CLKS_MASK) | (FTM_SC_PS(FTM0_TIMER_PRESCALE_BITS) & FTM_SC_PS_MASK); // Bus clock 60MHz divided by prescaler 8
FTM0_C0SC = FTM_CSC_CHIE | FTM_CSC_MSA | FTM_CSC_ELSA;
break;
@ -62,7 +62,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
FTM1_SC = 0x00; // Set this to zero before changing the modulus
FTM1_CNT = 0x0000; // Reset the count to zero
FTM1_MOD = 0xFFFF; // max modulus = 65535
FTM1_C0V = FTM1_TIMER_RATE / frequency; // Initial FTM Channel 0 compare value 65535
FTM1_C0V = (FTM1_TIMER_RATE) / frequency; // Initial FTM Channel 0 compare value 65535
FTM1_SC = (FTM_SC_CLKS(0b1) & FTM_SC_CLKS_MASK) | (FTM_SC_PS(FTM1_TIMER_PRESCALE_BITS) & FTM_SC_PS_MASK); // Bus clock 60MHz divided by prescaler 4
FTM1_C0SC = FTM_CSC_CHIE | FTM_CSC_MSA | FTM_CSC_ELSA;
break;

View File

@ -54,7 +54,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
FTM0_SC = 0x00; // Set this to zero before changing the modulus
FTM0_CNT = 0x0000; // Reset the count to zero
FTM0_MOD = 0xFFFF; // max modulus = 65535
FTM0_C0V = FTM0_TIMER_RATE / frequency; // Initial FTM Channel 0 compare value
FTM0_C0V = (FTM0_TIMER_RATE) / frequency; // Initial FTM Channel 0 compare value
FTM0_SC = (FTM_SC_CLKS(0b1) & FTM_SC_CLKS_MASK) | (FTM_SC_PS(FTM0_TIMER_PRESCALE_BITS) & FTM_SC_PS_MASK); // Bus clock 60MHz divided by prescaler 8
FTM0_C0SC = FTM_CSC_CHIE | FTM_CSC_MSA | FTM_CSC_ELSA;
break;
@ -63,7 +63,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
FTM1_SC = 0x00; // Set this to zero before changing the modulus
FTM1_CNT = 0x0000; // Reset the count to zero
FTM1_MOD = 0xFFFF; // max modulus = 65535
FTM1_C0V = FTM1_TIMER_RATE / frequency; // Initial FTM Channel 0 compare value 65535
FTM1_C0V = (FTM1_TIMER_RATE) / frequency; // Initial FTM Channel 0 compare value 65535
FTM1_SC = (FTM_SC_CLKS(0b1) & FTM_SC_CLKS_MASK) | (FTM_SC_PS(FTM1_TIMER_PRESCALE_BITS) & FTM_SC_PS_MASK); // Bus clock 60MHz divided by prescaler 4
FTM1_C0SC = FTM_CSC_CHIE | FTM_CSC_MSA | FTM_CSC_ELSA;
break;

View File

@ -1537,7 +1537,7 @@ void Stepper::stepper_pulse_phase_isr() {
uint32_t Stepper::stepper_block_phase_isr() {
// If no queued movements, just wait 1ms for the next move
uint32_t interval = (STEPPER_TIMER_RATE / 1000);
uint32_t interval = (STEPPER_TIMER_RATE) / 1000;
// If there is a current block
if (current_block) {

View File

@ -2290,7 +2290,7 @@ void Temperature::readings_ready() {
HAL_TEMP_TIMER_ISR() {
HAL_timer_isr_prologue(TEMP_TIMER_NUM);
Temperature::isr();
Temperature::tick();
HAL_timer_isr_epilogue(TEMP_TIMER_NUM);
}
@ -2320,11 +2320,21 @@ public:
#endif
};
void Temperature::isr() {
/**
* Handle various ~1KHz tasks associated with temperature
* - Heater PWM (~1KHz with scaler)
* - LCD Button polling (~500Hz)
* - Start / Read one ADC sensor
* - Advance Babysteps
* - Endstop polling
* - Planner clean buffer
*/
void Temperature::tick() {
static int8_t temp_count = -1;
static ADCSensorState adc_sensor_state = StartupDelay;
static uint8_t pwm_count = _BV(SOFT_PWM_SCALE);
// avoid multiple loads of pwm_count
uint8_t pwm_count_tmp = pwm_count;

View File

@ -217,8 +217,8 @@ typedef struct { int16_t raw_min, raw_max; } raw_range_t;
typedef struct { int16_t mintemp, maxtemp; } celsius_range_t;
typedef struct { int16_t raw_min, raw_max, mintemp, maxtemp; } temp_range_t;
#define THERMISTOR_ABS_ZERO_C -273.15f // bbbbrrrrr cold !
#define THERMISTOR_RESISTANCE_NOMINAL_C 25.0f // mmmmm comfortable
#define THERMISTOR_ABS_ZERO_C -273.15f // bbbbrrrrr cold !
#define THERMISTOR_RESISTANCE_NOMINAL_C 25.0f // mmmmm comfortable
#if HAS_USER_THERMISTORS
@ -267,8 +267,6 @@ class Temperature {
public:
static volatile bool in_temp_isr;
#if HOTENDS
#if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT)
#define HOTEND_TEMPS (HOTENDS + 1)
@ -513,7 +511,7 @@ class Temperature {
* Called from the Temperature ISR
*/
static void readings_ready();
static void isr();
static void tick();
/**
* Call periodically to manage heaters