701 changed files with 30146 additions and 13667 deletions
@ -1,396 +0,0 @@ |
|||||
/*
|
|
||||
* SoftwareSerial.cpp (formerly NewSoftSerial.cpp) |
|
||||
* |
|
||||
* Multi-instance software serial library for Arduino/Wiring |
|
||||
* -- Interrupt-driven receive and other improvements by ladyada |
|
||||
* <https://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 <https://www.pjrc.com>
|
|
||||
* -- 20MHz processor support by Garrett Mace <http://www.macetech.com>
|
|
||||
* -- ATmega1280/2560 support by Brett Hagman <https://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
|
|
||||
//
|
|
||||
#if defined(PLATFORMIO) && defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) |
|
||||
|
|
||||
#include "../../inc/MarlinConfig.h" |
|
||||
|
|
||||
#include "SoftwareSerial.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]; |
|
||||
} |
|
||||
|
|
||||
#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC
|
|
@ -1,114 +0,0 @@ |
|||||
/**
|
|
||||
* SoftwareSerial.h (formerly NewSoftSerial.h) |
|
||||
* |
|
||||
* Multi-instance software serial library for Arduino/Wiring |
|
||||
* -- Interrupt-driven receive and other improvements by ladyada |
|
||||
* (https://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 (https://www.pjrc.com)
|
|
||||
* -- 20MHz processor support by Garrett Mace (http://www.macetech.com)
|
|
||||
* -- ATmega1280/2560 support by Brett Hagman (https://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.
|
|
||||
*/ |
|
||||
#pragma once |
|
||||
|
|
||||
#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 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; |
|
||||
}; |
|
@ -0,0 +1,193 @@ |
|||||
|
/**
|
||||
|
* Marlin 3D Printer Firmware |
||||
|
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
|
* |
||||
|
* Based on Sprinter and grbl. |
||||
|
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm |
||||
|
* |
||||
|
* 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 <https://www.gnu.org/licenses/>.
|
||||
|
* |
||||
|
*/ |
||||
|
|
||||
|
#ifdef __STM32F1__ |
||||
|
|
||||
|
#include "../../inc/MarlinConfig.h" |
||||
|
#include "MarlinSerial.h" |
||||
|
#include <libmaple/usart.h> |
||||
|
|
||||
|
// Copied from ~/.platformio/packages/framework-arduinoststm32-maple/STM32F1/system/libmaple/usart_private.h
|
||||
|
// Changed to handle Emergency Parser
|
||||
|
static inline __always_inline void my_usart_irq(ring_buffer *rb, ring_buffer *wb, usart_reg_map *regs, MarlinSerial &serial) { |
||||
|
/* Handle RXNEIE and TXEIE interrupts.
|
||||
|
* RXNE signifies availability of a byte in DR. |
||||
|
* |
||||
|
* See table 198 (sec 27.4, p809) in STM document RM0008 rev 15. |
||||
|
* We enable RXNEIE. |
||||
|
*/ |
||||
|
uint32_t srflags = regs->SR, cr1its = regs->CR1; |
||||
|
|
||||
|
if ((cr1its & USART_CR1_RXNEIE) && (srflags & USART_SR_RXNE)) { |
||||
|
if (srflags & USART_SR_FE || srflags & USART_SR_PE ) { |
||||
|
// framing error or parity error
|
||||
|
regs->DR; // Read and throw away the data, which also clears FE and PE
|
||||
|
} |
||||
|
else { |
||||
|
uint8_t c = (uint8)regs->DR; |
||||
|
#ifdef USART_SAFE_INSERT |
||||
|
// If the buffer is full and the user defines USART_SAFE_INSERT,
|
||||
|
// ignore new bytes.
|
||||
|
rb_safe_insert(rb, c); |
||||
|
#else |
||||
|
// By default, push bytes around in the ring buffer.
|
||||
|
rb_push_insert(rb, c); |
||||
|
#endif |
||||
|
#if ENABLED(EMERGENCY_PARSER) |
||||
|
if (serial.emergency_parser_enabled()) |
||||
|
emergency_parser.update(serial.emergency_state, c); |
||||
|
#endif |
||||
|
} |
||||
|
} |
||||
|
else if (srflags & USART_SR_ORE) { |
||||
|
// overrun and empty data, just do a dummy read to clear ORE
|
||||
|
// and prevent a raise condition where a continous interrupt stream (due to ORE set) occurs
|
||||
|
// (see chapter "Overrun error" ) in STM32 reference manual
|
||||
|
regs->DR; |
||||
|
} |
||||
|
|
||||
|
// TXE signifies readiness to send a byte to DR.
|
||||
|
if ((cr1its & USART_CR1_TXEIE) && (srflags & USART_SR_TXE)) { |
||||
|
if (!rb_is_empty(wb)) |
||||
|
regs->DR=rb_remove(wb); |
||||
|
else |
||||
|
regs->CR1 &= ~((uint32)USART_CR1_TXEIE); // disable TXEIE
|
||||
|
} |
||||
|
} |
||||
|
|
||||
|
// Not every MarlinSerial port should handle emergency parsing.
|
||||
|
// It would not make sense to parse GCode from TMC responses, for example.
|
||||
|
constexpr bool serial_handles_emergency(int port) { |
||||
|
return false |
||||
|
#ifdef SERIAL_PORT |
||||
|
|| (SERIAL_PORT) == port |
||||
|
#endif |
||||
|
#ifdef SERIAL_PORT_2 |
||||
|
|| (SERIAL_PORT_2) == port |
||||
|
#endif |
||||
|
#ifdef LCD_SERIAL_PORT |
||||
|
|| (LCD_SERIAL_PORT) == port |
||||
|
#endif |
||||
|
; |
||||
|
} |
||||
|
|
||||
|
#define DEFINE_HWSERIAL_MARLIN(name, n) \ |
||||
|
MarlinSerial name(USART##n, \ |
||||
|
BOARD_USART##n##_TX_PIN, \ |
||||
|
BOARD_USART##n##_RX_PIN, \ |
||||
|
serial_handles_emergency(n)); \ |
||||
|
extern "C" void __irq_usart##n(void) { \ |
||||
|
my_usart_irq(USART##n->rb, USART##n->wb, USART##n##_BASE, MSerial##n); \ |
||||
|
} |
||||
|
|
||||
|
#define DEFINE_HWSERIAL_UART_MARLIN(name, n) \ |
||||
|
MarlinSerial name(UART##n, \ |
||||
|
BOARD_USART##n##_TX_PIN, \ |
||||
|
BOARD_USART##n##_RX_PIN, \ |
||||
|
serial_handles_emergency(n)); \ |
||||
|
extern "C" void __irq_usart##n(void) { \ |
||||
|
my_usart_irq(UART##n->rb, UART##n->wb, UART##n##_BASE, MSerial##n); \ |
||||
|
} |
||||
|
|
||||
|
// Instantiate all UARTs even if they are not needed
|
||||
|
// This avoids a bunch of logic to figure out every serial
|
||||
|
// port which may be in use on the system.
|
||||
|
DEFINE_HWSERIAL_MARLIN(MSerial1, 1); |
||||
|
DEFINE_HWSERIAL_MARLIN(MSerial2, 2); |
||||
|
DEFINE_HWSERIAL_MARLIN(MSerial3, 3); |
||||
|
#if EITHER(STM32_HIGH_DENSITY, STM32_XL_DENSITY) |
||||
|
DEFINE_HWSERIAL_UART_MARLIN(MSerial4, 4); |
||||
|
DEFINE_HWSERIAL_UART_MARLIN(MSerial5, 5); |
||||
|
#endif |
||||
|
|
||||
|
// Check the type of each serial port by passing it to a template function.
|
||||
|
// HardwareSerial is known to sometimes hang the controller when an error occurs,
|
||||
|
// so this case will fail the static assert. All other classes are assumed to be ok.
|
||||
|
template <typename T> |
||||
|
constexpr bool IsSerialClassAllowed(const T&) { return true; } |
||||
|
constexpr bool IsSerialClassAllowed(const HardwareSerial&) { return false; } |
||||
|
|
||||
|
#define CHECK_CFG_SERIAL(A) static_assert(IsSerialClassAllowed(A), STRINGIFY(A) " is defined incorrectly"); |
||||
|
#define CHECK_AXIS_SERIAL(A) static_assert(IsSerialClassAllowed(A##_HARDWARE_SERIAL), STRINGIFY(A) "_HARDWARE_SERIAL must be defined in the form MSerial1, rather than Serial1"); |
||||
|
|
||||
|
// If you encounter this error, replace SerialX with MSerialX, for example MSerial3.
|
||||
|
|
||||
|
// Non-TMC ports were already validated in HAL.h, so do not require verbose error messages.
|
||||
|
#ifdef MYSERIAL0 |
||||
|
CHECK_CFG_SERIAL(MYSERIAL0); |
||||
|
#endif |
||||
|
#ifdef MYSERIAL1 |
||||
|
CHECK_CFG_SERIAL(MYSERIAL1); |
||||
|
#endif |
||||
|
#ifdef LCD_SERIAL |
||||
|
CHECK_CFG_SERIAL(LCD_SERIAL); |
||||
|
#endif |
||||
|
#if AXIS_HAS_HW_SERIAL(X) |
||||
|
CHECK_AXIS_SERIAL(X); |
||||
|
#endif |
||||
|
#if AXIS_HAS_HW_SERIAL(X2) |
||||
|
CHECK_AXIS_SERIAL(X2); |
||||
|
#endif |
||||
|
#if AXIS_HAS_HW_SERIAL(Y) |
||||
|
CHECK_AXIS_SERIAL(Y); |
||||
|
#endif |
||||
|
#if AXIS_HAS_HW_SERIAL(Y2) |
||||
|
CHECK_AXIS_SERIAL(Y2); |
||||
|
#endif |
||||
|
#if AXIS_HAS_HW_SERIAL(Z) |
||||
|
CHECK_AXIS_SERIAL(Z); |
||||
|
#endif |
||||
|
#if AXIS_HAS_HW_SERIAL(Z2) |
||||
|
CHECK_AXIS_SERIAL(Z2); |
||||
|
#endif |
||||
|
#if AXIS_HAS_HW_SERIAL(Z3) |
||||
|
CHECK_AXIS_SERIAL(Z3); |
||||
|
#endif |
||||
|
#if AXIS_HAS_HW_SERIAL(Z4) |
||||
|
CHECK_AXIS_SERIAL(Z4); |
||||
|
#endif |
||||
|
#if AXIS_HAS_HW_SERIAL(E0) |
||||
|
CHECK_AXIS_SERIAL(E0); |
||||
|
#endif |
||||
|
#if AXIS_HAS_HW_SERIAL(E1) |
||||
|
CHECK_AXIS_SERIAL(E1); |
||||
|
#endif |
||||
|
#if AXIS_HAS_HW_SERIAL(E2) |
||||
|
CHECK_AXIS_SERIAL(E2); |
||||
|
#endif |
||||
|
#if AXIS_HAS_HW_SERIAL(E3) |
||||
|
CHECK_AXIS_SERIAL(E3); |
||||
|
#endif |
||||
|
#if AXIS_HAS_HW_SERIAL(E4) |
||||
|
CHECK_AXIS_SERIAL(E4); |
||||
|
#endif |
||||
|
#if AXIS_HAS_HW_SERIAL(E5) |
||||
|
CHECK_AXIS_SERIAL(E5); |
||||
|
#endif |
||||
|
#if AXIS_HAS_HW_SERIAL(E6) |
||||
|
CHECK_AXIS_SERIAL(E6); |
||||
|
#endif |
||||
|
#if AXIS_HAS_HW_SERIAL(E7) |
||||
|
CHECK_AXIS_SERIAL(E7); |
||||
|
#endif |
||||
|
|
||||
|
#endif // __STM32F1__
|
@ -0,0 +1,71 @@ |
|||||
|
/**
|
||||
|
* Marlin 3D Printer Firmware |
||||
|
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
|
* |
||||
|
* Based on Sprinter and grbl. |
||||
|
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm |
||||
|
* |
||||
|
* 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 <https://www.gnu.org/licenses/>.
|
||||
|
* |
||||
|
*/ |
||||
|
#pragma once |
||||
|
|
||||
|
#include <HardwareSerial.h> |
||||
|
#include <libmaple/usart.h> |
||||
|
#include <WString.h> |
||||
|
|
||||
|
#include "../../inc/MarlinConfigPre.h" |
||||
|
#if ENABLED(EMERGENCY_PARSER) |
||||
|
#include "../../feature/e_parser.h" |
||||
|
#endif |
||||
|
|
||||
|
// Increase priority of serial interrupts, to reduce overflow errors
|
||||
|
#define UART_IRQ_PRIO 1 |
||||
|
|
||||
|
class MarlinSerial : public HardwareSerial { |
||||
|
public: |
||||
|
#if ENABLED(EMERGENCY_PARSER) |
||||
|
const bool ep_enabled; |
||||
|
EmergencyParser::State emergency_state; |
||||
|
inline bool emergency_parser_enabled() { return ep_enabled; } |
||||
|
#endif |
||||
|
|
||||
|
MarlinSerial(struct usart_dev *usart_device, uint8 tx_pin, uint8 rx_pin, bool TERN_(EMERGENCY_PARSER, ep_capable)) : |
||||
|
HardwareSerial(usart_device, tx_pin, rx_pin) |
||||
|
#if ENABLED(EMERGENCY_PARSER) |
||||
|
, ep_enabled(ep_capable) |
||||
|
, emergency_state(EmergencyParser::State::EP_RESET) |
||||
|
#endif |
||||
|
{ } |
||||
|
|
||||
|
#ifdef UART_IRQ_PRIO |
||||
|
// Shadow the parent methods to set IRQ priority after begin()
|
||||
|
void begin(uint32 baud) { |
||||
|
MarlinSerial::begin(baud, SERIAL_8N1); |
||||
|
} |
||||
|
|
||||
|
void begin(uint32 baud, uint8_t config) { |
||||
|
HardwareSerial::begin(baud, config); |
||||
|
nvic_irq_set_priority(c_dev()->irq_num, UART_IRQ_PRIO); |
||||
|
} |
||||
|
#endif |
||||
|
}; |
||||
|
|
||||
|
extern MarlinSerial MSerial1; |
||||
|
extern MarlinSerial MSerial2; |
||||
|
extern MarlinSerial MSerial3; |
||||
|
#if EITHER(STM32_HIGH_DENSITY, STM32_XL_DENSITY) |
||||
|
extern MarlinSerial MSerial4; |
||||
|
extern MarlinSerial MSerial5; |
||||
|
#endif |
@ -0,0 +1,167 @@ |
|||||
|
/**
|
||||
|
* Marlin 3D Printer Firmware |
||||
|
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
|
* |
||||
|
* Based on Sprinter and grbl. |
||||
|
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm |
||||
|
* |
||||
|
* 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 <https://www.gnu.org/licenses/>.
|
||||
|
* |
||||
|
*/ |
||||
|
|
||||
|
/**
|
||||
|
* Description: HAL for Teensy40 (IMXRT1062) |
||||
|
*/ |
||||
|
|
||||
|
#ifdef __IMXRT1062__ |
||||
|
|
||||
|
#include "HAL.h" |
||||
|
#include "../shared/Delay.h" |
||||
|
#include "timers.h" |
||||
|
|
||||
|
#include <Wire.h> |
||||
|
|
||||
|
uint16_t HAL_adc_result, HAL_adc_select; |
||||
|
|
||||
|
static const uint8_t pin2sc1a[] = { |
||||
|
0x07, // 0/A0 AD_B1_02
|
||||
|
0x08, // 1/A1 AD_B1_03
|
||||
|
0x0C, // 2/A2 AD_B1_07
|
||||
|
0x0B, // 3/A3 AD_B1_06
|
||||
|
0x06, // 4/A4 AD_B1_01
|
||||
|
0x05, // 5/A5 AD_B1_00
|
||||
|
0x0F, // 6/A6 AD_B1_10
|
||||
|
0x00, // 7/A7 AD_B1_11
|
||||
|
0x0D, // 8/A8 AD_B1_08
|
||||
|
0x0E, // 9/A9 AD_B1_09
|
||||
|
0x01, // 24/A10 AD_B0_12
|
||||
|
0x02, // 25/A11 AD_B0_13
|
||||
|
0x83, // 26/A12 AD_B1_14 - only on ADC2, 3
|
||||
|
0x84, // 27/A13 AD_B1_15 - only on ADC2, 4
|
||||
|
0x07, // 14/A0 AD_B1_02
|
||||
|
0x08, // 15/A1 AD_B1_03
|
||||
|
0x0C, // 16/A2 AD_B1_07
|
||||
|
0x0B, // 17/A3 AD_B1_06
|
||||
|
0x06, // 18/A4 AD_B1_01
|
||||
|
0x05, // 19/A5 AD_B1_00
|
||||
|
0x0F, // 20/A6 AD_B1_10
|
||||
|
0x00, // 21/A7 AD_B1_11
|
||||
|
0x0D, // 22/A8 AD_B1_08
|
||||
|
0x0E, // 23/A9 AD_B1_09
|
||||
|
0x01, // 24/A10 AD_B0_12
|
||||
|
0x02, // 25/A11 AD_B0_13
|
||||
|
0x83, // 26/A12 AD_B1_14 - only on ADC2, 3
|
||||
|
0x84, // 27/A13 AD_B1_15 - only on ADC2, 4
|
||||
|
#ifdef ARDUINO_TEENSY41 |
||||
|
0xFF, // 28
|
||||
|
0xFF, // 29
|
||||
|
0xFF, // 30
|
||||
|
0xFF, // 31
|
||||
|
0xFF, // 32
|
||||
|
0xFF, // 33
|
||||
|
0xFF, // 34
|
||||
|
0xFF, // 35
|
||||
|
0xFF, // 36
|
||||
|
0xFF, // 37
|
||||
|
0x81, // 38/A14 AD_B1_12 - only on ADC2, 1
|
||||
|
0x82, // 39/A15 AD_B1_13 - only on ADC2, 2
|
||||
|
0x09, // 40/A16 AD_B1_04
|
||||
|
0x0A, // 41/A17 AD_B1_05
|
||||
|
#endif |
||||
|
}; |
||||
|
|
||||
|
/*
|
||||
|
// disable interrupts
|
||||
|
void cli() { noInterrupts(); } |
||||
|
|
||||
|
// enable interrupts
|
||||
|
void sei() { interrupts(); } |
||||
|
*/ |
||||
|
|
||||
|
void HAL_adc_init() { |
||||
|
analog_init(); |
||||
|
while (ADC1_GC & ADC_GC_CAL) ; |
||||
|
while (ADC2_GC & ADC_GC_CAL) ; |
||||
|
} |
||||
|
|
||||
|
void HAL_clear_reset_source() { |
||||
|
uint32_t reset_source = SRC_SRSR; |
||||
|
SRC_SRSR = reset_source; |
||||
|
} |
||||
|
|
||||
|
uint8_t HAL_get_reset_source() { |
||||
|
switch (SRC_SRSR & 0xFF) { |
||||
|
case 1: return RST_POWER_ON; break; |
||||
|
case 2: return RST_SOFTWARE; break; |
||||
|
case 4: return RST_EXTERNAL; break; |
||||
|
// case 8: return RST_BROWN_OUT; break;
|
||||
|
case 16: return RST_WATCHDOG; break; |
||||
|
case 64: return RST_JTAG; break; |
||||
|
// case 128: return RST_OVERTEMP; break;
|
||||
|
} |
||||
|
return 0; |
||||
|
} |
||||
|
|
||||
|
#define __bss_end _ebss |
||||
|
|
||||
|
extern "C" { |
||||
|
extern char __bss_end; |
||||
|
extern char __heap_start; |
||||
|
extern void* __brkval; |
||||
|
|
||||
|
// Doesn't work on Teensy 4.x
|
||||
|
uint32_t freeMemory() { |
||||
|
uint32_t free_memory; |
||||
|
if ((uint32_t)__brkval == 0) |
||||
|
free_memory = ((uint32_t)&free_memory) - ((uint32_t)&__bss_end); |
||||
|
else |
||||
|
free_memory = ((uint32_t)&free_memory) - ((uint32_t)__brkval); |
||||
|
return free_memory; |
||||
|
} |
||||
|
} |
||||
|
|
||||
|
void HAL_adc_start_conversion(const uint8_t adc_pin) { |
||||
|
const uint16_t pin = pin2sc1a[adc_pin]; |
||||
|
if (pin == 0xFF) { |
||||
|
HAL_adc_select = -1; // Digital only
|
||||
|
} |
||||
|
else if (pin & 0x80) { |
||||
|
HAL_adc_select = 1; |
||||
|
ADC2_HC0 = pin & 0x7F; |
||||
|
} |
||||
|
else { |
||||
|
HAL_adc_select = 0; |
||||
|
ADC1_HC0 = pin; |
||||
|
} |
||||
|
} |
||||
|
|
||||
|
uint16_t HAL_adc_get_result() { |
||||
|
switch (HAL_adc_select) { |
||||
|
case 0: |
||||
|
while (!(ADC1_HS & ADC_HS_COCO0)) ; // wait
|
||||
|
return ADC1_R0; |
||||
|
case 1: |
||||
|
while (!(ADC2_HS & ADC_HS_COCO0)) ; // wait
|
||||
|
return ADC2_R0; |
||||
|
} |
||||
|
return 0; |
||||
|
} |
||||
|
|
||||
|
bool is_output(uint8_t pin) { |
||||
|
const struct digital_pin_bitband_and_config_table_struct *p; |
||||
|
p = digital_pin_to_info_PGM + pin; |
||||
|
return (*(p->reg + 1) & p->mask); |
||||
|
} |
||||
|
|
||||
|
#endif // __IMXRT1062__
|
@ -0,0 +1,147 @@ |
|||||
|
/**
|
||||
|
* Marlin 3D Printer Firmware |
||||
|
* |
||||
|
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
|
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com |
||||
|
* Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com |
||||
|
* |
||||
|
* 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 <https://www.gnu.org/licenses/>.
|
||||
|
* |
||||
|
*/ |
||||
|
#pragma once |
||||
|
|
||||
|
/**
|
||||
|
* Description: HAL for Teensy 4.0 and Teensy 4.1 |
||||
|
*/ |
||||
|
|
||||
|
#define CPU_32_BIT |
||||
|
|
||||
|
#include "../shared/Marduino.h" |
||||
|
#include "../shared/math_32bit.h" |
||||
|
#include "../shared/HAL_SPI.h" |
||||
|
|
||||
|
#include "fastio.h" |
||||
|
#include "watchdog.h" |
||||
|
|
||||
|
#include <stdint.h> |
||||
|
#include <util/atomic.h> |
||||
|
|
||||
|
//#define ST7920_DELAY_1 DELAY_NS(600)
|
||||
|
//#define ST7920_DELAY_2 DELAY_NS(750)
|
||||
|
//#define ST7920_DELAY_3 DELAY_NS(750)
|
||||
|
|
||||
|
// ------------------------
|
||||
|
// Defines
|
||||
|
// ------------------------
|
||||
|
|
||||
|
#ifdef __IMXRT1062__ |
||||
|
#define IS_32BIT_TEENSY 1 |
||||
|
#define IS_TEENSY41 1 |
||||
|
#endif |
||||
|
|
||||
|
#define _MSERIAL(X) Serial##X |
||||
|
#define MSERIAL(X) _MSERIAL(X) |
||||
|
#define Serial0 Serial |
||||
|
|
||||
|
#if SERIAL_PORT == -1 |
||||
|
#define MYSERIAL0 SerialUSB |
||||
|
#elif WITHIN(SERIAL_PORT, 0, 8) |
||||
|
#define MYSERIAL0 MSERIAL(SERIAL_PORT) |
||||
|
#else |
||||
|
#error "The required SERIAL_PORT must be from -1 to 8. Please update your configuration." |
||||
|
#endif |
||||
|
|
||||
|
#ifdef SERIAL_PORT_2 |
||||
|
#if SERIAL_PORT_2 == -1 |
||||
|
#define MYSERIAL1 usbSerial |
||||
|
#elif WITHIN(SERIAL_PORT_2, 0, 8) |
||||
|
#define MYSERIAL1 MSERIAL(SERIAL_PORT_2) |
||||
|
#else |
||||
|
#error "SERIAL_PORT_2 must be from -1 to 8. Please update your configuration." |
||||
|
#endif |
||||
|
#endif |
||||
|
|
||||
|
#define HAL_SERVO_LIB libServo |
||||
|
|
||||
|
typedef int8_t pin_t; |
||||
|
|
||||
|
#ifndef analogInputToDigitalPin |
||||
|
#define analogInputToDigitalPin(p) ((p < 12u) ? (p) + 54u : -1) |
||||
|
#endif |
||||
|
|
||||
|
#define CRITICAL_SECTION_START() uint32_t primask = __get_primask(); __disable_irq() |
||||
|
#define CRITICAL_SECTION_END() if (!primask) __enable_irq() |
||||
|
#define ISRS_ENABLED() (!__get_primask()) |
||||
|
#define ENABLE_ISRS() __enable_irq() |
||||
|
#define DISABLE_ISRS() __disable_irq() |
||||
|
|
||||
|
#undef sq |
||||
|
#define sq(x) ((x)*(x)) |
||||
|
|
||||
|
#ifndef strncpy_P |
||||
|
#define strncpy_P(dest, src, num) strncpy((dest), (src), (num)) |
||||
|
#endif |
||||
|
|
||||
|
// Don't place string constants in PROGMEM
|
||||
|
#undef PSTR |
||||
|
#define PSTR(str) ({static const char *data = (str); &data[0];}) |
||||
|
|
||||
|
// Fix bug in pgm_read_ptr
|
||||
|
#undef pgm_read_ptr |
||||
|
#define pgm_read_ptr(addr) (*((void**)(addr))) |
||||
|
// Add type-checking to pgm_read_word
|
||||
|
#undef pgm_read_word |
||||
|
#define pgm_read_word(addr) (*((uint16_t*)(addr))) |
||||
|
|
||||
|
// Enable hooks into idle and setup for HAL
|
||||
|
#define HAL_IDLETASK 1 |
||||
|
FORCE_INLINE void HAL_idletask() {} |
||||
|
FORCE_INLINE void HAL_init() {} |
||||
|
|
||||
|
// Clear reset reason
|
||||
|
void HAL_clear_reset_source(); |
||||
|
|
||||
|
// Reset reason
|
||||
|
uint8_t HAL_get_reset_source(); |
||||
|
|
||||
|
FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); } |
||||
|
|
||||
|
#pragma GCC diagnostic push |
||||
|
#pragma GCC diagnostic ignored "-Wunused-function" |
||||
|
extern "C" { |
||||
|
uint32_t freeMemory(); |
||||
|
} |
||||
|
#pragma GCC diagnostic pop |
||||
|
|
||||
|
// ADC
|
||||
|
|
||||
|
void HAL_adc_init(); |
||||
|
|
||||
|
#define HAL_ADC_VREF 3.3 |
||||
|
#define HAL_ADC_RESOLUTION 10 |
||||
|
#define HAL_ADC_FILTERED // turn off ADC oversampling
|
||||
|
#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) |
||||
|
#define HAL_READ_ADC() HAL_adc_get_result() |
||||
|
#define HAL_ADC_READY() true |
||||
|
|
||||
|
#define HAL_ANALOG_SELECT(pin) |
||||
|
|
||||
|
void HAL_adc_start_conversion(const uint8_t adc_pin); |
||||
|
uint16_t HAL_adc_get_result(); |
||||
|
|
||||
|
#define GET_PIN_MAP_PIN(index) index |
||||
|
#define GET_PIN_MAP_INDEX(pin) pin |
||||
|
#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) |
||||
|
|
||||
|
bool is_output(uint8_t pin); |
@ -0,0 +1,138 @@ |
|||||
|
/**
|
||||
|
* Marlin 3D Printer Firmware |
||||
|
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
|
* |
||||
|
* Based on Sprinter and grbl. |
||||
|
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm |
||||
|
* |
||||
|
* 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 <https://www.gnu.org/licenses/>.
|
||||
|
* |
||||
|
*/ |
||||
|
#ifdef __IMXRT1062__ |
||||
|
|
||||
|
#include "HAL.h" |
||||
|
#include <SPI.h> |
||||
|
#include <pins_arduino.h> |
||||
|
#include "spi_pins.h" |
||||
|
#include "../../core/macros.h" |
||||
|
|
||||
|
static SPISettings spiConfig; |
||||
|
|
||||
|
// ------------------------
|
||||
|
// Public functions
|
||||
|
// ------------------------
|
||||
|
|
||||
|
#if ENABLED(SOFTWARE_SPI) |
||||
|
// ------------------------
|
||||
|
// Software SPI
|
||||
|
// ------------------------
|
||||
|
#error "Software SPI not supported for Teensy 4. Use Hardware SPI." |
||||
|
#else |
||||
|
|
||||
|
// ------------------------
|
||||
|
// Hardware SPI
|
||||
|
// ------------------------
|
||||
|
|
||||
|
void spiBegin() { |
||||
|
#ifndef SS_PIN |
||||
|
#error "SS_PIN is not defined!" |
||||
|
#endif |
||||
|
|
||||
|
OUT_WRITE(SS_PIN, HIGH); |
||||
|
|
||||
|
//SET_OUTPUT(SCK_PIN);
|
||||
|
//SET_INPUT(MISO_PIN);
|
||||
|
//SET_OUTPUT(MOSI_PIN);
|
||||
|
|
||||
|
#if 0 && DISABLED(SOFTWARE_SPI)
|
||||
|
// set SS high - may be chip select for another SPI device
|
||||
|
#if SET_SPI_SS_HIGH |
||||
|
WRITE(SS_PIN, HIGH); |
||||
|
#endif |
||||
|
// set a default rate
|
||||
|
spiInit(SPI_HALF_SPEED); // 1
|
||||
|
#endif |
||||
|
} |
||||
|
|
||||
|
void spiInit(uint8_t spiRate) { |
||||
|
// Use Marlin data-rates
|
||||
|
uint32_t clock; |
||||
|
switch (spiRate) { |
||||
|
case SPI_FULL_SPEED: clock = 10000000; break; |
||||
|
case SPI_HALF_SPEED: clock = 5000000; break; |
||||
|
case SPI_QUARTER_SPEED: clock = 2500000; break; |
||||
|
case SPI_EIGHTH_SPEED: clock = 1250000; break; |
||||
|
case SPI_SPEED_5: clock = 625000; break; |
||||
|
case SPI_SPEED_6: clock = 312500; break; |
||||
|
default: |
||||
|
clock = 4000000; // Default from the SPI libarary
|
||||
|
} |
||||
|
spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0); |
||||
|
SPI.begin(); |
||||
|
} |
||||
|
|
||||
|
uint8_t spiRec() { |
||||
|
SPI.beginTransaction(spiConfig); |
||||
|
uint8_t returnByte = SPI.transfer(0xFF); |
||||
|
SPI.endTransaction(); |
||||
|
return returnByte; |
||||
|
//SPDR = 0xFF;
|
||||
|
//while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
|
||||
|
//return SPDR;
|
||||
|
} |
||||
|
|
||||
|
void spiRead(uint8_t* buf, uint16_t nbyte) { |
||||
|
SPI.beginTransaction(spiConfig); |
||||
|
SPI.transfer(buf, nbyte); |
||||
|
SPI.endTransaction(); |
||||
|
//if (nbyte-- == 0) return;
|
||||
|
// SPDR = 0xFF;
|
||||
|
//for (uint16_t i = 0; i < nbyte; i++) {
|
||||
|
// while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
|
||||
|
// buf[i] = SPDR;
|
||||
|
// SPDR = 0xFF;
|
||||
|
//}
|
||||
|
//while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
|
||||
|
//buf[nbyte] = SPDR;
|
||||
|
} |
||||
|
|
||||
|
void spiSend(uint8_t b) { |
||||
|
SPI.beginTransaction(spiConfig); |
||||
|
SPI.transfer(b); |
||||
|
SPI.endTransaction(); |
||||
|
//SPDR = b;
|
||||
|
//while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
|
||||
|
} |
||||
|
|
||||
|
void spiSendBlock(uint8_t token, const uint8_t* buf) { |
||||
|
SPI.beginTransaction(spiConfig); |
||||
|
SPDR = token; |
||||
|
for (uint16_t i = 0; i < 512; i += 2) { |
||||
|
while (!TEST(SPSR, SPIF)) { /* nada */ }; |
||||
|
SPDR = buf[i]; |
||||
|
while (!TEST(SPSR, SPIF)) { /* nada */ }; |
||||
|
SPDR = buf[i + 1]; |
||||
|
} |
||||
|
while (!TEST(SPSR, SPIF)) { /* nada */ }; |
||||
|
SPI.endTransaction(); |
||||
|
} |
||||
|
|
||||
|
// Begin SPI transaction, set clock, bit order, data mode
|
||||
|
void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) { |
||||
|
spiConfig = SPISettings(spiClock, bitOrder, dataMode); |
||||
|
SPI.beginTransaction(spiConfig); |
||||
|
} |
||||
|
|
||||
|
#endif // SOFTWARE_SPI
|
||||
|
#endif // __IMXRT1062__
|
@ -0,0 +1,57 @@ |
|||||
|
/**
|
||||
|
* Marlin 3D Printer Firmware |
||||
|
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
|
* |
||||
|
* Based on Sprinter and grbl. |
||||
|
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm |
||||
|
* |
||||
|
* 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 <https://www.gnu.org/licenses/>.
|
||||
|
* |
||||
|
*/ |
||||
|
#ifdef __IMXRT1062__ |
||||
|
|
||||
|
#include "../../inc/MarlinConfig.h" |
||||
|
|
||||
|
#if HAS_SERVOS |
||||
|
|
||||
|
#include "Servo.h" |
||||
|
|
||||
|
int8_t libServo::attach(const int inPin) { |
||||
|
if (inPin > 0) servoPin = inPin; |
||||
|
return super::attach(servoPin); |
||||
|
} |
||||
|
|
||||
|
int8_t libServo::attach(const int inPin, const int inMin, const int inMax) { |
||||
|
if (inPin > 0) servoPin = inPin; |
||||
|
return super::attach(servoPin, inMin, inMax); |
||||
|
} |
||||
|
|
||||
|
void libServo::move(const int value) { |
||||
|
constexpr uint16_t servo_delay[] = SERVO_DELAY; |
||||
|
static_assert(COUNT(servo_delay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long."); |
||||
|
if (attach(0) >= 0) { |
||||
|
write(value); |
||||
|
safe_delay(servo_delay[servoIndex]); |
||||
|
TERN_(DEACTIVATE_SERVOS_AFTER_MOVE, detach()); |
||||
|
} |
||||
|
} |
||||
|
|
||||
|
void libServo::detach() { |
||||
|
// PWMServo library does not have detach() function
|
||||
|
//super::detach();
|
||||
|
} |
||||
|
|
||||
|
#endif // HAS_SERVOS
|
||||
|
|
||||
|
#endif // __IMXRT1062__
|
@ -0,0 +1,39 @@ |
|||||
|
/**
|
||||
|
* Marlin 3D Printer Firmware |
||||
|
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
|
* |
||||
|
* Based on Sprinter and grbl. |
||||
|
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm |
||||
|
* |
||||
|
* 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 <https://www.gnu.org/licenses/>.
|
||||
|
* |
||||
|
*/ |
||||
|
#pragma once |
||||
|
|
||||
|
#include <PWMServo.h> |
||||
|
|
||||
|
// Inherit and expand on core Servo library
|
||||
|
class libServo : public PWMServo { |
||||
|
public: |
||||
|
int8_t attach(const int pin); |
||||
|
int8_t attach(const int pin, const int min, const int max); |
||||
|
void move(const int value); |
||||
|
void detach(void); |
||||
|
private: |
||||
|
typedef PWMServo super; |
||||
|
uint8_t servoPin; |
||||
|
uint16_t min_ticks; |
||||
|
uint16_t max_ticks; |
||||
|
uint8_t servoIndex; // Index into the channel data for this servo
|
||||
|
}; |
@ -0,0 +1,77 @@ |
|||||
|
/**
|
||||
|
* Marlin 3D Printer Firmware |
||||
|
* |
||||
|
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
|
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com |
||||
|
* Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com |
||||
|
* Copyright (c) 2016 Victor Perez victor_pv@hotmail.com |
||||
|
* |
||||
|
* 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 <https://www.gnu.org/licenses/>.
|
||||
|
* |
||||
|
*/ |
||||
|
#ifdef __IMXRT1062__ |
||||
|
|
||||
|
#include "../../inc/MarlinConfig.h" |
||||
|
|
||||
|
#if USE_WIRED_EEPROM |
||||
|
|
||||
|
/**
|
||||
|
* PersistentStore for Arduino-style EEPROM interface |
||||
|
* with implementations supplied by the framework. |
||||
|
*/ |
||||
|
|
||||
|
#include "../shared/eeprom_api.h" |
||||
|
#include <avr/eeprom.h> |
||||
|
|
||||
|
#ifndef MARLIN_EEPROM_SIZE |
||||
|
#define MARLIN_EEPROM_SIZE size_t(E2END + 1) |
||||
|
#endif |
||||
|
size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } |
||||
|
|
||||
|
bool PersistentStore::access_start() { return true; } |
||||
|
bool PersistentStore::access_finish() { return true; } |
||||
|
|
||||
|
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { |
||||
|
while (size--) { |
||||
|
uint8_t * const p = (uint8_t * const)pos; |
||||
|
uint8_t v = *value; |
||||
|
// EEPROM has only ~100,000 write cycles,
|
||||
|
// so only write bytes that have changed!
|
||||
|
if (v != eeprom_read_byte(p)) { |
||||
|
eeprom_write_byte(p, v); |
||||
|
if (eeprom_read_byte(p) != v) { |
||||
|
SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE); |
||||
|
return true; |
||||
|
} |
||||
|
} |
||||
|
crc16(crc, &v, 1); |
||||
|
pos++; |
||||
|
value++; |
||||
|
} |
||||
|
return false; |
||||
|
} |
||||
|
|
||||
|
bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) { |
||||
|
do { |
||||
|
uint8_t c = eeprom_read_byte((uint8_t*)pos); |
||||
|
if (writing) *value = c; |
||||
|
crc16(crc, &c, 1); |
||||
|
pos++; |
||||
|
value++; |
||||
|
} while (--size); |
||||
|
return false; |
||||
|
} |
||||
|
|
||||
|
#endif // USE_WIRED_EEPROM
|
||||
|
#endif // __IMXRT1062__
|
@ -0,0 +1,66 @@ |
|||||
|
/**
|
||||
|
* Marlin 3D Printer Firmware |
||||
|
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
|
* |
||||
|
* Based on Sprinter and grbl. |
||||
|
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm |
||||
|
* |
||||
|
* 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 <https://www.gnu.org/licenses/>.
|
||||
|
* |
||||
|
*/ |
||||
|
#pragma once |
||||
|
|
||||
|
/**
|
||||
|
* Endstop Interrupts |
||||
|
* |
||||
|
* Without endstop interrupts the endstop pins must be polled continually in |
||||
|
* the temperature-ISR via endstops.update(), most of the time finding no change. |
||||
|
* With this feature endstops.update() is called only when we know that at |
||||
|
* least one endstop has changed state, saving valuable CPU cycles. |
||||
|
* |
||||
|
* This feature only works when all used endstop pins can generate an 'external interrupt'. |
||||
|
* |
||||
|
* Test whether pins issue interrupts on your board by flashing 'pin_interrupt_test.ino'. |
||||
|
* (Located in Marlin/buildroot/share/pin_interrupt_test/pin_interrupt_test.ino) |
||||
|
*/ |
||||
|
|
||||
|
#include "../../module/endstops.h" |
||||
|
|
||||
|
// One ISR for all EXT-Interrupts
|
||||
|
void endstop_ISR() { endstops.update(); } |
||||
|
|
||||
|
/**
|
||||
|
* Endstop interrupts for Due based targets. |
||||
|
* On Due, all pins support external interrupt capability. |
||||
|
*/ |
||||
|
void setup_endstop_interrupts() { |
||||
|
#define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE) |
||||
|
TERN_(HAS_X_MAX, _ATTACH(X_MAX_PIN)); |
||||
|
TERN_(HAS_X_MIN, _ATTACH(X_MIN_PIN)); |
||||
|
TERN_(HAS_Y_MAX, _ATTACH(Y_MAX_PIN)); |
||||
|
TERN_(HAS_Y_MIN, _ATTACH(Y_MIN_PIN)); |
||||
|
TERN_(HAS_Z_MAX, _ATTACH(Z_MAX_PIN)); |
||||
|
TERN_(HAS_Z_MIN, _ATTACH(Z_MIN_PIN)); |
||||
|
TERN_(HAS_X2_MAX, _ATTACH(X2_MAX_PIN)); |
||||
|
TERN_(HAS_X2_MIN, _ATTACH(X2_MIN_PIN)); |
||||
|
TERN_(HAS_Y2_MAX, _ATTACH(Y2_MAX_PIN)); |
||||
|
TERN_(HAS_Y2_MIN, _ATTACH(Y2_MIN_PIN)); |
||||
|
TERN_(HAS_Z2_MAX, _ATTACH(Z2_MAX_PIN)); |
||||
|
TERN_(HAS_Z2_MIN, _ATTACH(Z2_MIN_PIN)); |
||||
|
TERN_(HAS_Z3_MAX, _ATTACH(Z3_MAX_PIN)); |
||||
|
TERN_(HAS_Z3_MIN, _ATTACH(Z3_MIN_PIN)); |
||||
|
TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); |
||||
|
TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN)); |
||||
|
TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN)); |
||||
|
} |
@ -0,0 +1,58 @@ |
|||||
|
/**
|
||||
|
* Marlin 3D Printer Firmware |
||||
|
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
|
* |
||||
|
* Based on Sprinter and grbl. |
||||
|
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm |
||||
|
* Copyright (c) 2017 Victor Perez |
||||
|
* |
||||
|
* 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 <https://www.gnu.org/licenses/>.
|
||||
|
* |
||||
|
*/ |
||||
|
#pragma once |
||||
|
|
||||
|
/**
|
||||
|
* Fast I/O interfaces for Teensy 4 |
||||
|
* These use GPIO functions instead of Direct Port Manipulation, as on AVR. |
||||
|
*/ |
||||
|
|
||||
|
#ifndef PWM |
||||
|
#define PWM OUTPUT |
||||
|
#endif |
||||
|
|
||||
|
#define READ(IO) digitalRead(IO) |
||||
|
#define WRITE(IO,V) digitalWrite(IO,V) |
||||
|
|
||||
|
#define _GET_MODE(IO) !is_output(IO) |
||||
|
#define _SET_MODE(IO,M) pinMode(IO, M) |
||||
|
#define _SET_OUTPUT(IO) pinMode(IO, OUTPUT) /*!< Output Push Pull Mode & GPIO_NOPULL */ |
||||
|
|
||||
|
#define OUT_WRITE(IO,V) do{ _SET_OUTPUT(IO); WRITE(IO,V); }while(0) |
||||
|
|
||||
|
#define SET_INPUT(IO) _SET_MODE(IO, INPUT) /*!< Input Floating Mode */ |
||||
|
#define SET_INPUT_PULLUP(IO) _SET_MODE(IO, INPUT_PULLUP) /*!< Input with Pull-up activation */ |
||||
|
#define SET_INPUT_PULLDOWN(IO) _SET_MODE(IO, INPUT_PULLDOWN) /*!< Input with Pull-down activation */ |
||||
|
#define SET_OUTPUT(IO) OUT_WRITE(IO, LOW) |
||||
|
#define SET_PWM(IO) _SET_MODE(IO, PWM) |
||||
|
|
||||
|
#define TOGGLE(IO) OUT_WRITE(IO, !READ(IO)) |
||||
|
|
||||
|
#define IS_INPUT(IO) !is_output(IO) |
||||
|
#define IS_OUTPUT(IO) is_output(IO) |
||||
|
|
||||
|
#define PWM_PIN(P) digitalPinHasPWM(P) |
||||
|
|
||||
|
// digitalRead/Write wrappers
|
||||
|
#define extDigitalRead(IO) digitalRead(IO) |
||||
|
#define extDigitalWrite(IO,V) digitalWrite(IO,V) |
@ -0,0 +1,26 @@ |
|||||
|
/**
|
||||
|
* Marlin 3D Printer Firmware |
||||
|
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
|
* |
||||
|
* Based on Sprinter and grbl. |
||||
|
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm |
||||
|
* |
||||
|
* 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 <https://www.gnu.org/licenses/>.
|
||||
|
* |
||||
|
*/ |
||||
|
#pragma once |
||||
|
|
||||
|
#if HAS_SPI_TFT || HAS_FSMC_TFT |
||||
|
#error "Sorry! TFT displays are not available for HAL/TEENSY40_41." |
||||
|
#endif |
@ -0,0 +1,22 @@ |
|||||
|
/**
|
||||
|
* Marlin 3D Printer Firmware |
||||
|
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
|
* |
||||
|
* Based on Sprinter and grbl. |
||||
|
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm |
||||
|
* |
||||
|
* 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 <https://www.gnu.org/licenses/>.
|
||||
|
* |
||||
|
*/ |
||||
|
#pragma once |
@ -0,0 +1,26 @@ |
|||||
|
/**
|
||||
|
* Marlin 3D Printer Firmware |
||||
|
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
|
* |
||||
|
* Based on Sprinter and grbl. |
||||
|
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm |
||||
|
* |
||||
|
* 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 <https://www.gnu.org/licenses/>.
|
||||
|
* |
||||
|
*/ |
||||
|
#pragma once |
||||
|
|
||||
|
#if USE_FALLBACK_EEPROM |
||||
|
#define USE_WIRED_EEPROM 1 |
||||
|
#endif |
@ -0,0 +1,38 @@ |
|||||
|
/**
|
||||
|
* Marlin 3D Printer Firmware |
||||
|
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
|
* |
||||
|
* Based on Sprinter and grbl. |
||||
|
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm |
||||
|
* |
||||
|
* 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 <https://www.gnu.org/licenses/>.
|
||||
|
* |
||||
|
*/ |
||||
|
#pragma once |
||||
|
|
||||
|
/**
|
||||
|
* Test TEENSY41 specific configuration values for errors at compile-time. |
||||
|
*/ |
||||
|
|
||||
|
#if ENABLED(EMERGENCY_PARSER) |
||||
|
#error "EMERGENCY_PARSER is not yet implemented for Teensy 4.0/4.1. Disable EMERGENCY_PARSER to continue." |
||||
|
#endif |
||||
|
|
||||
|
#if ENABLED(FAST_PWM_FAN) || SPINDLE_LASER_FREQUENCY |
||||
|
#error "Features requiring Hardware PWM (FAST_PWM_FAN, SPINDLE_LASER_FREQUENCY) are not yet supported on Teensy 4.0/4.1." |
||||
|
#endif |
||||
|
|
||||
|
#if HAS_TMC_SW_SERIAL |
||||
|
#error "TMC220x Software Serial is not supported on this platform." |
||||
|
#endif |
@ -0,0 +1,146 @@ |
|||||
|
/**
|
||||
|
* Marlin 3D Printer Firmware |
||||
|
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
|
* |
||||
|
* 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 <https://www.gnu.org/licenses/>.
|
||||
|
* |
||||
|
*/ |
||||
|
#pragma once |
||||
|
|
||||
|
#warning "PINS_DEBUGGING is not fully supported for Teensy 4.0 / 4.1 so 'M43' may cause hangs." |
||||
|
|
||||
|
#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS |
||||
|
|
||||
|
#define digitalRead_mod(p) extDigitalRead(p) // AVR digitalRead disabled PWM before it read the pin
|
||||
|
#define PRINT_PORT(p) |
||||
|
#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) |
||||
|
#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%02d"), p); SERIAL_ECHO(buffer); }while(0) |
||||
|
#define GET_ARRAY_PIN(p) pin_array[p].pin |
||||
|
#define GET_ARRAY_IS_DIGITAL(p) pin_array[p].is_digital |
||||
|
#define VALID_PIN(pin) (pin >= 0 && pin < (int8_t)NUMBER_PINS_TOTAL ? 1 : 0) |
||||
|
#define DIGITAL_PIN_TO_ANALOG_PIN(p) int(p - analogInputToDigitalPin(0)) |
||||
|
#define IS_ANALOG(P) ((P) >= analogInputToDigitalPin(0) && (P) <= analogInputToDigitalPin(13)) || ((P) >= analogInputToDigitalPin(14) && (P) <= analogInputToDigitalPin(17)) |
||||
|
#define pwm_status(pin) HAL_pwm_status(pin) |
||||
|
#define GET_PINMODE(PIN) (VALID_PIN(pin) && IS_OUTPUT(pin)) |
||||
|
#define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin
|
||||
|
|
||||
|
struct pwm_pin_info_struct { |
||||
|
uint8_t type; // 0=no pwm, 1=flexpwm, 2=quad
|
||||
|
uint8_t module; // 0-3, 0-3
|
||||
|
uint8_t channel; // 0=X, 1=A, 2=B
|
||||
|
uint8_t muxval; //
|
||||
|
}; |
||||
|
|
||||
|
#define M(a, b) ((((a) - 1) << 4) | (b)) |
||||
|
|
||||
|
const struct pwm_pin_info_struct pwm_pin_info[] = { |
||||
|
{1, M(1, 1), 0, 4}, // FlexPWM1_1_X 0 // AD_B0_03
|
||||
|
{1, M(1, 0), 0, 4}, // FlexPWM1_0_X 1 // AD_B0_02
|
||||
|
{1, M(4, 2), 1, 1}, // FlexPWM4_2_A 2 // EMC_04
|
||||
|
{1, M(4, 2), 2, 1}, // FlexPWM4_2_B 3 // EMC_05
|
||||
|
{1, M(2, 0), 1, 1}, // FlexPWM2_0_A 4 // EMC_06
|
||||
|
{1, M(2, 1), 1, 1}, // FlexPWM2_1_A 5 // EMC_08
|
||||
|
{1, M(2, 2), 1, 2}, // FlexPWM2_2_A 6 // B0_10
|
||||
|
{1, M(1, 3), 2, 6}, // FlexPWM1_3_B 7 // B1_01
|
||||
|
{1, M(1, 3), 1, 6}, // FlexPWM1_3_A 8 // B1_00
|
||||
|
{1, M(2, 2), 2, 2}, // FlexPWM2_2_B 9 // B0_11
|
||||
|
{2, M(1, 0), 0, 1}, // QuadTimer1_0 10 // B0_00
|
||||
|
{2, M(1, 2), 0, 1}, // QuadTimer1_2 11 // B0_02
|
||||
|
{2, M(1, 1), 0, 1}, // QuadTimer1_1 12 // B0_01
|
||||
|
{2, M(2, 0), 0, 1}, // QuadTimer2_0 13 // B0_03
|
||||
|
{2, M(3, 2), 0, 1}, // QuadTimer3_2 14 // AD_B1_02
|
||||
|
{2, M(3, 3), 0, 1}, // QuadTimer3_3 15 // AD_B1_03
|
||||
|
{0, M(1, 0), 0, 0}, |
||||
|
{0, M(1, 0), 0, 0}, |
||||
|
{2, M(3, 1), 0, 1}, // QuadTimer3_1 18 // AD_B1_01
|
||||
|
{2, M(3, 0), 0, 1}, // QuadTimer3_0 19 // AD_B1_00
|
||||
|
{0, M(1, 0), 0, 0}, |
||||
|
{0, M(1, 0), 0, 0}, |
||||
|
{1, M(4, 0), 1, 1}, // FlexPWM4_0_A 22 // AD_B1_08
|
||||
|
{1, M(4, 1), 1, 1}, // FlexPWM4_1_A 23 // AD_B1_09
|
||||
|
{1, M(1, 2), 0, 4}, // FlexPWM1_2_X 24 // AD_B0_12
|
||||
|
{1, M(1, 3), 0, 4}, // FlexPWM1_3_X 25 // AD_B0_13
|
||||
|
{0, M(1, 0), 0, 0}, |
||||
|
{0, M(1, 0), 0, 0}, |
||||
|
{1, M(3, 1), 2, 1}, // FlexPWM3_1_B 28 // EMC_32
|
||||
|
{1, M(3, 1), 1, 1}, // FlexPWM3_1_A 29 // EMC_31
|
||||
|
{0, M(1, 0), 0, 0}, |
||||
|
{0, M(1, 0), 0, 0}, |
||||
|
{0, M(1, 0), 0, 0}, |
||||
|
{1, M(2, 0), 2, 1}, // FlexPWM2_0_B 33 // EMC_07
|
||||
|
#ifdef ARDUINO_TEENSY40 |
||||
|
{1, M(1, 1), 2, 1}, // FlexPWM1_1_B 34 // SD_B0_03
|
||||
|
{1, M(1, 1), 1, 1}, // FlexPWM1_1_A 35 // SD_B0_02
|
||||
|
{1, M(1, 0), 2, 1}, // FlexPWM1_0_B 36 // SD_B0_01
|
||||
|
{1, M(1, 0), 1, 1}, // FlexPWM1_0_A 37 // SD_B0_00
|
||||
|
{1, M(1, 2), 2, 1}, // FlexPWM1_2_B 38 // SD_B0_05
|
||||
|
{1, M(1, 2), 1, 1}, // FlexPWM1_2_A 39 // SD_B0_04
|
||||
|
#endif |
||||
|
#ifdef ARDUINO_TEENSY41 |
||||
|
{0, M(1, 0), 0, 0}, |
||||
|
{0, M(1, 0), 0, 0}, |
||||
|
{1, M(2, 3), 1, 6}, // FlexPWM2_3_A 36 // B1_00
|
||||
|
{1, M(2, 3), 2, 6}, // FlexPWM2_3_B 37 // B1_01
|
||||
|
{0, M(1, 0), 0, 0}, |
||||
|
{0, M(1, 0), 0, 0}, |
||||
|
{0, M(1, 0), 0, 0}, |
||||
|
{0, M(1, 0), 0, 0}, |
||||
|
{1, M(1, 1), 2, 1}, // FlexPWM1_1_B 42 // SD_B0_03
|
||||
|
{1, M(1, 1), 1, 1}, // FlexPWM1_1_A 43 // SD_B0_02
|
||||
|
{1, M(1, 0), 2, 1}, // FlexPWM1_0_B 44 // SD_B0_01
|
||||
|
{1, M(1, 0), 1, 1}, // FlexPWM1_0_A 45 // SD_B0_00
|
||||
|
{1, M(1, 2), 2, 1}, // FlexPWM1_2_B 46 // SD_B0_05
|
||||
|
{1, M(1, 2), 1, 1}, // FlexPWM1_2_A 47 // SD_B0_04
|
||||
|
{0, M(1, 0), 0, 0}, // duplicate FlexPWM1_0_B
|
||||
|
{0, M(1, 0), 0, 0}, // duplicate FlexPWM1_2_A
|
||||
|
{0, M(1, 0), 0, 0}, // duplicate FlexPWM1_2_B
|
||||
|
{1, M(3, 3), 2, 1}, // FlexPWM3_3_B 51 // EMC_22
|
||||
|
{0, M(1, 0), 0, 0}, // duplicate FlexPWM1_1_B
|
||||
|
{0, M(1, 0), 0, 0}, // duplicate FlexPWM1_1_A
|
||||
|
{1, M(3, 0), 1, 1}, // FlexPWM3_0_A 53 // EMC_29
|
||||
|
#endif |
||||
|
}; |
||||
|
|
||||
|
void HAL_print_analog_pin(char buffer[], int8_t pin) { |
||||
|
if (pin <= 23) sprintf_P(buffer, PSTR("(A%2d) "), int(pin - 14)); |
||||
|
else if (pin <= 41) sprintf_P(buffer, PSTR("(A%2d) "), int(pin - 24)); |
||||
|
} |
||||
|
|
||||
|
void HAL_analog_pin_state(char buffer[], int8_t pin) { |
||||
|
if (pin <= 23) sprintf_P(buffer, PSTR("Analog in =% 5d"), analogRead(pin - 14)); |
||||
|
else if (pin <= 41) sprintf_P(buffer, PSTR("Analog in =% 5d"), analogRead(pin - 24)); |
||||
|
} |
||||
|
|
||||
|
#define PWM_PRINT(V) do{ sprintf_P(buffer, PSTR("PWM: %4d"), V); SERIAL_ECHO(buffer); }while(0) |
||||
|
|
||||
|
/**
|
||||
|
* Print a pin's PWM status. |
||||
|
* Return true if it's currently a PWM pin. |
||||
|
*/ |
||||
|
bool HAL_pwm_status(int8_t pin) { |
||||
|
char buffer[20]; // for the sprintf statements
|
||||
|
const struct pwm_pin_info_struct *info; |
||||
|
|
||||
|
if (pin >= CORE_NUM_DIGITAL) return 0; |
||||
|
info = pwm_pin_info + pin; |
||||
|
|
||||
|
if (info->type == 0) return 0; |
||||
|
|
||||
|
/* TODO decode pwm value from timers */ |
||||
|
// for now just indicate if output is set as pwm
|
||||
|
PWM_PRINT(*(portConfigRegister(pin)) == info->muxval); |
||||
|
return (*(portConfigRegister(pin)) == info->muxval); |
||||
|
} |
||||
|
|
||||
|
static void pwm_details(uint8_t pin) { /* TODO */ } |
@ -0,0 +1,27 @@ |
|||||
|
/**
|
||||
|
* Marlin 3D Printer Firmware |
||||
|
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
|
* |
||||
|
* Based on Sprinter and grbl. |
||||
|
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm |
||||
|
* |
||||
|
* 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 <https://www.gnu.org/licenses/>.
|
||||
|
* |
||||
|
*/ |
||||
|
#pragma once |
||||
|
|
||||
|
#define SCK_PIN 13 |
||||
|
#define MISO_PIN 12 |
||||
|
#define MOSI_PIN 11 |
||||
|
#define SS_PIN 20 // SDSS // A.28, A.29, B.21, C.26, C.29
|
@ -0,0 +1,114 @@ |
|||||
|
/**
|
||||
|
* Marlin 3D Printer Firmware |
||||
|
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
|
* |
||||
|
* Based on Sprinter and grbl. |
||||
|
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm |
||||
|
* |
||||
|
* 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 <https://www.gnu.org/licenses/>.
|
||||
|
* |
||||
|
*/ |
||||
|
|
||||
|
/**
|
||||
|
* Teensy4.0/4.1 (__IMXRT1062__) |
||||
|
*/ |
||||
|
|
||||
|
#ifdef __IMXRT1062__ |
||||
|
|
||||
|
#include "../../inc/MarlinConfig.h" |
||||
|
|
||||
|
void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { |
||||
|
switch (timer_num) { |
||||
|
case 0: |
||||
|
CCM_CSCMR1 &= ~CCM_CSCMR1_PERCLK_CLK_SEL; // turn off 24mhz mode
|
||||
|
CCM_CCGR1 |= CCM_CCGR1_GPT1_BUS(CCM_CCGR_ON); |
||||
|
|
||||
|
GPT1_CR = 0; // disable timer
|
||||
|
GPT1_SR = 0x3F; // clear all prior status
|
||||
|
GPT1_PR = GPT1_TIMER_PRESCALE - 1; |
||||
|
GPT1_CR |= GPT_CR_CLKSRC(1); //clock selection #1 (peripheral clock = 150 MHz)
|
||||
|
GPT1_CR |= GPT_CR_ENMOD; //reset count to zero before enabling
|
||||
|
GPT1_CR |= GPT_CR_OM1(1); // toggle mode
|
||||
|
GPT1_OCR1 = (GPT1_TIMER_RATE / frequency) -1; // Initial compare value
|
||||
|
GPT1_IR = GPT_IR_OF1IE; // Compare3 value
|
||||
|
GPT1_CR |= GPT_CR_EN; //enable GPT2 counting at 150 MHz
|
||||
|
|
||||
|
OUT_WRITE(15, HIGH); |
||||
|
attachInterruptVector(IRQ_GPT1, &stepTC_Handler); |
||||
|
NVIC_SET_PRIORITY(IRQ_GPT1, 16); |
||||
|
break; |
||||
|
case 1: |
||||
|
CCM_CSCMR1 &= ~CCM_CSCMR1_PERCLK_CLK_SEL; // turn off 24mhz mode
|
||||
|
CCM_CCGR0 |= CCM_CCGR0_GPT2_BUS(CCM_CCGR_ON); |
||||
|
|
||||
|
GPT2_CR = 0; // disable timer
|
||||
|
GPT2_SR = 0x3F; // clear all prior status
|
||||
|
GPT2_PR = GPT2_TIMER_PRESCALE - 1; |
||||
|
GPT2_CR |= GPT_CR_CLKSRC(1); //clock selection #1 (peripheral clock = 150 MHz)
|
||||
|
GPT2_CR |= GPT_CR_ENMOD; //reset count to zero before enabling
|
||||
|
GPT2_CR |= GPT_CR_OM1(1); // toggle mode
|
||||
|
GPT2_OCR1 = (GPT2_TIMER_RATE / frequency) -1; // Initial compare value
|
||||
|
GPT2_IR = GPT_IR_OF1IE; // Compare3 value
|
||||
|
GPT2_CR |= GPT_CR_EN; //enable GPT2 counting at 150 MHz
|
||||
|
|
||||
|
OUT_WRITE(14, HIGH); |
||||
|
attachInterruptVector(IRQ_GPT2, &tempTC_Handler); |
||||
|
NVIC_SET_PRIORITY(IRQ_GPT2, 32); |
||||
|
break; |
||||
|
} |
||||
|
} |
||||
|
|
||||
|
void HAL_timer_enable_interrupt(const uint8_t timer_num) { |
||||
|
switch (timer_num) { |
||||
|
case 0: |
||||
|
NVIC_ENABLE_IRQ(IRQ_GPT1); |
||||
|
break; |
||||
|
case 1: |
||||
|
NVIC_ENABLE_IRQ(IRQ_GPT2); |
||||
|
break; |
||||
|
} |
||||
|
} |
||||
|
|
||||
|
void HAL_timer_disable_interrupt(const uint8_t timer_num) { |
||||
|
switch (timer_num) { |
||||
|
case 0: NVIC_DISABLE_IRQ(IRQ_GPT1); break; |
||||
|
case 1: NVIC_DISABLE_IRQ(IRQ_GPT2); break; |
||||
|
} |
||||
|
|
||||
|
// We NEED memory barriers to ensure Interrupts are actually disabled!
|
||||
|
// ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the )
|
||||
|
asm volatile("dsb"); |
||||
|
} |
||||
|
|
||||
|
bool HAL_timer_interrupt_enabled(const uint8_t timer_num) { |
||||
|
switch (timer_num) { |
||||
|
case 0: return (NVIC_IS_ENABLED(IRQ_GPT1)); |
||||
|
case 1: return (NVIC_IS_ENABLED(IRQ_GPT2)); |
||||
|
} |
||||
|
return false; |
||||
|
} |
||||
|
|
||||
|
void HAL_timer_isr_prologue(const uint8_t timer_num) { |
||||
|
switch (timer_num) { |
||||
|
case 0: |
||||
|
GPT1_SR = GPT_IR_OF1IE; // clear OF3 bit
|
||||
|
break; |
||||
|
case 1: |
||||
|
GPT2_SR = GPT_IR_OF1IE; // clear OF3 bit
|
||||
|
break; |
||||
|
} |
||||
|
asm volatile("dsb"); |
||||
|
} |
||||
|
|
||||
|
#endif // __IMXRT1062__
|
@ -0,0 +1,120 @@ |
|||||
|
/**
|
||||
|
* Marlin 3D Printer Firmware |
||||
|
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
|
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com |
||||
|
* Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com |
||||
|
* |
||||
|
* 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 <https://www.gnu.org/licenses/>.
|
||||
|
* |
||||
|
*/ |
||||
|
#pragma once |
||||
|
|
||||
|
/**
|
||||
|
* Description: HAL for |
||||
|
* Teensy4.0/4.1 (__IMXRT1062__) |
||||
|
*/ |
||||
|
|
||||
|
#include <stdint.h> |
||||
|
|
||||
|
// ------------------------
|
||||
|
// Defines
|
||||
|
// ------------------------
|
||||
|
|
||||
|
#define FORCE_INLINE __attribute__((always_inline)) inline |
||||
|
|
||||
|
typedef uint32_t hal_timer_t; |
||||
|
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFE |
||||
|
|
||||
|
#define GPT_TIMER_RATE F_BUS_ACTUAL // 150MHz
|
||||
|
|
||||
|
#define GPT1_TIMER_PRESCALE 2 |
||||
|
#define GPT2_TIMER_PRESCALE 10 |
||||
|
|
||||
|
#define GPT1_TIMER_RATE (GPT_TIMER_RATE / GPT1_TIMER_PRESCALE) // 75MHz
|
||||
|
#define GPT2_TIMER_RATE (GPT_TIMER_RATE / GPT2_TIMER_PRESCALE) // 15MHz
|
||||
|
|
||||
|
#ifndef STEP_TIMER_NUM |
||||
|
#define STEP_TIMER_NUM 0 // Timer Index for Stepper
|
||||
|
#endif |
||||
|
#ifndef PULSE_TIMER_NUM |
||||
|
#define PULSE_TIMER_NUM STEP_TIMER_NUM |
||||
|
#endif |
||||
|
#ifndef TEMP_TIMER_NUM |
||||
|
#define TEMP_TIMER_NUM 1 // Timer Index for Temperature
|
||||
|
#endif |
||||
|
|
||||
|
#define TEMP_TIMER_RATE 1000000 |
||||
|
#define TEMP_TIMER_FREQUENCY 1000 |
||||
|
|
||||
|
#define STEPPER_TIMER_RATE GPT1_TIMER_RATE |
||||
|
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) |
||||
|
#define STEPPER_TIMER_PRESCALE ((GPT_TIMER_RATE / 1000000) / STEPPER_TIMER_TICKS_PER_US) |
||||
|
|
||||
|
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer
|
||||
|
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE |
||||
|
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US |
||||
|
|
||||
|
#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(STEP_TIMER_NUM) |
||||
|
#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(STEP_TIMER_NUM) |
||||
|
#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM) |
||||
|
|
||||
|
#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM) |
||||
|
#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM) |
||||
|
|
||||
|
#ifndef HAL_STEP_TIMER_ISR |
||||
|
#define HAL_STEP_TIMER_ISR() extern "C" void stepTC_Handler() // GPT1_Handler()
|
||||
|
#endif |
||||
|
#ifndef HAL_TEMP_TIMER_ISR |
||||
|
#define HAL_TEMP_TIMER_ISR() extern "C" void tempTC_Handler() // GPT2_Handler()
|
||||
|
#endif |
||||
|
|
||||
|
extern "C" void stepTC_Handler(); |
||||
|
extern "C" void tempTC_Handler(); |
||||
|
|
||||
|
void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency); |
||||
|
|
||||
|
FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare) { |
||||
|
switch (timer_num) { |
||||
|
case 0: |
||||
|
GPT1_OCR1 = compare - 1; |
||||
|
break; |
||||
|
case 1: |
||||
|
GPT2_OCR1 = compare - 1; |
||||
|
break; |
||||
|
} |
||||
|
} |
||||
|
|
||||
|
FORCE_INLINE static hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) { |
||||
|
switch (timer_num) { |
||||
|
case 0: return GPT1_OCR1; |
||||
|
case 1: return GPT2_OCR1; |
||||
|
} |
||||
|
return 0; |
||||
|
} |
||||
|
|
||||
|
FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) { |
||||
|
switch (timer_num) { |
||||
|
case 0: return GPT1_CNT; |
||||
|
case 1: return GPT2_CNT; |
||||
|
} |
||||
|
return 0; |
||||
|
} |
||||
|
|
||||
|
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); |
||||
|
|
||||
|
void HAL_timer_isr_prologue(const uint8_t timer_num); |
||||
|
//void HAL_timer_isr_epilogue(const uint8_t timer_num) {}
|
||||
|
#define HAL_timer_isr_epilogue(TIMER_NUM) |
@ -0,0 +1,52 @@ |
|||||
|
/**
|
||||
|
* Marlin 3D Printer Firmware |
||||
|
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
|
* |
||||
|
* Based on Sprinter and grbl. |
||||
|
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm |
||||
|
* |
||||
|
* 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 <https://www.gnu.org/licenses/>.
|
||||
|
* |
||||
|
*/ |
||||
|
#ifdef __IMXRT1062__ |
||||
|
|
||||
|
#include "../../inc/MarlinConfig.h" |
||||
|
|
||||
|
#if ENABLED(USE_WATCHDOG) |
||||
|
|
||||
|
#include "watchdog.h" |
||||
|
|
||||
|
// 4 seconds timeout
|
||||
|
#define WDTO 4 //seconds
|
||||
|
|
||||
|
uint8_t timeoutval = (WDTO - 0.5f) / 0.5f; |
||||
|
|
||||
|
void watchdog_init() { |
||||
|
|
||||
|
CCM_CCGR3 |= CCM_CCGR3_WDOG1(3); // enable WDOG1 clocks
|
||||
|
WDOG1_WMCR = 0; // disable power down PDE
|
||||
|
WDOG1_WCR |= WDOG_WCR_SRS | WDOG_WCR_WT(timeoutval); |
||||
|
WDOG1_WCR |= WDOG_WCR_WDE | WDOG_WCR_WDT | WDOG_WCR_SRE; |
||||
|
|
||||
|
} |
||||
|
|
||||
|
void HAL_watchdog_refresh() { |
||||
|
// Watchdog refresh sequence
|
||||
|
WDOG1_WSR = 0x5555; |
||||
|
WDOG1_WSR = 0xAAAA; |
||||
|
} |
||||
|
|
||||
|
#endif // USE_WATCHDOG
|
||||
|
|
||||
|
#endif // __IMXRT1062__
|
@ -0,0 +1,30 @@ |
|||||
|
/**
|
||||
|
* Marlin 3D Printer Firmware |
||||
|
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
|
* |
||||
|
* Based on Sprinter and grbl. |
||||
|
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm |
||||
|
* |
||||
|
* 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 <https://www.gnu.org/licenses/>.
|
||||
|
* |
||||
|
*/ |
||||
|
#pragma once |
||||
|
|
||||
|
/**
|
||||
|
* Watchdog for Teensy4.0/4.1 (__IMXRT1062__) |
||||
|
*/ |
||||
|
|
||||
|
void watchdog_init(); |
||||
|
|
||||
|
void HAL_watchdog_refresh(); |
Some files were not shown because too many files changed in this diff
Loading…
Reference in new issue