♻️ Refactor HAL as singleton (#23295)

This commit is contained in:
Scott Lahteine
2021-12-24 21:33:59 -06:00
committed by GitHub
parent 532f21f96f
commit e211ff148c
69 changed files with 1772 additions and 1283 deletions

View File

@@ -36,7 +36,7 @@
// ------------------------ // ------------------------
// Don't initialize/override variable (which would happen in .init4) // Don't initialize/override variable (which would happen in .init4)
uint8_t reset_reason __attribute__((section(".noinit"))); uint8_t MarlinHAL::reset_reason __attribute__((section(".noinit")));
// ------------------------ // ------------------------
// Public functions // Public functions
@@ -45,22 +45,22 @@ uint8_t reset_reason __attribute__((section(".noinit")));
__attribute__((naked)) // Don't output function pro- and epilogue __attribute__((naked)) // Don't output function pro- and epilogue
__attribute__((used)) // Output the function, even if "not used" __attribute__((used)) // Output the function, even if "not used"
__attribute__((section(".init3"))) // Put in an early user definable section __attribute__((section(".init3"))) // Put in an early user definable section
void HAL_save_reset_reason() { void save_reset_reason() {
#if ENABLED(OPTIBOOT_RESET_REASON) #if ENABLED(OPTIBOOT_RESET_REASON)
__asm__ __volatile__( __asm__ __volatile__(
A("STS %0, r2") A("STS %0, r2")
: "=m"(reset_reason) : "=m"(hal.reset_reason)
); );
#else #else
reset_reason = MCUSR; hal.reset_reason = MCUSR;
#endif #endif
// Clear within 16ms since WDRF bit enables a 16ms watchdog timer -> Boot loop // Clear within 16ms since WDRF bit enables a 16ms watchdog timer -> Boot loop
MCUSR = 0; hal.clear_reset_source();
wdt_disable(); wdt_disable();
} }
void HAL_init() { void MarlinHAL::init() {
// Init Servo Pins // Init Servo Pins
#define INIT_SERVO(N) OUT_WRITE(SERVO##N##_PIN, LOW) #define INIT_SERVO(N) OUT_WRITE(SERVO##N##_PIN, LOW)
#if HAS_SERVO_0 #if HAS_SERVO_0
@@ -77,7 +77,7 @@ void HAL_init() {
#endif #endif
} }
void HAL_reboot() { void MarlinHAL::reboot() {
#if ENABLED(USE_WATCHDOG) #if ENABLED(USE_WATCHDOG)
while (1) { /* run out the watchdog */ } while (1) { /* run out the watchdog */ }
#else #else

View File

@@ -74,9 +74,8 @@
#define CRITICAL_SECTION_START() unsigned char _sreg = SREG; cli() #define CRITICAL_SECTION_START() unsigned char _sreg = SREG; cli()
#define CRITICAL_SECTION_END() SREG = _sreg #define CRITICAL_SECTION_END() SREG = _sreg
#endif #endif
#define ISRS_ENABLED() TEST(SREG, SREG_I)
#define ENABLE_ISRS() sei() #define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment
#define DISABLE_ISRS() cli()
// ------------------------ // ------------------------
// Types // Types
@@ -84,16 +83,16 @@
typedef int8_t pin_t; typedef int8_t pin_t;
// Use shared/servos.cpp
#define SHARED_SERVOS HAS_SERVOS #define SHARED_SERVOS HAS_SERVOS
#define HAL_SERVO_LIB Servo
class Servo;
typedef Servo hal_servo_t;
// ------------------------ // ------------------------
// Public Variables
// ------------------------
extern uint8_t reset_reason;
// Serial ports // Serial ports
// ------------------------
#ifdef USBCON #ifdef USBCON
#include "../../core/serial_hook.h" #include "../../core/serial_hook.h"
typedef ForwardSerial1Class< decltype(Serial) > DefaultSerial1; typedef ForwardSerial1Class< decltype(Serial) > DefaultSerial1;
@@ -142,57 +141,15 @@ extern uint8_t reset_reason;
#endif #endif
#endif #endif
// ------------------------ //
// Public functions
// ------------------------
void HAL_init();
//void cli();
//void _delay_ms(const int delay);
inline void HAL_clear_reset_source() { }
inline uint8_t HAL_get_reset_source() { return reset_reason; }
void HAL_reboot();
#pragma GCC diagnostic push
#if GCC_VERSION <= 50000
#pragma GCC diagnostic ignored "-Wunused-function"
#endif
extern "C" int freeMemory();
#pragma GCC diagnostic pop
// ADC // ADC
#ifdef DIDR2 //
#define HAL_ANALOG_SELECT(ind) do{ if (ind < 8) SBI(DIDR0, ind); else SBI(DIDR2, ind & 0x07); }while(0)
#else
#define HAL_ANALOG_SELECT(ind) SBI(DIDR0, ind);
#endif
inline void HAL_adc_init() {
ADCSRA = _BV(ADEN) | _BV(ADSC) | _BV(ADIF) | 0x07;
DIDR0 = 0;
#ifdef DIDR2
DIDR2 = 0;
#endif
}
#define SET_ADMUX_ADCSRA(ch) ADMUX = _BV(REFS0) | (ch & 0x07); SBI(ADCSRA, ADSC)
#ifdef MUX5
#define HAL_START_ADC(ch) if (ch > 7) ADCSRB = _BV(MUX5); else ADCSRB = 0; SET_ADMUX_ADCSRA(ch)
#else
#define HAL_START_ADC(ch) ADCSRB = 0; SET_ADMUX_ADCSRA(ch)
#endif
#define HAL_ADC_VREF 5.0 #define HAL_ADC_VREF 5.0
#define HAL_ADC_RESOLUTION 10 #define HAL_ADC_RESOLUTION 10
#define HAL_READ_ADC() ADC
#define HAL_ADC_READY() !TEST(ADCSRA, ADSC)
//
// Pin Mapping for M42, M43, M226
//
#define GET_PIN_MAP_PIN(index) index #define GET_PIN_MAP_PIN(index) index
#define GET_PIN_MAP_INDEX(pin) pin #define GET_PIN_MAP_INDEX(pin) pin
#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) #define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
@@ -206,23 +163,102 @@ inline void HAL_adc_init() {
// AVR compatibility // AVR compatibility
#define strtof strtod #define strtof strtod
#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment // ------------------------
// Class Utilities
// ------------------------
#pragma GCC diagnostic push
#if GCC_VERSION <= 50000
#pragma GCC diagnostic ignored "-Wunused-function"
#endif
extern "C" int freeMemory();
#pragma GCC diagnostic pop
// ------------------------
// MarlinHAL Class
// ------------------------
class MarlinHAL {
public:
// Earliest possible init, before setup()
MarlinHAL() {}
static void init(); // Called early in setup()
static inline void init_board() {} // Called less early in setup()
static void reboot(); // Restart the firmware from 0x0
static inline bool isr_state() { return TEST(SREG, SREG_I); }
static inline void isr_on() { sei(); }
static inline void isr_off() { cli(); }
static inline void delay_ms(const int ms) { _delay_ms(ms); }
// Tasks, called from idle()
static inline void idletask() {}
// Reset
static uint8_t reset_reason;
static inline uint8_t get_reset_source() { return reset_reason; }
static inline void clear_reset_source() { MCUSR = 0; }
// Free SRAM
static inline int freeMemory() { return freeMemory(); }
//
// ADC Methods
//
// Called by Temperature::init once at startup
static inline void adc_init() {
ADCSRA = _BV(ADEN) | _BV(ADSC) | _BV(ADIF) | 0x07;
DIDR0 = 0;
#ifdef DIDR2
DIDR2 = 0;
#endif
}
// Called by Temperature::init for each sensor at startup
static inline void adc_enable(const uint8_t ch) {
#ifdef DIDR2
if (ch > 7) { SBI(DIDR2, ch & 0x07); return; }
#endif
SBI(DIDR0, ch);
}
// Begin ADC sampling on the given channel
static inline void adc_start(const pin_t ch) {
#ifdef MUX5
if (ch > 7) { ADCSRB = _BV(MUX5); return; }
#endif
ADCSRB = 0;
ADMUX = _BV(REFS0) | (ch & 0x07); SBI(ADCSRA, ADSC);
}
// Is the ADC ready for reading?
static inline bool adc_ready() { return !TEST(ADCSRA, ADSC); }
// The current value of the ADC register
static inline __typeof__(ADC) adc_value() { return ADC; }
/** /**
* set_pwm_frequency * Set the PWM duty cycle for the pin to the given value.
* Sets the frequency of the timer corresponding to the provided pin * Optionally invert the duty cycle [default = false]
* as close as possible to the provided desired frequency. Internally * Optionally change the scale of the provided value to enable finer PWM duty control [default = 255]
* calculates the required waveform generation mode, prescaler and */
* resolution values required and sets the timer registers accordingly. static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false);
/**
* Set the frequency of the timer for the given pin as close as
* possible to the provided desired frequency. Internally calculate
* the required waveform generation mode, prescaler, and resolution
* values and set timer registers accordingly.
* NOTE that the frequency is applied to all pins on the timer (Ex OC3A, OC3B and OC3B) * NOTE that the frequency is applied to all pins on the timer (Ex OC3A, OC3B and OC3B)
* NOTE that there are limitations, particularly if using TIMER2. (see Configuration_adv.h -> FAST FAN PWM Settings) * NOTE that there are limitations, particularly if using TIMER2. (see Configuration_adv.h -> FAST FAN PWM Settings)
*/ */
void set_pwm_frequency(const pin_t pin, int f_desired); static void set_pwm_frequency(const pin_t pin, int f_desired);
};
/** extern MarlinHAL hal;
* set_pwm_duty
* Set the PWM duty cycle of the provided pin to the provided value
* Optionally allows inverting the duty cycle [default = false]
* Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255]
*/
void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false);

View File

@@ -486,7 +486,7 @@ void MarlinSerial<Cfg>::write(const uint8_t c) {
const uint8_t i = (tx_buffer.head + 1) & (Cfg::TX_SIZE - 1); const uint8_t i = (tx_buffer.head + 1) & (Cfg::TX_SIZE - 1);
// If global interrupts are disabled (as the result of being called from an ISR)... // If global interrupts are disabled (as the result of being called from an ISR)...
if (!ISRS_ENABLED()) { if (!hal.isr_state()) {
// Make room by polling if it is possible to transmit, and do so! // Make room by polling if it is possible to transmit, and do so!
while (i == tx_buffer.tail) { while (i == tx_buffer.tail) {
@@ -534,7 +534,7 @@ void MarlinSerial<Cfg>::flushTX() {
if (!_written) return; if (!_written) return;
// If global interrupts are disabled (as the result of being called from an ISR)... // If global interrupts are disabled (as the result of being called from an ISR)...
if (!ISRS_ENABLED()) { if (!hal.isr_state()) {
// Wait until everything was transmitted - We must do polling, as interrupts are disabled // Wait until everything was transmitted - We must do polling, as interrupts are disabled
while (tx_buffer.head != tx_buffer.tail || !B_TXC) { while (tx_buffer.head != tx_buffer.tail || !B_TXC) {

View File

@@ -35,8 +35,7 @@ struct Timer {
}; };
/** /**
* get_pwm_timer * Get the timer information and register for a pin.
* Get the timer information and register of the provided pin.
* Return a Timer struct containing this information. * Return a Timer struct containing this information.
* Used by set_pwm_frequency, set_pwm_duty * Used by set_pwm_frequency, set_pwm_duty
*/ */
@@ -150,7 +149,7 @@ Timer get_pwm_timer(const pin_t pin) {
return timer; return timer;
} }
void set_pwm_frequency(const pin_t pin, int f_desired) { void MarlinHAL::set_pwm_frequency(const pin_t pin, int f_desired) {
Timer timer = get_pwm_timer(pin); Timer timer = get_pwm_timer(pin);
if (timer.n == 0) return; // Don't proceed if protected timer or not recognized if (timer.n == 0) return; // Don't proceed if protected timer or not recognized
uint16_t size; uint16_t size;
@@ -230,7 +229,7 @@ void set_pwm_frequency(const pin_t pin, int f_desired) {
#endif // NEEDS_HARDWARE_PWM #endif // NEEDS_HARDWARE_PWM
void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) {
#if NEEDS_HARDWARE_PWM #if NEEDS_HARDWARE_PWM
// If v is 0 or v_size (max), digitalWrite to LOW or HIGH. // If v is 0 or v_size (max), digitalWrite to LOW or HIGH.

View File

@@ -109,8 +109,8 @@ FORCE_INLINE void HAL_timer_start(const uint8_t timer_num, const uint32_t) {
* (otherwise, characters will be lost due to UART overflow). * (otherwise, characters will be lost due to UART overflow).
* Then: Stepper, Endstops, Temperature, and -finally- all others. * Then: Stepper, Endstops, Temperature, and -finally- all others.
*/ */
#define HAL_timer_isr_prologue(T) #define HAL_timer_isr_prologue(T) NOOP
#define HAL_timer_isr_epilogue(T) #define HAL_timer_isr_epilogue(T) NOOP
/* 18 cycles maximum latency */ /* 18 cycles maximum latency */
#ifndef HAL_STEP_TIMER_ISR #ifndef HAL_STEP_TIMER_ISR

View File

@@ -34,7 +34,7 @@
// Public Variables // Public Variables
// ------------------------ // ------------------------
uint16_t HAL_adc_result; uint16_t MarlinHAL::adc_result;
// ------------------------ // ------------------------
// Public functions // Public functions
@@ -42,8 +42,7 @@ uint16_t HAL_adc_result;
TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial()); TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial());
// HAL initialization task void MarlinHAL::init() {
void HAL_init() {
// Initialize the USB stack // Initialize the USB stack
#if ENABLED(SDSUPPORT) #if ENABLED(SDSUPPORT)
OUT_WRITE(SDSS, HIGH); // Try to set SDSS inactive before any other SPI users start up OUT_WRITE(SDSS, HIGH); // Try to set SDSS inactive before any other SPI users start up
@@ -52,21 +51,17 @@ void HAL_init() {
TERN_(POSTMORTEM_DEBUGGING, install_min_serial()); // Install the min serial handler TERN_(POSTMORTEM_DEBUGGING, install_min_serial()); // Install the min serial handler
} }
// HAL idle task void MarlinHAL::init_board() {
void HAL_idletask() { #ifdef BOARD_INIT
// Perform USB stack housekeeping BOARD_INIT();
usb_task_idle(); #endif
} }
// Disable interrupts void MarlinHAL::idletask() {
void cli() { noInterrupts(); } usb_task_idle(); // Perform USB stack housekeeping
}
// Enable interrupts uint8_t MarlinHAL::get_reset_source() {
void sei() { interrupts(); }
void HAL_clear_reset_source() { }
uint8_t HAL_get_reset_source() {
switch ((RSTC->RSTC_SR >> 8) & 0x07) { switch ((RSTC->RSTC_SR >> 8) & 0x07) {
case 0: return RST_POWER_ON; case 0: return RST_POWER_ON;
case 1: return RST_BACKUP; case 1: return RST_BACKUP;
@@ -77,12 +72,7 @@ uint8_t HAL_get_reset_source() {
} }
} }
void HAL_reboot() { rstc_start_software_reset(RSTC); } void MarlinHAL::reboot() { rstc_start_software_reset(RSTC); }
void _delay_ms(const int delay_ms) {
// Todo: port for Due?
delay(delay_ms);
}
extern "C" { extern "C" {
extern unsigned int _ebss; // end of bss section extern unsigned int _ebss; // end of bss section
@@ -94,19 +84,6 @@ int freeMemory() {
return (int)&free_memory - (heap_end ?: (int)&_ebss); return (int)&free_memory - (heap_end ?: (int)&_ebss);
} }
// ------------------------
// ADC
// ------------------------
void HAL_adc_start_conversion(const uint8_t ch) {
HAL_adc_result = analogRead(ch);
}
uint16_t HAL_adc_get_result() {
// nop
return HAL_adc_result;
}
// Forward the default serial ports // Forward the default serial ports
#if USING_HW_SERIAL0 #if USING_HW_SERIAL0
DefaultSerial1 MSerial0(false, Serial); DefaultSerial1 MSerial0(false, Serial);

View File

@@ -38,6 +38,10 @@
#include "../../core/serial_hook.h" #include "../../core/serial_hook.h"
// ------------------------
// Serial ports
// ------------------------
typedef ForwardSerial1Class< decltype(Serial) > DefaultSerial1; typedef ForwardSerial1Class< decltype(Serial) > DefaultSerial1;
typedef ForwardSerial1Class< decltype(Serial1) > DefaultSerial2; typedef ForwardSerial1Class< decltype(Serial1) > DefaultSerial2;
typedef ForwardSerial1Class< decltype(Serial2) > DefaultSerial3; typedef ForwardSerial1Class< decltype(Serial2) > DefaultSerial3;
@@ -97,35 +101,31 @@ extern DefaultSerial4 MSerial3;
#include "MarlinSerial.h" #include "MarlinSerial.h"
#include "MarlinSerialUSB.h" #include "MarlinSerialUSB.h"
// On AVR this is in math.h? // ------------------------
#define square(x) ((x)*(x)) // Types
// ------------------------
typedef int8_t pin_t; typedef int8_t pin_t;
// Use shared/servos.cpp
#define SHARED_SERVOS HAS_SERVOS #define SHARED_SERVOS HAS_SERVOS
#define HAL_SERVO_LIB Servo class Servo;
typedef Servo hal_servo_t;
// //
// Interrupts // Interrupts
// //
#define CRITICAL_SECTION_START() uint32_t primask = __get_PRIMASK(); __disable_irq() #define sei() noInterrupts()
#define CRITICAL_SECTION_END() if (!primask) __enable_irq() #define cli() interrupts()
#define ISRS_ENABLED() (!__get_PRIMASK())
#define ENABLE_ISRS() __enable_irq()
#define DISABLE_ISRS() __disable_irq()
void cli(); // Disable interrupts #define CRITICAL_SECTION_START() const bool _irqon = hal.isr_state(); hal.isr_off()
void sei(); // Enable interrupts #define CRITICAL_SECTION_END() if (_irqon) hal.isr_on()
void HAL_clear_reset_source(); // clear reset reason
uint8_t HAL_get_reset_source(); // get reset reason
void HAL_reboot();
// //
// ADC // ADC
// //
extern uint16_t HAL_adc_result; // result of last ADC conversion #define HAL_ADC_VREF 3.3
#define HAL_ADC_RESOLUTION 10
#ifndef analogInputToDigitalPin #ifndef analogInputToDigitalPin
#define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1) #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1)
@@ -133,24 +133,8 @@ extern uint16_t HAL_adc_result; // result of last ADC conversion
#define HAL_ANALOG_SELECT(ch) #define HAL_ANALOG_SELECT(ch)
inline void HAL_adc_init() {}//todo
#define HAL_ADC_VREF 3.3
#define HAL_ADC_RESOLUTION 10
#define HAL_START_ADC(ch) HAL_adc_start_conversion(ch)
#define HAL_READ_ADC() HAL_adc_result
#define HAL_ADC_READY() true
void HAL_adc_start_conversion(const uint8_t ch);
uint16_t HAL_adc_get_result();
// //
// PWM // Pin Mapping for M42, M43, M226
//
inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); }
//
// Pin Map
// //
#define GET_PIN_MAP_PIN(index) index #define GET_PIN_MAP_PIN(index) index
#define GET_PIN_MAP_INDEX(pin) pin #define GET_PIN_MAP_INDEX(pin) pin
@@ -159,27 +143,18 @@ inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255,
// //
// Tone // Tone
// //
void toneInit();
void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration=0); void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration=0);
void noTone(const pin_t _pin); void noTone(const pin_t _pin);
// Enable hooks into idle and setup for HAL // ------------------------
#define HAL_IDLETASK 1 // Class Utilities
void HAL_idletask(); // ------------------------
void HAL_init();
//
// Utility functions
//
void _delay_ms(const int delay);
#pragma GCC diagnostic push #pragma GCC diagnostic push
#if GCC_VERSION <= 50000 #if GCC_VERSION <= 50000
#pragma GCC diagnostic ignored "-Wunused-function" #pragma GCC diagnostic ignored "-Wunused-function"
#endif #endif
int freeMemory();
#pragma GCC diagnostic pop #pragma GCC diagnostic pop
#ifdef __cplusplus #ifdef __cplusplus
@@ -189,3 +164,70 @@ char *dtostrf(double __val, signed char __width, unsigned char __prec, char *__s
#ifdef __cplusplus #ifdef __cplusplus
} }
#endif #endif
// Return free RAM between end of heap (or end bss) and whatever is current
int freeMemory();
// ------------------------
// MarlinHAL Class
// ------------------------
class MarlinHAL {
public:
// Earliest possible init, before setup()
MarlinHAL() {}
static void init(); // Called early in setup()
static void init_board(); // Called less early in setup()
static void reboot(); // Software reset
static inline bool isr_state() { return !__get_PRIMASK(); }
static inline void isr_on() { __enable_irq(); }
static inline void isr_off() { __disable_irq(); }
static inline void delay_ms(const int ms) { delay(ms); }
// Tasks, called from idle()
static void idletask();
// Reset
static uint8_t get_reset_source();
static inline void clear_reset_source() {}
// Free SRAM
static inline int freeMemory() { return freeMemory(); }
//
// ADC Methods
//
static uint16_t adc_result;
// Called by Temperature::init once at startup
static inline void adc_init() {}
// Called by Temperature::init for each sensor at startup
static inline void adc_enable(const int ch) {}
// Begin ADC sampling on the given channel
static inline void adc_start(const uint8_t ch) { adc_result = analogRead(ch); }
// Is the ADC ready for reading?
static inline bool adc_ready() { return true; }
// The current value of the ADC register
static inline uint16_t adc_value() { return adc_result; }
/**
* Set the PWM duty cycle for the pin to the given value.
* No inverting the duty cycle in this HAL.
* No changing the maximum size of the provided value to enable finer PWM duty control in this HAL.
*/
static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) {
analogWrite(pin, v);
}
};
extern MarlinHAL hal;

View File

@@ -406,7 +406,7 @@ size_t MarlinSerial<Cfg>::write(const uint8_t c) {
const uint8_t i = (tx_buffer.head + 1) & (Cfg::TX_SIZE - 1); const uint8_t i = (tx_buffer.head + 1) & (Cfg::TX_SIZE - 1);
// If global interrupts are disabled (as the result of being called from an ISR)... // If global interrupts are disabled (as the result of being called from an ISR)...
if (!ISRS_ENABLED()) { if (!hal.isr_state()) {
// Make room by polling if it is possible to transmit, and do so! // Make room by polling if it is possible to transmit, and do so!
while (i == tx_buffer.tail) { while (i == tx_buffer.tail) {
@@ -454,7 +454,7 @@ void MarlinSerial<Cfg>::flushTX() {
if (!_written) return; if (!_written) return;
// If global interrupts are disabled (as the result of being called from an ISR)... // If global interrupts are disabled (as the result of being called from an ISR)...
if (!ISRS_ENABLED()) { if (!hal.isr_state()) {
// Wait until everything was transmitted - We must do polling, as interrupts are disabled // Wait until everything was transmitted - We must do polling, as interrupts are disabled
while (tx_buffer.head != tx_buffer.tail || !(HWUART->UART_SR & UART_SR_TXEMPTY)) { while (tx_buffer.head != tx_buffer.tail || !(HWUART->UART_SR & UART_SR_TXEMPTY)) {

View File

@@ -125,4 +125,4 @@ FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) {
pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_SR; pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_SR;
} }
#define HAL_timer_isr_epilogue(T) #define HAL_timer_isr_epilogue(T) NOOP

View File

@@ -52,7 +52,7 @@
// Externs // Externs
// ------------------------ // ------------------------
portMUX_TYPE spinlock = portMUX_INITIALIZER_UNLOCKED; portMUX_TYPE MarlinHAL::spinlock = portMUX_INITIALIZER_UNLOCKED;
// ------------------------ // ------------------------
// Local defines // Local defines
@@ -64,7 +64,7 @@ portMUX_TYPE spinlock = portMUX_INITIALIZER_UNLOCKED;
// Public Variables // Public Variables
// ------------------------ // ------------------------
uint16_t HAL_adc_result; uint16_t MarlinHAL::adc_result;
// ------------------------ // ------------------------
// Private Variables // Private Variables
@@ -95,20 +95,22 @@ volatile int numPWMUsed = 0,
#endif #endif
#if ENABLED(USE_ESP32_EXIO) #if ENABLED(USE_ESP32_EXIO)
HardwareSerial YSerial2(2); HardwareSerial YSerial2(2);
void Write_EXIO(uint8_t IO, uint8_t v) { void Write_EXIO(uint8_t IO, uint8_t v) {
if (ISRS_ENABLED()) { if (hal.isr_state()) {
DISABLE_ISRS(); hal.isr_off();
YSerial2.write(0x80 | (((char)v) << 5) | (IO - 100)); YSerial2.write(0x80 | (((char)v) << 5) | (IO - 100));
ENABLE_ISRS(); hal.isr_on();
} }
else else
YSerial2.write(0x80 | (((char)v) << 5) | (IO - 100)); YSerial2.write(0x80 | (((char)v) << 5) | (IO - 100));
} }
#endif #endif
void HAL_init_board() { void MarlinHAL::init_board() {
#if ENABLED(USE_ESP32_TASK_WDT) #if ENABLED(USE_ESP32_TASK_WDT)
esp_task_wdt_init(10, true); esp_task_wdt_init(10, true);
#endif #endif
@@ -154,27 +156,24 @@ void HAL_init_board() {
#endif #endif
} }
void HAL_idletask() { void MarlinHAL::idletask() {
#if BOTH(WIFISUPPORT, OTASUPPORT) #if BOTH(WIFISUPPORT, OTASUPPORT)
OTA_handle(); OTA_handle();
#endif #endif
TERN_(ESP3D_WIFISUPPORT, esp3dlib.idletask()); TERN_(ESP3D_WIFISUPPORT, esp3dlib.idletask());
} }
void HAL_clear_reset_source() { } uint8_t MarlinHAL::get_reset_source() { return rtc_get_reset_reason(1); }
uint8_t HAL_get_reset_source() { return rtc_get_reset_reason(1); } void MarlinHAL::reboot() { ESP.restart(); }
void HAL_reboot() { ESP.restart(); }
void _delay_ms(int delay_ms) { delay(delay_ms); }
// return free memory between end of heap (or end bss) and whatever is current // return free memory between end of heap (or end bss) and whatever is current
int freeMemory() { return ESP.getFreeHeap(); } int MarlinHAL::freeMemory() { return ESP.getFreeHeap(); }
// ------------------------ // ------------------------
// ADC // ADC
// ------------------------ // ------------------------
#define ADC1_CHANNEL(pin) ADC1_GPIO ## pin ## _CHANNEL #define ADC1_CHANNEL(pin) ADC1_GPIO ## pin ## _CHANNEL
adc1_channel_t get_channel(int pin) { adc1_channel_t get_channel(int pin) {
@@ -196,7 +195,7 @@ void adc1_set_attenuation(adc1_channel_t chan, adc_atten_t atten) {
} }
} }
void HAL_adc_init() { void MarlinHAL::adc_init() {
// Configure ADC // Configure ADC
adc1_config_width(ADC_WIDTH_12Bit); adc1_config_width(ADC_WIDTH_12Bit);
@@ -226,11 +225,11 @@ void HAL_adc_init() {
} }
} }
void HAL_adc_start_conversion(const uint8_t adc_pin) { void MarlinHAL::adc_start(const pin_t pin) {
const adc1_channel_t chan = get_channel(adc_pin); const adc1_channel_t chan = get_channel(pin);
uint32_t mv; uint32_t mv;
esp_adc_cal_get_voltage((adc_channel_t)chan, &characteristics[attenuations[chan]], &mv); esp_adc_cal_get_voltage((adc_channel_t)chan, &characteristics[attenuations[chan]], &mv);
HAL_adc_result = mv * 1023.0 / 3300.0; adc_result = mv * 1023.0 / 3300.0;
// Change the attenuation level based on the new reading // Change the attenuation level based on the new reading
adc_atten_t atten; adc_atten_t atten;

View File

@@ -49,8 +49,6 @@
// Defines // Defines
// ------------------------ // ------------------------
extern portMUX_TYPE spinlock;
#define MYSERIAL1 flushableSerial #define MYSERIAL1 flushableSerial
#if EITHER(WIFISUPPORT, ESP3D_WIFISUPPORT) #if EITHER(WIFISUPPORT, ESP3D_WIFISUPPORT)
@@ -65,9 +63,6 @@ extern portMUX_TYPE spinlock;
#define CRITICAL_SECTION_START() portENTER_CRITICAL(&spinlock) #define CRITICAL_SECTION_START() portENTER_CRITICAL(&spinlock)
#define CRITICAL_SECTION_END() portEXIT_CRITICAL(&spinlock) #define CRITICAL_SECTION_END() portEXIT_CRITICAL(&spinlock)
#define ISRS_ENABLED() (spinlock.owner == portMUX_FREE_VAL)
#define ENABLE_ISRS() if (spinlock.owner != portMUX_FREE_VAL) portEXIT_CRITICAL(&spinlock)
#define DISABLE_ISRS() portENTER_CRITICAL(&spinlock)
// ------------------------ // ------------------------
// Types // Types
@@ -75,14 +70,8 @@ extern portMUX_TYPE spinlock;
typedef int16_t pin_t; typedef int16_t pin_t;
#define HAL_SERVO_LIB Servo class Servo;
typedef Servo hal_servo_t;
// ------------------------
// Public Variables
// ------------------------
/** result of last ADC conversion */
extern uint16_t HAL_adc_result;
// ------------------------ // ------------------------
// Public functions // Public functions
@@ -91,59 +80,21 @@ extern uint16_t HAL_adc_result;
// //
// Tone // Tone
// //
void toneInit();
void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration=0); void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration=0);
void noTone(const pin_t _pin); void noTone(const pin_t _pin);
// clear reset reason
void HAL_clear_reset_source();
// reset reason
uint8_t HAL_get_reset_source();
void HAL_reboot();
void _delay_ms(int delay);
#pragma GCC diagnostic push
#if GCC_VERSION <= 50000
#pragma GCC diagnostic ignored "-Wunused-function"
#endif
int freeMemory();
#pragma GCC diagnostic pop
void analogWrite(pin_t pin, int value); void analogWrite(pin_t pin, int value);
// ADC // ADC
#define HAL_ANALOG_SELECT(pin) #define HAL_ANALOG_SELECT(pin)
void HAL_adc_init(); //
// Pin Mapping for M42, M43, M226
#define HAL_ADC_VREF 3.3 //
#define HAL_ADC_RESOLUTION 10
#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin)
#define HAL_READ_ADC() HAL_adc_result
#define HAL_ADC_READY() true
void HAL_adc_start_conversion(const uint8_t adc_pin);
// PWM
inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); }
// Pin Map
#define GET_PIN_MAP_PIN(index) index #define GET_PIN_MAP_PIN(index) index
#define GET_PIN_MAP_INDEX(pin) pin #define GET_PIN_MAP_INDEX(pin) pin
#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) #define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
// Enable hooks into idle and setup for HAL
#define HAL_IDLETASK 1
#define BOARD_INIT() HAL_init_board();
void HAL_idletask();
inline void HAL_init() {}
void HAL_init_board();
#if ENABLED(USE_ESP32_EXIO) #if ENABLED(USE_ESP32_EXIO)
void Write_EXIO(uint8_t IO, uint8_t v); void Write_EXIO(uint8_t IO, uint8_t v);
#endif #endif
@@ -188,3 +139,86 @@ FORCE_INLINE static void DELAY_CYCLES(uint32_t x) {
} }
} }
// ------------------------
// Class Utilities
// ------------------------
#pragma GCC diagnostic push
#if GCC_VERSION <= 50000
#pragma GCC diagnostic ignored "-Wunused-function"
#endif
int freeMemory();
#pragma GCC diagnostic pop
void _delay_ms(const int ms);
// ------------------------
// MarlinHAL Class
// ------------------------
#define HAL_ADC_VREF 3.3
#define HAL_ADC_RESOLUTION 10
class MarlinHAL {
public:
// Earliest possible init, before setup()
MarlinHAL() {}
static inline void init() {} // Called early in setup()
static void init_board(); // Called less early in setup()
static void reboot(); // Restart the firmware
static portMUX_TYPE spinlock;
static inline bool isr_state() { return spinlock.owner == portMUX_FREE_VAL; }
static inline void isr_on() { if (spinlock.owner != portMUX_FREE_VAL) portEXIT_CRITICAL(&spinlock); }
static inline void isr_off() { portENTER_CRITICAL(&spinlock); }
static inline void delay_ms(const int ms) { _delay_ms(ms); }
// Tasks, called from idle()
static void idletask();
// Reset
static uint8_t get_reset_source();
static inline void clear_reset_source() {}
// Free SRAM
static int freeMemory();
//
// ADC Methods
//
static uint16_t adc_result;
// Called by Temperature::init once at startup
static void adc_init();
// Called by Temperature::init for each sensor at startup
static inline void adc_enable(const pin_t pin) {}
// Begin ADC sampling on the given channel
static void adc_start(const pin_t pin);
// Is the ADC ready for reading?
static inline bool adc_ready() { return true; }
// The current value of the ADC register
static inline uint16_t adc_value() { return adc_result; }
/**
* Set the PWM duty cycle for the pin to the given value.
* No inverting the duty cycle in this HAL.
* No changing the maximum size of the provided value to enable finer PWM duty control in this HAL.
*/
static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) {
analogWrite(pin, v);
}
};
extern MarlinHAL hal;

View File

@@ -136,5 +136,5 @@ void HAL_timer_enable_interrupt(const uint8_t timer_num);
void HAL_timer_disable_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); bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
#define HAL_timer_isr_prologue(T) #define HAL_timer_isr_prologue(T) NOOP
#define HAL_timer_isr_epilogue(T) #define HAL_timer_isr_epilogue(T) NOOP

View File

@@ -24,6 +24,12 @@
#include "../../inc/MarlinConfig.h" #include "../../inc/MarlinConfig.h"
#include "../shared/Delay.h" #include "../shared/Delay.h"
extern MarlinHAL hal;
// ------------------------
// Serial ports
// ------------------------
MSerialT usb_serial(TERN0(EMERGENCY_PARSER, true)); MSerialT usb_serial(TERN0(EMERGENCY_PARSER, true));
// U8glib required functions // U8glib required functions
@@ -37,42 +43,21 @@ extern "C" {
//************************// //************************//
// return free heap space // return free heap space
int freeMemory() { int freeMemory() { return 0; }
return 0;
}
// ------------------------ // ------------------------
// ADC // ADC
// ------------------------ // ------------------------
void HAL_adc_init() { uint8_t MarlinHAL::active_ch = 0;
} uint16_t MarlinHAL::adc_value() {
const pin_t pin = analogInputToDigitalPin(active_ch);
void HAL_adc_enable_channel(const uint8_t ch) {
}
uint8_t active_ch = 0;
void HAL_adc_start_conversion(const uint8_t ch) {
active_ch = ch;
}
bool HAL_adc_finished() {
return true;
}
uint16_t HAL_adc_get_result() {
pin_t pin = analogInputToDigitalPin(active_ch);
if (!VALID_PIN(pin)) return 0; if (!VALID_PIN(pin)) return 0;
uint16_t data = ((Gpio::get(pin) >> 2) & 0x3FF); const uint16_t data = ((Gpio::get(pin) >> 2) & 0x3FF);
return data; // return 10bit value as Marlin expects return data; // return 10bit value as Marlin expects
} }
void HAL_pwm_init() { void MarlinHAL::reboot() { /* Reset the application state and GPIO */ }
}
void HAL_reboot() { /* Reset the application state and GPIO */ }
#endif // __PLAT_LINUX__ #endif // __PLAT_LINUX__

View File

@@ -21,34 +21,13 @@
*/ */
#pragma once #pragma once
#define CPU_32_BIT
#define F_CPU 100000000UL
#define SystemCoreClock F_CPU
#include <iostream> #include <iostream>
#include <stdint.h> #include <stdint.h>
#include <stdarg.h> #include <stdarg.h>
#undef min #undef min
#undef max #undef max
#include <algorithm> #include <algorithm>
void _printf (const char *format, ...);
void _putc(uint8_t c);
uint8_t _getc();
//extern "C" volatile uint32_t _millis;
//arduino: Print.h
#define DEC 10
#define HEX 16
#define OCT 8
#define BIN 2
//arduino: binary.h (weird defines)
#define B01 1
#define B10 2
#include "hardware/Clock.h" #include "hardware/Clock.h"
#include "../shared/Marduino.h" #include "../shared/Marduino.h"
@@ -58,27 +37,57 @@ uint8_t _getc();
#include "watchdog.h" #include "watchdog.h"
#include "serial.h" #include "serial.h"
#define SHARED_SERVOS HAS_SERVOS // ------------------------
// Defines
// ------------------------
extern MSerialT usb_serial; #define CPU_32_BIT
#define MYSERIAL1 usb_serial #define SHARED_SERVOS HAS_SERVOS // Use shared/servos.cpp
#define F_CPU 100000000UL
#define SystemCoreClock F_CPU
#define DELAY_CYCLES(x) Clock::delayCycles(x)
#define CPU_ST7920_DELAY_1 600 #define CPU_ST7920_DELAY_1 600
#define CPU_ST7920_DELAY_2 750 #define CPU_ST7920_DELAY_2 750
#define CPU_ST7920_DELAY_3 750 #define CPU_ST7920_DELAY_3 750
void _printf(const char *format, ...);
void _putc(uint8_t c);
uint8_t _getc();
//arduino: Print.h
#define DEC 10
#define HEX 16
#define OCT 8
#define BIN 2
//arduino: binary.h (weird defines)
#define B01 1
#define B10 2
// ------------------------
// Serial ports
// ------------------------
extern MSerialT usb_serial;
#define MYSERIAL1 usb_serial
// //
// Interrupts // Interrupts
// //
#define CRITICAL_SECTION_START() #define CRITICAL_SECTION_START()
#define CRITICAL_SECTION_END() #define CRITICAL_SECTION_END()
#define ISRS_ENABLED()
#define ENABLE_ISRS()
#define DISABLE_ISRS()
inline void HAL_init() {} // ADC
#define HAL_ADC_VREF 5.0
#define HAL_ADC_RESOLUTION 10
#define HAL_ANALOG_SELECT(ch) hal.adc_enable(ch)
// ------------------------
// Class Utilities
// ------------------------
// Utility functions
#pragma GCC diagnostic push #pragma GCC diagnostic push
#if GCC_VERSION <= 50000 #if GCC_VERSION <= 50000
#pragma GCC diagnostic ignored "-Wunused-function" #pragma GCC diagnostic ignored "-Wunused-function"
@@ -88,29 +97,67 @@ int freeMemory();
#pragma GCC diagnostic pop #pragma GCC diagnostic pop
// ADC // ------------------------
#define HAL_ADC_VREF 5.0 // MarlinHAL Class
#define HAL_ADC_RESOLUTION 10 // ------------------------
#define HAL_ANALOG_SELECT(ch) HAL_adc_enable_channel(ch)
#define HAL_START_ADC(ch) HAL_adc_start_conversion(ch)
#define HAL_READ_ADC() HAL_adc_get_result()
#define HAL_ADC_READY() true
void HAL_adc_init(); class MarlinHAL {
void HAL_adc_enable_channel(const uint8_t ch); public:
void HAL_adc_start_conversion(const uint8_t ch);
uint16_t HAL_adc_get_result();
// PWM // Earliest possible init, before setup()
inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } MarlinHAL() {}
// Reset source static inline void init() {} // Called early in setup()
inline void HAL_clear_reset_source(void) {} static inline void init_board() {} // Called less early in setup()
inline uint8_t HAL_get_reset_source(void) { return RST_POWER_ON; } static void reboot(); // Reset the application state and GPIO
void HAL_reboot(); // Reset the application state and GPIO static inline bool isr_state() { return true; }
static inline void isr_on() {}
static inline void isr_off() {}
/* ---------------- Delay in cycles */ static inline void delay_ms(const int ms) { _delay_ms(ms); }
FORCE_INLINE static void DELAY_CYCLES(uint64_t x) {
Clock::delayCycles(x); // Tasks, called from idle()
static inline void idletask() {}
// Reset
static constexpr uint8_t reset_reason = RST_POWER_ON;
static inline uint8_t get_reset_source() { return reset_reason; }
static inline void clear_reset_source() {}
// Free SRAM
static inline int freeMemory() { return freeMemory(); }
//
// ADC Methods
//
static uint8_t active_ch;
// Called by Temperature::init once at startup
static inline void adc_init() {}
// Called by Temperature::init for each sensor at startup
static inline void adc_enable(const uint8_t) {}
// Begin ADC sampling on the given channel
static inline void adc_start(const pin_t ch) { active_ch = ch; }
// Is the ADC ready for reading?
static inline bool adc_ready() { return true; }
// The current value of the ADC register
static uint16_t adc_value();
/**
* Set the PWM duty cycle for the pin to the given value.
* No option to change the resolution or invert the duty cycle.
*/
static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) {
analogWrite(pin, v);
} }
static inline void set_pwm_frequency(const pin_t, int) {}
};
extern MarlinHAL hal;

View File

@@ -31,9 +31,7 @@ void cli() { } // Disable
void sei() { } // Enable void sei() { } // Enable
// Time functions // Time functions
void _delay_ms(const int delay_ms) { void _delay_ms(const int ms) { delay(ms); }
delay(delay_ms);
}
uint32_t millis() { uint32_t millis() {
return (uint32_t)Clock::millis(); return (uint32_t)Clock::millis();

View File

@@ -59,7 +59,6 @@ typedef uint8_t byte;
#endif #endif
#define sq(v) ((v) * (v)) #define sq(v) ((v) * (v))
#define square(v) sq(v)
#define constrain(value, arg_min, arg_max) ((value) < (arg_min) ? (arg_min) :((value) > (arg_max) ? (arg_max) : (value))) #define constrain(value, arg_min, arg_max) ((value) < (arg_min) ? (arg_min) :((value) > (arg_max) ? (arg_max) : (value)))
//Interrupts //Interrupts
@@ -74,8 +73,8 @@ extern "C" {
} }
// Time functions // Time functions
extern "C" void delay(const int milis); extern "C" void delay(const int ms);
void _delay_ms(const int delay); void _delay_ms(const int ms);
void delayMicroseconds(unsigned long); void delayMicroseconds(unsigned long);
uint32_t millis(); uint32_t millis();

View File

@@ -92,5 +92,5 @@ void HAL_timer_enable_interrupt(const uint8_t timer_num);
void HAL_timer_disable_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); bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
#define HAL_timer_isr_prologue(T) #define HAL_timer_isr_prologue(T) NOOP
#define HAL_timer_isr_epilogue(T) #define HAL_timer_isr_epilogue(T) NOOP

View File

@@ -31,7 +31,7 @@
DefaultSerial1 USBSerial(false, UsbSerial); DefaultSerial1 USBSerial(false, UsbSerial);
uint32_t HAL_adc_reading = 0; uint32_t MarlinHAL::adc_result = 0;
// U8glib required functions // U8glib required functions
extern "C" { extern "C" {
@@ -41,8 +41,6 @@ extern "C" {
void u8g_Delay(uint16_t val) { delay(val); } void u8g_Delay(uint16_t val) { delay(val); }
} }
//************************//
// return free heap space // return free heap space
int freeMemory() { int freeMemory() {
char stack_end; char stack_end;
@@ -54,7 +52,27 @@ int freeMemory() {
return result; return result;
} }
// scan command line for code void MarlinHAL::reboot() { NVIC_SystemReset(); }
uint8_t MarlinHAL::get_reset_source() {
#if ENABLED(USE_WATCHDOG)
if (watchdog_timed_out()) return RST_WATCHDOG;
#endif
return RST_POWER_ON;
}
void MarlinHAL::clear_reset_source() {
TERN_(USE_WATCHDOG, watchdog_clear_timeout_flag());
}
void flashFirmware(const int16_t) {
delay(500); // Give OS time to disconnect
USB_Connect(false); // USB clear connection
delay(1000); // Give OS time to notice
hal.reboot();
}
// For M42/M43, scan command line for pin code
// return index into pin map array if found and the pin is valid. // return index into pin map array if found and the pin is valid.
// return dval if not found or not a valid pin. // return dval if not found or not a valid pin.
int16_t PARSED_PIN_INDEX(const char code, const int16_t dval) { int16_t PARSED_PIN_INDEX(const char code, const int16_t dval) {
@@ -63,24 +81,4 @@ int16_t PARSED_PIN_INDEX(const char code, const int16_t dval) {
return ind > -1 ? ind : dval; return ind > -1 ? ind : dval;
} }
void flashFirmware(const int16_t) {
delay(500); // Give OS time to disconnect
USB_Connect(false); // USB clear connection
delay(1000); // Give OS time to notice
HAL_reboot();
}
void HAL_clear_reset_source(void) {
TERN_(USE_WATCHDOG, watchdog_clear_timeout_flag());
}
uint8_t HAL_get_reset_source(void) {
#if ENABLED(USE_WATCHDOG)
if (watchdog_timed_out()) return RST_WATCHDOG;
#endif
return RST_POWER_ON;
}
void HAL_reboot() { NVIC_SystemReset(); }
#endif // TARGET_LPC1768 #endif // TARGET_LPC1768

View File

@@ -28,8 +28,6 @@
#define CPU_32_BIT #define CPU_32_BIT
void HAL_init();
#include <stdint.h> #include <stdint.h>
#include <stdarg.h> #include <stdarg.h>
#include <algorithm> #include <algorithm>
@@ -47,12 +45,9 @@ extern "C" volatile uint32_t _millis;
#include <pinmapping.h> #include <pinmapping.h>
#include <CDCSerial.h> #include <CDCSerial.h>
// // ------------------------
// Default graphical display delays // Serial ports
// // ------------------------
#define CPU_ST7920_DELAY_1 600
#define CPU_ST7920_DELAY_2 750
#define CPU_ST7920_DELAY_3 750
typedef ForwardSerial1Class< decltype(UsbSerial) > DefaultSerial1; typedef ForwardSerial1Class< decltype(UsbSerial) > DefaultSerial1;
extern DefaultSerial1 USBSerial; extern DefaultSerial1 USBSerial;
@@ -114,26 +109,12 @@ extern DefaultSerial1 USBSerial;
// //
// Interrupts // Interrupts
// //
#define CRITICAL_SECTION_START() uint32_t primask = __get_PRIMASK(); __disable_irq()
#define CRITICAL_SECTION_END() if (!primask) __enable_irq() #define CRITICAL_SECTION_START() const bool irqon = !__get_PRIMASK(); __disable_irq()
#define ISRS_ENABLED() (!__get_PRIMASK()) #define CRITICAL_SECTION_END() if (irqon) __enable_irq()
#define ENABLE_ISRS() __enable_irq()
#define DISABLE_ISRS() __disable_irq()
// //
// Utility functions // ADC
//
#pragma GCC diagnostic push
#if GCC_VERSION <= 50000
#pragma GCC diagnostic ignored "-Wunused-function"
#endif
int freeMemory();
#pragma GCC diagnostic pop
//
// ADC API
// //
#define ADC_MEDIAN_FILTER_SIZE (23) // Higher values increase step delay (phase shift), #define ADC_MEDIAN_FILTER_SIZE (23) // Higher values increase step delay (phase shift),
@@ -152,20 +133,11 @@ int freeMemory();
#define HAL_ADC_RESOLUTION 12 // 15 bit maximum, raw temperature is stored as int16_t #define HAL_ADC_RESOLUTION 12 // 15 bit maximum, raw temperature is stored as int16_t
#define HAL_ADC_FILTERED // Disable oversampling done in Marlin as ADC values already filtered in HAL #define HAL_ADC_FILTERED // Disable oversampling done in Marlin as ADC values already filtered in HAL
using FilteredADC = LPC176x::ADC<ADC_LOWPASS_K_VALUE, ADC_MEDIAN_FILTER_SIZE>; #define HAL_ANALOG_SELECT(pin) hal.adc_enable(pin)
extern uint32_t HAL_adc_reading;
[[gnu::always_inline]] inline void HAL_adc_start_conversion(const pin_t pin) {
HAL_adc_reading = FilteredADC::read(pin) >> (16 - HAL_ADC_RESOLUTION); // returns 16bit value, reduce to required bits
}
[[gnu::always_inline]] inline uint16_t HAL_adc_get_result() {
return HAL_adc_reading;
}
#define HAL_adc_init() //
#define HAL_ANALOG_SELECT(pin) FilteredADC::enable_channel(pin) // Pin Mapping for M42, M43, M226
#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) //
#define HAL_READ_ADC() HAL_adc_get_result()
#define HAL_ADC_READY() (true)
// Test whether the pin is valid // Test whether the pin is valid
constexpr bool VALID_PIN(const pin_t pin) { constexpr bool VALID_PIN(const pin_t pin) {
@@ -192,32 +164,104 @@ int16_t PARSED_PIN_INDEX(const char code, const int16_t dval);
// P0.6 thru P0.9 are for the onboard SD card // P0.6 thru P0.9 are for the onboard SD card
#define HAL_SENSITIVE_PINS P0_06, P0_07, P0_08, P0_09, #define HAL_SENSITIVE_PINS P0_06, P0_07, P0_08, P0_09,
#define HAL_IDLETASK 1 // ------------------------
void HAL_idletask(); // Defines
// ------------------------
#define PLATFORM_M997_SUPPORT #define PLATFORM_M997_SUPPORT
void flashFirmware(const int16_t); void flashFirmware(const int16_t);
#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment #define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment
// Default graphical display delays
#define CPU_ST7920_DELAY_1 600
#define CPU_ST7920_DELAY_2 750
#define CPU_ST7920_DELAY_3 750
// ------------------------
// Class Utilities
// ------------------------
#pragma GCC diagnostic push
#if GCC_VERSION <= 50000
#pragma GCC diagnostic ignored "-Wunused-function"
#endif
int freeMemory();
#pragma GCC diagnostic pop
// ------------------------
// MarlinHAL Class
// ------------------------
class MarlinHAL {
public:
// Earliest possible init, before setup()
MarlinHAL() {}
static void init(); // Called early in setup()
static inline void init_board() {} // Called less early in setup()
static void reboot(); // Restart the firmware from 0x0
static inline bool isr_state() { return !__get_PRIMASK(); }
static inline void isr_on() { __enable_irq(); }
static inline void isr_off() { __disable_irq(); }
static inline void delay_ms(const int ms) { _delay_ms(ms); }
// Tasks, called from idle()
static void idletask();
// Reset
static uint8_t get_reset_source();
static void clear_reset_source();
// Free SRAM
static inline int freeMemory() { return freeMemory(); }
//
// ADC Methods
//
using FilteredADC = LPC176x::ADC<ADC_LOWPASS_K_VALUE, ADC_MEDIAN_FILTER_SIZE>;
// Called by Temperature::init once at startup
static inline void adc_init() {}
// Called by Temperature::init for each sensor at startup
static inline void adc_enable(const pin_t pin) {
FilteredADC::enable_channel(pin);
}
// Begin ADC sampling on the given pin
static uint32_t adc_result;
FORCE_INLINE static void adc_start(const pin_t pin) {
adc_result = FilteredADC::read(pin) >> (16 - HAL_ADC_RESOLUTION); // returns 16bit value, reduce to required bits
}
// Is the ADC ready for reading?
static inline bool adc_ready() { return true; }
// The current value of the ADC register
FORCE_INLINE static uint16_t adc_value() {
return (uint16_t)adc_result;
}
/**
* Set the PWM duty cycle for the pin to the given value.
* Optionally invert the duty cycle [default = false]
* Optionally change the scale of the provided value to enable finer PWM duty control [default = 255]
*/
static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false);
/** /**
* set_pwm_frequency
* Set the frequency of the timer corresponding to the provided pin * Set the frequency of the timer corresponding to the provided pin
* All Hardware PWM pins run at the same frequency and all * All Hardware PWM pins will run at the same frequency and
* Software PWM pins run at the same frequency * All Software PWM pins will run at the same frequency
*/ */
void set_pwm_frequency(const pin_t pin, int f_desired); static void set_pwm_frequency(const pin_t pin, int f_desired);
};
/** extern MarlinHAL hal;
* set_pwm_duty
* Set the PWM duty cycle of the provided pin to the provided value
* Optionally allows inverting the duty cycle [default = false]
* Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255]
*/
void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false);
// Reset source
void HAL_clear_reset_source(void);
uint8_t HAL_get_reset_source(void);
void HAL_reboot();

View File

@@ -65,4 +65,5 @@ class libServo: public Servo {
} }
}; };
#define HAL_SERVO_LIB libServo class libServo;
typedef libServo hal_servo_t;

View File

@@ -21,21 +21,17 @@
*/ */
#ifdef TARGET_LPC1768 #ifdef TARGET_LPC1768
#include "../../inc/MarlinConfigPre.h" #include "../../inc/MarlinConfig.h"
#include <pwm.h> #include <pwm.h>
void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) {
if (!LPC176x::pin_is_valid(pin)) return; if (!LPC176x::pin_is_valid(pin)) return;
if (LPC176x::pwm_attach_pin(pin)) if (LPC176x::pwm_attach_pin(pin))
LPC176x::pwm_write_ratio(pin, invert ? 1.0f - (float)v / v_size : (float)v / v_size); // map 1-254 onto PWM range LPC176x::pwm_write_ratio(pin, invert ? 1.0f - (float)v / v_size : (float)v / v_size); // map 1-254 onto PWM range
} }
#if NEEDS_HARDWARE_PWM // Specific meta-flag for features that mandate PWM void MarlinHAL::set_pwm_frequency(const pin_t pin, int f_desired) {
void set_pwm_frequency(const pin_t pin, int f_desired) {
LPC176x::pwm_set_frequency(pin, f_desired); LPC176x::pwm_set_frequency(pin, f_desired);
} }
#endif
#endif // TARGET_LPC1768 #endif // TARGET_LPC1768

View File

@@ -48,7 +48,7 @@ void SysTick_Callback() { disk_timerproc(); }
TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial()); TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial());
void HAL_init() { void MarlinHAL::init() {
// Init LEDs // Init LEDs
#if PIN_EXISTS(LED) #if PIN_EXISTS(LED)
@@ -130,7 +130,7 @@ void HAL_init() {
const millis_t usb_timeout = millis() + 2000; const millis_t usb_timeout = millis() + 2000;
while (!USB_Configuration && PENDING(millis(), usb_timeout)) { while (!USB_Configuration && PENDING(millis(), usb_timeout)) {
delay(50); delay(50);
HAL_idletask(); idletask();
#if PIN_EXISTS(LED) #if PIN_EXISTS(LED)
TOGGLE(LED_PIN); // Flash quickly during USB initialization TOGGLE(LED_PIN); // Flash quickly during USB initialization
#endif #endif
@@ -142,7 +142,7 @@ void HAL_init() {
} }
// HAL idle task // HAL idle task
void HAL_idletask() { void MarlinHAL::idletask() {
#if HAS_SHARED_MEDIA #if HAS_SHARED_MEDIA
// If Marlin is using the SD card we need to lock it to prevent access from // If Marlin is using the SD card we need to lock it to prevent access from
// a PC via USB. // a PC via USB.

View File

@@ -170,4 +170,4 @@ FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) {
} }
} }
#define HAL_timer_isr_epilogue(T) #define HAL_timer_isr_epilogue(T) NOOP

View File

@@ -21,18 +21,10 @@
*/ */
#pragma once #pragma once
#define CPU_32_BIT
#define HAL_IDLETASK
void HAL_idletask();
#define F_CPU 100000000
#define SystemCoreClock F_CPU
#include <stdint.h> #include <stdint.h>
#include <stdarg.h> #include <stdarg.h>
#undef min #undef min
#undef max #undef max
#include <algorithm> #include <algorithm>
#include "pinmapping.h" #include "pinmapping.h"
@@ -40,8 +32,6 @@ void _printf (const char *format, ...);
void _putc(uint8_t c); void _putc(uint8_t c);
uint8_t _getc(); uint8_t _getc();
//extern "C" volatile uint32_t _millis;
//arduino: Print.h //arduino: Print.h
#define DEC 10 #define DEC 10
#define HEX 16 #define HEX 16
@@ -58,7 +48,23 @@ uint8_t _getc();
#include "watchdog.h" #include "watchdog.h"
#include "serial.h" #include "serial.h"
#define SHARED_SERVOS HAS_SERVOS // ------------------------
// Defines
// ------------------------
#define CPU_32_BIT
#define SHARED_SERVOS HAS_SERVOS // Use shared/servos.cpp
#define F_CPU 100000000
#define SystemCoreClock F_CPU
#define CPU_ST7920_DELAY_1 600
#define CPU_ST7920_DELAY_2 750
#define CPU_ST7920_DELAY_3 750
// ------------------------
// Serial ports
// ------------------------
extern MSerialT serial_stream_0; extern MSerialT serial_stream_0;
extern MSerialT serial_stream_1; extern MSerialT serial_stream_1;
@@ -98,49 +104,20 @@ extern MSerialT serial_stream_3;
#endif #endif
#endif #endif
// ------------------------
#define CPU_ST7920_DELAY_1 600
#define CPU_ST7920_DELAY_2 750
#define CPU_ST7920_DELAY_3 750
//
// Interrupts // Interrupts
// // ------------------------
#define CRITICAL_SECTION_START() #define CRITICAL_SECTION_START()
#define CRITICAL_SECTION_END() #define CRITICAL_SECTION_END()
#define ISRS_ENABLED()
#define ENABLE_ISRS()
#define DISABLE_ISRS()
inline void HAL_init() {}
// Utility functions
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-function"
int freeMemory();
#pragma GCC diagnostic pop
// ------------------------
// ADC // ADC
// ------------------------
#define HAL_ADC_VREF 5.0 #define HAL_ADC_VREF 5.0
#define HAL_ADC_RESOLUTION 10 #define HAL_ADC_RESOLUTION 10
#define HAL_ANALOG_SELECT(ch) HAL_adc_enable_channel(ch) #define HAL_ANALOG_SELECT(ch) hal.adc_enable(ch)
#define HAL_START_ADC(ch) HAL_adc_start_conversion(ch)
#define HAL_READ_ADC() HAL_adc_get_result()
#define HAL_ADC_READY() true
void HAL_adc_init();
void HAL_adc_enable_channel(const uint8_t ch);
void HAL_adc_start_conversion(const uint8_t ch);
uint16_t HAL_adc_get_result();
// PWM
inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); }
// Reset source
inline void HAL_clear_reset_source(void) {}
inline uint8_t HAL_get_reset_source(void) { return RST_POWER_ON; }
void HAL_reboot();
/* ---------------- Delay in cycles */ /* ---------------- Delay in cycles */
@@ -159,29 +136,22 @@ constexpr inline std::size_t strlen_constexpr(const char* str) {
// https://github.com/gcc-mirror/gcc/blob/5c7634a0e5f202935aa6c11b6ea953b8bf80a00a/libstdc%2B%2B-v3/include/bits/char_traits.h#L329 // https://github.com/gcc-mirror/gcc/blob/5c7634a0e5f202935aa6c11b6ea953b8bf80a00a/libstdc%2B%2B-v3/include/bits/char_traits.h#L329
if (str != nullptr) { if (str != nullptr) {
std::size_t i = 0; std::size_t i = 0;
while (str[i] != '\0') { while (str[i] != '\0') ++i;
++i;
}
return i; return i;
} }
return 0; return 0;
} }
constexpr inline int strncmp_constexpr(const char* lhs, const char* rhs, std::size_t count) { constexpr inline int strncmp_constexpr(const char* lhs, const char* rhs, std::size_t count) {
// https://github.com/gcc-mirror/gcc/blob/13b9cbfc32fe3ac4c81c4dd9c42d141c8fb95db4/libstdc%2B%2B-v3/include/bits/char_traits.h#L655 // https://github.com/gcc-mirror/gcc/blob/13b9cbfc32fe3ac4c81c4dd9c42d141c8fb95db4/libstdc%2B%2B-v3/include/bits/char_traits.h#L655
if (lhs == nullptr || rhs == nullptr) { if (lhs == nullptr || rhs == nullptr)
return rhs != nullptr ? -1 : 1; return rhs != nullptr ? -1 : 1;
}
for (std::size_t i = 0; i < count; ++i) { for (std::size_t i = 0; i < count; ++i)
if (lhs[i] != rhs[i]) { if (lhs[i] != rhs[i]) {
return lhs[i] < rhs[i] ? -1 : 1; return lhs[i] < rhs[i] ? -1 : 1;
} else if (lhs[i] == '\0') { else if (lhs[i] == '\0')
return 0; return 0;
}
}
return 0; return 0;
} }
@@ -193,14 +163,11 @@ constexpr inline const char* strstr_constexpr(const char* str, const char* targe
do { do {
char sc = {}; char sc = {};
do { do {
if ((sc = *str++) == '\0') { if ((sc = *str++) == '\0') return nullptr;
return nullptr;
}
} while (sc != c); } while (sc != c);
} while (strncmp_constexpr(str, target, len) != 0); } while (strncmp_constexpr(str, target, len) != 0);
--str; --str;
} }
return str; return str;
} }
@@ -211,12 +178,88 @@ constexpr inline char* strstr_constexpr(char* str, const char* target) {
do { do {
char sc = {}; char sc = {};
do { do {
if ((sc = *str++) == '\0') { if ((sc = *str++) == '\0') return nullptr;
return nullptr;
}
} while (sc != c); } while (sc != c);
} while (strncmp_constexpr(str, target, len) != 0); } while (strncmp_constexpr(str, target, len) != 0);
--str; --str;
} }
return str; return str;
} }
// ------------------------
// Class Utilities
// ------------------------
#pragma GCC diagnostic push
#if GCC_VERSION <= 50000
#pragma GCC diagnostic ignored "-Wunused-function"
#endif
int freeMemory();
#pragma GCC diagnostic pop
// ------------------------
// MarlinHAL Class
// ------------------------
class MarlinHAL {
public:
// Earliest possible init, before setup()
MarlinHAL() {}
static inline void init() {} // Called early in setup()
static inline void init_board() {} // Called less early in setup()
static void reboot(); // Restart the firmware from 0x0
static inline bool isr_state() { return true; }
static inline void isr_on() {}
static inline void isr_off() {}
static inline void delay_ms(const int ms) { _delay_ms(ms); }
// Tasks, called from idle()
static void idletask();
// Reset
static constexpr uint8_t reset_reason = RST_POWER_ON;
static inline uint8_t get_reset_source() { return reset_reason; }
static inline void clear_reset_source() {}
// Free SRAM
static inline int freeMemory() { return freeMemory(); }
//
// ADC Methods
//
static uint8_t active_ch;
// Called by Temperature::init once at startup
static void adc_init();
// Called by Temperature::init for each sensor at startup
static void adc_enable(const uint8_t ch);
// Begin ADC sampling on the given channel
static void adc_start(const uint8_t ch);
// Is the ADC ready for reading?
static bool adc_ready();
// The current value of the ADC register
static uint16_t adc_value();
/**
* Set the PWM duty cycle for the pin to the given value.
* No option to invert the duty cycle [default = false]
* No option to change the scale of the provided value to enable finer PWM duty control [default = 255]
*/
static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) {
analogWrite(pin, v);
}
};
extern MarlinHAL hal;

View File

@@ -87,5 +87,5 @@ void HAL_timer_enable_interrupt(const uint8_t timer_num);
void HAL_timer_disable_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); bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
#define HAL_timer_isr_prologue(T) #define HAL_timer_isr_prologue(T) NOOP
#define HAL_timer_isr_epilogue(T) #define HAL_timer_isr_epilogue(T) NOOP

View File

@@ -106,7 +106,7 @@
// Private Variables // Private Variables
// ------------------------ // ------------------------
uint16_t HAL_adc_result; uint16_t MarlinHAL::adc_result;
#if ADC_IS_REQUIRED #if ADC_IS_REQUIRED
@@ -402,7 +402,7 @@ uint16_t HAL_adc_result;
// ------------------------ // ------------------------
// HAL initialization task // HAL initialization task
void HAL_init() { void MarlinHAL::init() {
TERN_(DMA_IS_REQUIRED, dma_init()); TERN_(DMA_IS_REQUIRED, dma_init());
#if ENABLED(SDSUPPORT) #if ENABLED(SDSUPPORT)
#if SD_CONNECTION_IS(ONBOARD) && PIN_EXISTS(SD_DETECT) #if SD_CONNECTION_IS(ONBOARD) && PIN_EXISTS(SD_DETECT)
@@ -412,17 +412,9 @@ void HAL_init() {
#endif #endif
} }
// HAL idle task
/*
void HAL_idletask() {
}
*/
void HAL_clear_reset_source() { }
#pragma push_macro("WDT") #pragma push_macro("WDT")
#undef WDT // Required to be able to use '.bit.WDT'. Compiler wrongly replace struct field with WDT define #undef WDT // Required to be able to use '.bit.WDT'. Compiler wrongly replace struct field with WDT define
uint8_t HAL_get_reset_source() { uint8_t MarlinHAL::get_reset_source() {
RSTC_RCAUSE_Type resetCause; RSTC_RCAUSE_Type resetCause;
resetCause.reg = REG_RSTC_RCAUSE; resetCause.reg = REG_RSTC_RCAUSE;
@@ -436,7 +428,7 @@ uint8_t HAL_get_reset_source() {
} }
#pragma pop_macro("WDT") #pragma pop_macro("WDT")
void HAL_reboot() { NVIC_SystemReset(); } void MarlinHAL::reboot() { NVIC_SystemReset(); }
extern "C" { extern "C" {
void * _sbrk(int incr); void * _sbrk(int incr);
@@ -454,7 +446,7 @@ int freeMemory() {
// ADC // ADC
// ------------------------ // ------------------------
void HAL_adc_init() { void MarlinHAL::adc_init() {
#if ADC_IS_REQUIRED #if ADC_IS_REQUIRED
memset(HAL_adc_results, 0xFF, sizeof(HAL_adc_results)); // Fill result with invalid values memset(HAL_adc_results, 0xFF, sizeof(HAL_adc_results)); // Fill result with invalid values
@@ -491,17 +483,17 @@ void HAL_adc_init() {
#endif // ADC_IS_REQUIRED #endif // ADC_IS_REQUIRED
} }
void HAL_adc_start_conversion(const uint8_t adc_pin) { void MarlinHAL::adc_start(const pin_t pin) {
#if ADC_IS_REQUIRED #if ADC_IS_REQUIRED
LOOP_L_N(pi, COUNT(adc_pins)) { LOOP_L_N(pi, COUNT(adc_pins)) {
if (adc_pin == adc_pins[pi]) { if (pin == adc_pins[pi]) {
HAL_adc_result = HAL_adc_results[pi]; adc_result = HAL_adc_results[pi];
return; return;
} }
} }
#endif #endif
HAL_adc_result = 0xFFFF; adc_result = 0xFFFF;
} }
#endif // __SAMD51__ #endif // __SAMD51__

View File

@@ -89,51 +89,31 @@
typedef int8_t pin_t; typedef int8_t pin_t;
#define SHARED_SERVOS HAS_SERVOS #define SHARED_SERVOS HAS_SERVOS // Use shared/servos.cpp
#define HAL_SERVO_LIB Servo class Servo;
typedef Servo hal_servo_t;
// //
// Interrupts // Interrupts
// //
#define CRITICAL_SECTION_START() uint32_t primask = __get_PRIMASK(); __disable_irq() #define CRITICAL_SECTION_START() const bool irqon = !__get_PRIMASK(); __disable_irq()
#define CRITICAL_SECTION_END() if (!primask) __enable_irq() #define CRITICAL_SECTION_END() if (irqon) __enable_irq()
#define ISRS_ENABLED() (!__get_PRIMASK())
#define ENABLE_ISRS() __enable_irq()
#define DISABLE_ISRS() __disable_irq()
#define cli() __disable_irq() // Disable interrupts #define cli() __disable_irq() // Disable interrupts
#define sei() __enable_irq() // Enable interrupts #define sei() __enable_irq() // Enable interrupts
void HAL_clear_reset_source(); // clear reset reason
uint8_t HAL_get_reset_source(); // get reset reason
void HAL_reboot();
// //
// ADC // ADC
// //
extern uint16_t HAL_adc_result; // Most recent ADC conversion
#define HAL_ANALOG_SELECT(pin) #define HAL_ANALOG_SELECT(pin)
void HAL_adc_init();
//#define HAL_ADC_FILTERED // Disable Marlin's oversampling. The HAL filters ADC values. //#define HAL_ADC_FILTERED // Disable Marlin's oversampling. The HAL filters ADC values.
#define HAL_ADC_VREF 3.3 #define HAL_ADC_VREF 3.3
#define HAL_ADC_RESOLUTION 10 // ... 12 #define HAL_ADC_RESOLUTION 10 // ... 12
#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin)
#define HAL_READ_ADC() HAL_adc_result
#define HAL_ADC_READY() true
void HAL_adc_start_conversion(const uint8_t adc_pin);
// //
// PWM // Pin Mapping for M42, M43, M226
//
inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); }
//
// Pin Map
// //
#define GET_PIN_MAP_PIN(index) index #define GET_PIN_MAP_PIN(index) index
#define GET_PIN_MAP_INDEX(pin) pin #define GET_PIN_MAP_INDEX(pin) pin
@@ -142,35 +122,92 @@ inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255,
// //
// Tone // Tone
// //
void toneInit();
void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration=0); void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration=0);
void noTone(const pin_t _pin); void noTone(const pin_t _pin);
// Enable hooks into idle and setup for HAL // ------------------------
void HAL_init(); // Class Utilities
/* // ------------------------
#define HAL_IDLETASK 1
void HAL_idletask();
*/
//
// Utility functions
//
FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); }
#pragma GCC diagnostic push #pragma GCC diagnostic push
#if GCC_VERSION <= 50000 #if GCC_VERSION <= 50000
#pragma GCC diagnostic ignored "-Wunused-function" #pragma GCC diagnostic ignored "-Wunused-function"
#endif #endif
int freeMemory();
#pragma GCC diagnostic pop
#ifdef __cplusplus #ifdef __cplusplus
extern "C" { extern "C" {
#endif #endif
char *dtostrf(double __val, signed char __width, unsigned char __prec, char *__s); char *dtostrf(double __val, signed char __width, unsigned char __prec, char *__s);
extern "C" int freeMemory();
#ifdef __cplusplus #ifdef __cplusplus
} }
#endif #endif
#pragma GCC diagnostic pop
// ------------------------
// MarlinHAL Class
// ------------------------
class MarlinHAL {
public:
// Earliest possible init, before setup()
MarlinHAL() {}
static void init(); // Called early in setup()
static inline void init_board() {} // Called less early in setup()
static void reboot(); // Restart the firmware from 0x0
static inline bool isr_state() { return !__get_PRIMASK(); }
static inline void isr_on() { sei(); }
static inline void isr_off() { cli(); }
static inline void delay_ms(const int ms) { delay(ms); }
// Tasks, called from idle()
static inline void idletask() {}
// Reset
static uint8_t get_reset_source();
static inline void clear_reset_source() {}
// Free SRAM
static inline int freeMemory() { return freeMemory(); }
//
// ADC Methods
//
static uint16_t adc_result;
// Called by Temperature::init once at startup
static void adc_init();
// Called by Temperature::init for each sensor at startup
static void adc_enable(const uint8_t ch);
// Begin ADC sampling on the given channel
static void adc_start(const pin_t pin);
// Is the ADC ready for reading?
static inline bool adc_ready() { return true; }
// The current value of the ADC register
static uint16_t adc_value() { return adc_result; }
/**
* Set the PWM duty cycle for the pin to the given value.
* No option to invert the duty cycle [default = false]
* No option to change the scale of the provided value to enable finer PWM duty control [default = 255]
*/
static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false) {
analogWrite(pin, v);
}
};
extern MarlinHAL hal;

View File

@@ -53,16 +53,18 @@
// Public Variables // Public Variables
// ------------------------ // ------------------------
uint16_t HAL_adc_result; uint16_t MarlinHAL::adc_result;
// ------------------------ // ------------------------
// Public functions // Public functions
// ------------------------ // ------------------------
TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial()); #if ENABLED(POSTMORTEM_DEBUGGING)
extern void install_min_serial();
#endif
// HAL initialization task // HAL initialization task
void HAL_init() { void MarlinHAL::init() {
// Ensure F_CPU is a constant expression. // Ensure F_CPU is a constant expression.
// If the compiler breaks here, it means that delay code that should compute at compile time will not work. // If the compiler breaks here, it means that delay code that should compute at compile time will not work.
// So better safe than sorry here. // So better safe than sorry here.
@@ -103,7 +105,7 @@ void HAL_init() {
} }
// HAL idle task // HAL idle task
void HAL_idletask() { void MarlinHAL::idletask() {
#if HAS_SHARED_MEDIA #if HAS_SHARED_MEDIA
// Stm32duino currently doesn't have a "loop/idle" method // Stm32duino currently doesn't have a "loop/idle" method
CDC_resume_receive(); CDC_resume_receive();
@@ -111,9 +113,9 @@ void HAL_idletask() {
#endif #endif
} }
void HAL_clear_reset_source() { __HAL_RCC_CLEAR_RESET_FLAGS(); } void MarlinHAL::reboot() { NVIC_SystemReset(); }
uint8_t HAL_get_reset_source() { uint8_t MarlinHAL::get_reset_source() {
return return
#ifdef RCC_FLAG_IWDGRST // Some sources may not exist... #ifdef RCC_FLAG_IWDGRST // Some sources may not exist...
RESET != __HAL_RCC_GET_FLAG(RCC_FLAG_IWDGRST) ? RST_WATCHDOG : RESET != __HAL_RCC_GET_FLAG(RCC_FLAG_IWDGRST) ? RST_WATCHDOG :
@@ -137,24 +139,14 @@ uint8_t HAL_get_reset_source() {
; ;
} }
void HAL_reboot() { NVIC_SystemReset(); } void MarlinHAL::clear_reset_source() { __HAL_RCC_CLEAR_RESET_FLAGS(); }
void _delay_ms(const int delay_ms) { delay(delay_ms); }
extern "C" { extern "C" {
extern unsigned int _ebss; // end of bss section extern unsigned int _ebss; // end of bss section
} }
// ------------------------
// ADC
// ------------------------
// TODO: Make sure this doesn't cause any delay
void HAL_adc_start_conversion(const uint8_t adc_pin) { HAL_adc_result = analogRead(adc_pin); }
uint16_t HAL_adc_get_result() { return HAL_adc_result; }
// Reset the system to initiate a firmware flash // Reset the system to initiate a firmware flash
WEAK void flashFirmware(const int16_t) { HAL_reboot(); } WEAK void flashFirmware(const int16_t) { hal.reboot(); }
// Maple Compatibility // Maple Compatibility
volatile uint32_t systick_uptime_millis = 0; volatile uint32_t systick_uptime_millis = 0;

View File

@@ -44,9 +44,9 @@
#define CPU_ST7920_DELAY_2 40 #define CPU_ST7920_DELAY_2 40
#define CPU_ST7920_DELAY_3 340 #define CPU_ST7920_DELAY_3 340
// // ------------------------
// Serial Ports // Serial ports
// // ------------------------
#ifdef USBCON #ifdef USBCON
#include <USBSerial.h> #include <USBSerial.h>
#include "../../core/serial_hook.h" #include "../../core/serial_hook.h"
@@ -115,17 +115,14 @@
#define analogInputToDigitalPin(p) (p) #define analogInputToDigitalPin(p) (p)
#endif #endif
#define CRITICAL_SECTION_START() uint32_t primask = __get_PRIMASK(); __disable_irq() //
#define CRITICAL_SECTION_END() if (!primask) __enable_irq() // Interrupts
#define ISRS_ENABLED() (!__get_PRIMASK()) //
#define ENABLE_ISRS() __enable_irq() #define CRITICAL_SECTION_START() const bool irqon = !__get_PRIMASK(); __disable_irq()
#define DISABLE_ISRS() __disable_irq() #define CRITICAL_SECTION_END() if (irqon) __enable_irq()
#define cli() __disable_irq() #define cli() __disable_irq()
#define sei() __enable_irq() #define sei() __enable_irq()
// On AVR this is in math.h?
#define square(x) ((x)*(x))
// ------------------------ // ------------------------
// Types // Types
// ------------------------ // ------------------------
@@ -136,54 +133,14 @@
typedef int16_t pin_t; typedef int16_t pin_t;
#endif #endif
#define HAL_SERVO_LIB libServo class libServo;
typedef libServo hal_servo_t;
#define PAUSE_SERVO_OUTPUT() libServo::pause_all_servos() #define PAUSE_SERVO_OUTPUT() libServo::pause_all_servos()
#define RESUME_SERVO_OUTPUT() libServo::resume_all_servos() #define RESUME_SERVO_OUTPUT() libServo::resume_all_servos()
// ------------------------ // ------------------------
// Public Variables
// ------------------------
// result of last ADC conversion
extern uint16_t HAL_adc_result;
// ------------------------
// Public functions
// ------------------------
// Memory related
#define __bss_end __bss_end__
// Enable hooks into setup for HAL
void HAL_init();
#define HAL_IDLETASK 1
void HAL_idletask();
// Clear reset reason
void HAL_clear_reset_source();
// Reset reason
uint8_t HAL_get_reset_source();
void HAL_reboot();
void _delay_ms(const int delay);
extern "C" char* _sbrk(int incr);
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-function"
static inline int freeMemory() {
volatile char top;
return &top - reinterpret_cast<char*>(_sbrk(0));
}
#pragma GCC diagnostic pop
//
// ADC // ADC
// // ------------------------
#define HAL_ANALOG_SELECT(pin) pinMode(pin, INPUT) #define HAL_ANALOG_SELECT(pin) pinMode(pin, INPUT)
@@ -194,16 +151,10 @@ static inline int freeMemory() {
#endif #endif
#define HAL_ADC_VREF 3.3 #define HAL_ADC_VREF 3.3
#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin)
#define HAL_READ_ADC() HAL_adc_result
#define HAL_ADC_READY() true
inline void HAL_adc_init() { analogReadResolution(HAL_ADC_RESOLUTION); }
void HAL_adc_start_conversion(const uint8_t adc_pin);
uint16_t HAL_adc_get_result();
//
// Pin Mapping for M42, M43, M226
//
#define GET_PIN_MAP_PIN(index) index #define GET_PIN_MAP_PIN(index) index
#define GET_PIN_MAP_INDEX(pin) pin #define GET_PIN_MAP_INDEX(pin) pin
#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) #define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
@@ -226,17 +177,93 @@ extern volatile uint32_t systick_uptime_millis;
#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment #define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment
/** // ------------------------
* set_pwm_frequency // Class Utilities
* Set the frequency of the timer corresponding to the provided pin // ------------------------
* All Timer PWM pins run at the same frequency
*/ // Memory related
void set_pwm_frequency(const pin_t pin, int f_desired); #define __bss_end __bss_end__
extern "C" char* _sbrk(int incr);
#pragma GCC diagnostic push
#if GCC_VERSION <= 50000
#pragma GCC diagnostic ignored "-Wunused-function"
#endif
static inline int freeMemory() {
volatile char top;
return &top - reinterpret_cast<char*>(_sbrk(0));
}
#pragma GCC diagnostic pop
// ------------------------
// MarlinHAL Class
// ------------------------
class MarlinHAL {
public:
// Earliest possible init, before setup()
MarlinHAL() {}
static void init(); // Called early in setup()
static inline void init_board() {} // Called less early in setup()
static void reboot(); // Restart the firmware from 0x0
static inline bool isr_state() { return !__get_PRIMASK(); }
static inline void isr_on() { sei(); }
static inline void isr_off() { cli(); }
static inline void delay_ms(const int ms) { delay(ms); }
// Tasks, called from idle()
static void idletask();
// Reset
static uint8_t get_reset_source();
static void clear_reset_source();
// Free SRAM
static inline int freeMemory() { return freeMemory(); }
//
// ADC Methods
//
static uint16_t adc_result;
// Called by Temperature::init once at startup
static inline void adc_init() {
analogReadResolution(HAL_ADC_RESOLUTION);
}
// Called by Temperature::init for each sensor at startup
static void adc_enable(const pin_t pin);
// Begin ADC sampling on the given channel
static void adc_start(const pin_t pin) { adc_result = analogRead(pin); }
// Is the ADC ready for reading?
static inline bool adc_ready() { return true; }
// The current value of the ADC register
static uint16_t adc_value() { return adc_result; }
/** /**
* set_pwm_duty * Set the PWM duty cycle for the pin to the given value.
* Set the PWM duty cycle of the provided pin to the provided value * Optionally invert the duty cycle [default = false]
* Optionally allows inverting the duty cycle [default = false] * Optionally change the maximum size of the provided value to enable finer PWM duty control [default = 255]
* Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255]
*/ */
void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false);
/**
* Set the frequency of the timer for the given pin.
* All Timer PWM pins run at the same frequency.
*/
static void set_pwm_frequency(const pin_t pin, int f_desired);
};
extern MarlinHAL hal;

View File

@@ -102,9 +102,9 @@ static SPISettings spiConfig;
// Soft SPI receive byte // Soft SPI receive byte
uint8_t spiRec() { uint8_t spiRec() {
DISABLE_ISRS(); // No interrupts during byte receive hal.isr_off(); // No interrupts during byte receive
const uint8_t data = HAL_SPI_STM32_SpiTransfer_Mode_3(0xFF); const uint8_t data = HAL_SPI_STM32_SpiTransfer_Mode_3(0xFF);
ENABLE_ISRS(); // Enable interrupts hal.isr_off(); // Enable interrupts
return data; return data;
} }
@@ -116,9 +116,9 @@ static SPISettings spiConfig;
// Soft SPI send byte // Soft SPI send byte
void spiSend(uint8_t data) { void spiSend(uint8_t data) {
DISABLE_ISRS(); // No interrupts during byte send hal.isr_off(); // No interrupts during byte send
HAL_SPI_STM32_SpiTransfer_Mode_3(data); // Don't care what is received HAL_SPI_STM32_SpiTransfer_Mode_3(data); // Don't care what is received
ENABLE_ISRS(); // Enable interrupts hal.isr_on(); // Enable interrupts
} }
// Soft SPI send block // Soft SPI send block

View File

@@ -174,9 +174,9 @@ bool PersistentStore::access_finish() {
UNLOCK_FLASH(); UNLOCK_FLASH();
TERN_(HAS_PAUSE_SERVO_OUTPUT, PAUSE_SERVO_OUTPUT()); TERN_(HAS_PAUSE_SERVO_OUTPUT, PAUSE_SERVO_OUTPUT());
DISABLE_ISRS(); hal.isr_off();
status = HAL_FLASHEx_Erase(&EraseInitStruct, &SectorError); status = HAL_FLASHEx_Erase(&EraseInitStruct, &SectorError);
ENABLE_ISRS(); hal.isr_on();
TERN_(HAS_PAUSE_SERVO_OUTPUT, RESUME_SERVO_OUTPUT()); TERN_(HAS_PAUSE_SERVO_OUTPUT, RESUME_SERVO_OUTPUT());
if (status != HAL_OK) { if (status != HAL_OK) {
DEBUG_ECHOLNPGM("HAL_FLASHEx_Erase=", status); DEBUG_ECHOLNPGM("HAL_FLASHEx_Erase=", status);
@@ -229,9 +229,9 @@ bool PersistentStore::access_finish() {
// output. Servo output still glitches with interrupts disabled, but recovers after the // output. Servo output still glitches with interrupts disabled, but recovers after the
// erase. // erase.
TERN_(HAS_PAUSE_SERVO_OUTPUT, PAUSE_SERVO_OUTPUT()); TERN_(HAS_PAUSE_SERVO_OUTPUT, PAUSE_SERVO_OUTPUT());
DISABLE_ISRS(); hal.isr_off();
eeprom_buffer_flush(); eeprom_buffer_flush();
ENABLE_ISRS(); hal.isr_on();
TERN_(HAS_PAUSE_SERVO_OUTPUT, RESUME_SERVO_OUTPUT()); TERN_(HAS_PAUSE_SERVO_OUTPUT, RESUME_SERVO_OUTPUT());
eeprom_data_written = false; eeprom_data_written = false;

View File

@@ -29,7 +29,7 @@
// Array to support sticky frequency sets per timer // Array to support sticky frequency sets per timer
static uint16_t timer_freq[TIMER_NUM]; static uint16_t timer_freq[TIMER_NUM];
void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) {
if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer
const PinName pin_name = digitalPinToPinName(pin); const PinName pin_name = digitalPinToPinName(pin);
TIM_TypeDef * const Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM); TIM_TypeDef * const Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM);
@@ -56,7 +56,7 @@ void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255
if (previousMode != TIMER_OUTPUT_COMPARE_PWM1) HT->resume(); if (previousMode != TIMER_OUTPUT_COMPARE_PWM1) HT->resume();
} }
void set_pwm_frequency(const pin_t pin, int f_desired) { void MarlinHAL::set_pwm_frequency(const pin_t pin, int f_desired) {
if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer
const PinName pin_name = digitalPinToPinName(pin); const PinName pin_name = digitalPinToPinName(pin);
TIM_TypeDef * const Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM); // Get HAL timer instance TIM_TypeDef * const Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM); // Get HAL timer instance

View File

@@ -115,7 +115,6 @@ const XrefInfo pin_xref[] PROGMEM = {
#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0) #define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0)
#define PRINT_PORT(ANUM) port_print(ANUM) #define PRINT_PORT(ANUM) port_print(ANUM)
#define DIGITAL_PIN_TO_ANALOG_PIN(ANUM) -1 // will report analog pin number in the print port routine #define DIGITAL_PIN_TO_ANALOG_PIN(ANUM) -1 // will report analog pin number in the print port routine
#define GET_PIN_MAP_PIN_M43(Index) pin_xref[Index].Ard_num
// x is a variable used to search pin_array // x is a variable used to search pin_array
#define GET_ARRAY_IS_DIGITAL(x) ((bool) pin_array[x].is_digital) #define GET_ARRAY_IS_DIGITAL(x) ((bool) pin_array[x].is_digital)
@@ -123,6 +122,11 @@ const XrefInfo pin_xref[] PROGMEM = {
#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_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
#define MULTI_NAME_PAD 33 // space needed to be pretty if not first name assigned to a pin #define MULTI_NAME_PAD 33 // space needed to be pretty if not first name assigned to a pin
//
// Pin Mapping for M43
//
#define GET_PIN_MAP_PIN_M43(Index) pin_xref[Index].Ard_num
#ifndef M43_NEVER_TOUCH #ifndef M43_NEVER_TOUCH
#define _M43_NEVER_TOUCH(Index) (Index >= 9 && Index <= 12) // SERIAL/USB pins: PA9(TX) PA10(RX) PA11(USB_DM) PA12(USB_DP) #define _M43_NEVER_TOUCH(Index) (Index >= 9 && Index <= 12) // SERIAL/USB pins: PA9(TX) PA10(RX) PA11(USB_DM) PA12(USB_DP)
#ifdef KILL_PIN #ifdef KILL_PIN

View File

@@ -116,5 +116,5 @@ FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const ha
} }
} }
#define HAL_timer_isr_prologue(T) #define HAL_timer_isr_prologue(T) NOOP
#define HAL_timer_isr_epilogue(T) #define HAL_timer_isr_epilogue(T) NOOP

View File

@@ -79,7 +79,7 @@
#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ #define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */
// ------------------------ // ------------------------
// Public Variables // Serial ports
// ------------------------ // ------------------------
#if defined(SERIAL_USB) && !HAS_SD_HOST_DRIVE #if defined(SERIAL_USB) && !HAS_SD_HOST_DRIVE
@@ -112,72 +112,21 @@
#endif #endif
#endif #endif
uint16_t HAL_adc_result;
// ------------------------ // ------------------------
// Private Variables // ADC
// ------------------------ // ------------------------
STM32ADC adc(ADC1);
const uint8_t adc_pins[] = { uint16_t analogRead(pin_t pin) {
#if HAS_TEMP_ADC_0 const bool is_analog = _GET_MODE(pin) == GPIO_INPUT_ANALOG;
TEMP_0_PIN, return is_analog ? analogRead(uint8_t(pin)) : 0;
#endif }
#if HAS_TEMP_ADC_PROBE
TEMP_PROBE_PIN, // Wrapper to maple unprotected analogWrite
#endif void analogWrite(pin_t pin, int pwm_val8) {
#if HAS_HEATED_BED if (PWM_PIN(pin)) analogWrite(uint8_t(pin), pwm_val8);
TEMP_BED_PIN, }
#endif
#if HAS_TEMP_CHAMBER uint16_t MarlinHAL::adc_result;
TEMP_CHAMBER_PIN,
#endif
#if HAS_TEMP_COOLER
TEMP_COOLER_PIN,
#endif
#if HAS_TEMP_ADC_1
TEMP_1_PIN,
#endif
#if HAS_TEMP_ADC_2
TEMP_2_PIN,
#endif
#if HAS_TEMP_ADC_3
TEMP_3_PIN,
#endif
#if HAS_TEMP_ADC_4
TEMP_4_PIN,
#endif
#if HAS_TEMP_ADC_5
TEMP_5_PIN,
#endif
#if HAS_TEMP_ADC_6
TEMP_6_PIN,
#endif
#if HAS_TEMP_ADC_7
TEMP_7_PIN,
#endif
#if ENABLED(FILAMENT_WIDTH_SENSOR)
FILWIDTH_PIN,
#endif
#if HAS_ADC_BUTTONS
ADC_KEYPAD_PIN,
#endif
#if HAS_JOY_ADC_X
JOY_X_PIN,
#endif
#if HAS_JOY_ADC_Y
JOY_Y_PIN,
#endif
#if HAS_JOY_ADC_Z
JOY_Z_PIN,
#endif
#if ENABLED(POWER_MONITOR_CURRENT)
POWER_MONITOR_CURRENT_PIN,
#endif
#if ENABLED(POWER_MONITOR_VOLTAGE)
POWER_MONITOR_VOLTAGE_PIN,
#endif
};
enum TempPinIndex : char { enum TempPinIndex : char {
#if HAS_TEMP_ADC_0 #if HAS_TEMP_ADC_0
@@ -245,15 +194,16 @@ uint16_t HAL_adc_results[ADC_PIN_COUNT];
// ------------------------ // ------------------------
// Private functions // Private functions
// ------------------------ // ------------------------
static void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) { static void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) {
uint32_t reg_value; uint32_t reg_value;
uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07); /* only values 0..7 are used */ uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07); // only values 0..7 are used
reg_value = SCB->AIRCR; /* read old register configuration */ reg_value = SCB->AIRCR; // read old register configuration
reg_value &= ~(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk); /* clear bits to change */ reg_value &= ~(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk); // clear bits to change
reg_value = (reg_value | reg_value = (reg_value |
((uint32_t)0x5FA << SCB_AIRCR_VECTKEY_Pos) | ((uint32_t)0x5FA << SCB_AIRCR_VECTKEY_Pos) |
(PriorityGroupTmp << 8)); /* Insert write key & priority group */ (PriorityGroupTmp << 8)); // Insert write key & priority group
SCB->AIRCR = reg_value; SCB->AIRCR = reg_value;
} }
@@ -261,6 +211,8 @@ static void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) {
// Public functions // Public functions
// ------------------------ // ------------------------
void flashFirmware(const int16_t) { hal.reboot(); }
// //
// Leave PA11/PA12 intact if USBSerial is not used // Leave PA11/PA12 intact if USBSerial is not used
// //
@@ -280,7 +232,11 @@ static void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) {
TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial()); TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial());
void HAL_init() { // ------------------------
// MarlinHAL class
// ------------------------
void MarlinHAL::init() {
NVIC_SetPriorityGrouping(0x3); NVIC_SetPriorityGrouping(0x3);
#if PIN_EXISTS(LED) #if PIN_EXISTS(LED)
OUT_WRITE(LED_PIN, LOW); OUT_WRITE(LED_PIN, LOW);
@@ -299,7 +255,7 @@ void HAL_init() {
} }
// HAL idle task // HAL idle task
void HAL_idletask() { void MarlinHAL::idletask() {
#if HAS_SHARED_MEDIA #if HAS_SHARED_MEDIA
// If Marlin is using the SD card we need to lock it to prevent access from // If Marlin is using the SD card we need to lock it to prevent access from
// a PC via USB. // a PC via USB.
@@ -314,14 +270,7 @@ void HAL_idletask() {
#endif #endif
} }
void HAL_clear_reset_source() { } void MarlinHAL::reboot() { nvic_sys_reset(); }
/**
* TODO: Check this and change or remove.
*/
uint8_t HAL_get_reset_source() { return RST_POWER_ON; }
void _delay_ms(const int delay_ms) { delay(delay_ms); }
extern "C" { extern "C" {
extern unsigned int _ebss; // end of bss section extern unsigned int _ebss; // end of bss section
@@ -355,11 +304,70 @@ extern "C" {
} }
*/ */
// ------------------------
// ADC // ADC
// ------------------------
// Init the AD in continuous capture mode // Init the AD in continuous capture mode
void HAL_adc_init() { void MarlinHAL::adc_init() {
static const uint8_t adc_pins[] = {
#if HAS_TEMP_ADC_0
TEMP_0_PIN,
#endif
#if HAS_TEMP_ADC_PROBE
TEMP_PROBE_PIN,
#endif
#if HAS_HEATED_BED
TEMP_BED_PIN,
#endif
#if HAS_TEMP_CHAMBER
TEMP_CHAMBER_PIN,
#endif
#if HAS_TEMP_COOLER
TEMP_COOLER_PIN,
#endif
#if HAS_TEMP_ADC_1
TEMP_1_PIN,
#endif
#if HAS_TEMP_ADC_2
TEMP_2_PIN,
#endif
#if HAS_TEMP_ADC_3
TEMP_3_PIN,
#endif
#if HAS_TEMP_ADC_4
TEMP_4_PIN,
#endif
#if HAS_TEMP_ADC_5
TEMP_5_PIN,
#endif
#if HAS_TEMP_ADC_6
TEMP_6_PIN,
#endif
#if HAS_TEMP_ADC_7
TEMP_7_PIN,
#endif
#if ENABLED(FILAMENT_WIDTH_SENSOR)
FILWIDTH_PIN,
#endif
#if HAS_ADC_BUTTONS
ADC_KEYPAD_PIN,
#endif
#if HAS_JOY_ADC_X
JOY_X_PIN,
#endif
#if HAS_JOY_ADC_Y
JOY_Y_PIN,
#endif
#if HAS_JOY_ADC_Z
JOY_Z_PIN,
#endif
#if ENABLED(POWER_MONITOR_CURRENT)
POWER_MONITOR_CURRENT_PIN,
#endif
#if ENABLED(POWER_MONITOR_VOLTAGE)
POWER_MONITOR_VOLTAGE_PIN,
#endif
};
static STM32ADC adc(ADC1);
// configure the ADC // configure the ADC
adc.calibrate(); adc.calibrate();
#if F_CPU > 72000000 #if F_CPU > 72000000
@@ -374,10 +382,10 @@ void HAL_adc_init() {
adc.startConversion(); adc.startConversion();
} }
void HAL_adc_start_conversion(const uint8_t adc_pin) { void MarlinHAL::adc_start(const pin_t pin) {
//TEMP_PINS pin_index; //TEMP_PINS pin_index;
TempPinIndex pin_index; TempPinIndex pin_index;
switch (adc_pin) { switch (pin) {
default: return; default: return;
#if HAS_TEMP_ADC_0 #if HAS_TEMP_ADC_0
case TEMP_0_PIN: pin_index = TEMP_0; break; case TEMP_0_PIN: pin_index = TEMP_0; break;
@@ -440,20 +448,4 @@ void HAL_adc_start_conversion(const uint8_t adc_pin) {
HAL_adc_result = HAL_adc_results[(int)pin_index] >> (12 - HAL_ADC_RESOLUTION); // shift out unused bits HAL_adc_result = HAL_adc_results[(int)pin_index] >> (12 - HAL_ADC_RESOLUTION); // shift out unused bits
} }
uint16_t HAL_adc_get_result() { return HAL_adc_result; }
uint16_t analogRead(pin_t pin) {
const bool is_analog = _GET_MODE(pin) == GPIO_INPUT_ANALOG;
return is_analog ? analogRead(uint8_t(pin)) : 0;
}
// Wrapper to maple unprotected analogWrite
void analogWrite(pin_t pin, int pwm_val8) {
if (PWM_PIN(pin)) analogWrite(uint8_t(pin), pwm_val8);
}
void HAL_reboot() { nvic_sys_reset(); }
void flashFirmware(const int16_t) { HAL_reboot(); }
#endif // __STM32F1__ #endif // __STM32F1__

View File

@@ -66,6 +66,10 @@
#endif #endif
#endif #endif
// ------------------------
// Serial ports
// ------------------------
#ifdef SERIAL_USB #ifdef SERIAL_USB
typedef ForwardSerial1Class< USBSerial > DefaultSerial1; typedef ForwardSerial1Class< USBSerial > DefaultSerial1;
extern DefaultSerial1 MSerial0; extern DefaultSerial1 MSerial0;
@@ -141,11 +145,6 @@
#endif #endif
#endif #endif
// Set interrupt grouping for this MCU
void HAL_init();
#define HAL_IDLETASK 1
void HAL_idletask();
/** /**
* TODO: review this to return 1 for pins that are not analog input * TODO: review this to return 1 for pins that are not analog input
*/ */
@@ -158,15 +157,7 @@ void HAL_idletask();
#define NO_COMPILE_TIME_PWM #define NO_COMPILE_TIME_PWM
#endif #endif
#define CRITICAL_SECTION_START() uint32_t primask = __get_primask(); (void)__iCliRetVal() // Reset Reason
#define CRITICAL_SECTION_END() if (!primask) (void)__iSeiRetVal()
#define ISRS_ENABLED() (!__get_primask())
#define ENABLE_ISRS() ((void)__iSeiRetVal())
#define DISABLE_ISRS() ((void)__iCliRetVal())
// On AVR this is in math.h?
#define square(x) ((x)*(x))
#define RST_POWER_ON 1 #define RST_POWER_ON 1
#define RST_EXTERNAL 2 #define RST_EXTERNAL 2
#define RST_BROWN_OUT 4 #define RST_BROWN_OUT 4
@@ -181,62 +172,24 @@ void HAL_idletask();
typedef int8_t pin_t; typedef int8_t pin_t;
// ------------------------
// Public Variables
// ------------------------
// Result of last ADC conversion // Result of last ADC conversion
extern uint16_t HAL_adc_result; extern uint16_t HAL_adc_result;
// ------------------------ // ------------------------
// Public functions // Interrupts
// ------------------------ // ------------------------
// Disable interrupts #define CRITICAL_SECTION_START() const bool irqon = !__get_primask(); (void)__iCliRetVal()
#define CRITICAL_SECTION_END() if (!primask) (void)__iSeiRetVal()
#define cli() noInterrupts() #define cli() noInterrupts()
// Enable interrupts
#define sei() interrupts() #define sei() interrupts()
// Memory related // ------------------------
#define __bss_end __bss_end__
// Clear reset reason
void HAL_clear_reset_source();
// Reset reason
uint8_t HAL_get_reset_source();
void HAL_reboot();
void _delay_ms(const int delay);
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-function"
/*
extern "C" {
int freeMemory();
}
*/
extern "C" char* _sbrk(int incr);
static inline int freeMemory() {
volatile char top;
return &top - _sbrk(0);
}
#pragma GCC diagnostic pop
//
// ADC // ADC
// // ------------------------
#define HAL_ANALOG_SELECT(pin) pinMode(pin, INPUT_ANALOG); #define HAL_ANALOG_SELECT(pin) pinMode(pin, INPUT_ANALOG);
void HAL_adc_init();
#ifdef ADC_RESOLUTION #ifdef ADC_RESOLUTION
#define HAL_ADC_RESOLUTION ADC_RESOLUTION #define HAL_ADC_RESOLUTION ADC_RESOLUTION
#else #else
@@ -244,16 +197,13 @@ void HAL_adc_init();
#endif #endif
#define HAL_ADC_VREF 3.3 #define HAL_ADC_VREF 3.3
#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin)
#define HAL_READ_ADC() HAL_adc_result
#define HAL_ADC_READY() true
void HAL_adc_start_conversion(const uint8_t adc_pin);
uint16_t HAL_adc_get_result();
uint16_t analogRead(pin_t pin); // need HAL_ANALOG_SELECT() first uint16_t analogRead(pin_t pin); // need HAL_ANALOG_SELECT() first
void analogWrite(pin_t pin, int pwm_val8); // PWM only! mul by 257 in maple!? void analogWrite(pin_t pin, int pwm_val8); // PWM only! mul by 257 in maple!?
//
// Pin Mapping for M42, M43, M226
//
#define GET_PIN_MAP_PIN(index) index #define GET_PIN_MAP_PIN(index) index
#define GET_PIN_MAP_INDEX(pin) pin #define GET_PIN_MAP_INDEX(pin) pin
#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) #define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
@@ -264,23 +214,99 @@ void analogWrite(pin_t pin, int pwm_val8); // PWM only! mul by 257 in maple!?
#define PLATFORM_M997_SUPPORT #define PLATFORM_M997_SUPPORT
void flashFirmware(const int16_t); void flashFirmware(const int16_t);
#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment
#ifndef PWM_FREQUENCY #ifndef PWM_FREQUENCY
#define PWM_FREQUENCY 1000 // Default PWM Frequency #define PWM_FREQUENCY 1000 // Default PWM Frequency
#endif #endif
#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment
// ------------------------
// Class Utilities
// ------------------------
// Memory related
#define __bss_end __bss_end__
void _delay_ms(const int ms);
extern "C" char* _sbrk(int incr);
#pragma GCC diagnostic push
#if GCC_VERSION <= 50000
#pragma GCC diagnostic ignored "-Wunused-function"
#endif
static inline int freeMemory() {
volatile char top;
return &top - _sbrk(0);
}
#pragma GCC diagnostic pop
// ------------------------
// MarlinHAL Class
// ------------------------
class MarlinHAL {
public:
// Earliest possible init, before setup()
MarlinHAL() {}
static void init(); // Called early in setup()
static inline void init_board() {} // Called less early in setup()
static void reboot(); // Restart the firmware from 0x0
static inline bool isr_state() { return !__get_primask(); }
static inline void isr_on() { ((void)__iSeiRetVal()); }
static inline void isr_off() { ((void)__iCliRetVal()); }
static inline void delay_ms(const int ms) { delay(ms); }
// Tasks, called from idle()
static void idletask();
// Reset
static inline uint8_t get_reset_source() { return RST_POWER_ON; }
static inline void clear_reset_source() {}
// Free SRAM
static inline int freeMemory() { return freeMemory(); }
//
// ADC Methods
//
static uint16_t adc_result;
// Called by Temperature::init once at startup
static void adc_init();
// Called by Temperature::init for each sensor at startup
static void adc_enable(const pin_t pin);
// Begin ADC sampling on the given channel
static void adc_start(const pin_t pin);
// Is the ADC ready for reading?
static inline bool adc_ready() { return true; }
// The current value of the ADC register
static uint16_t adc_value() { return adc_result; }
/** /**
* set_pwm_frequency * Set the PWM duty cycle for the pin to the given value.
* Set the frequency of the timer corresponding to the provided pin * Optionally invert the duty cycle [default = false]
* All Timer PWM pins run at the same frequency * Optionally change the maximum size of the provided value to enable finer PWM duty control [default = 255]
*/
void set_pwm_frequency(const pin_t pin, int f_desired);
/**
* set_pwm_duty
* Set the PWM duty cycle of the provided pin to the provided value
* Optionally allows inverting the duty cycle [default = false]
* Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255]
* The timer must be pre-configured with set_pwm_frequency() if the default frequency is not desired. * The timer must be pre-configured with set_pwm_frequency() if the default frequency is not desired.
*/ */
void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false);
/**
* Set the frequency of the timer for the given pin.
* All Timer PWM pins run at the same frequency.
*/
static void set_pwm_frequency(const pin_t pin, int f_desired);
};
extern MarlinHAL hal;

View File

@@ -35,7 +35,8 @@
#define SERVO_DEFAULT_MIN_ANGLE 0 #define SERVO_DEFAULT_MIN_ANGLE 0
#define SERVO_DEFAULT_MAX_ANGLE 180 #define SERVO_DEFAULT_MAX_ANGLE 180
#define HAL_SERVO_LIB libServo class libServo;
typedef libServo hal_servo_t;
class libServo { class libServo {
public: public:

View File

@@ -21,11 +21,9 @@
*/ */
#ifdef __STM32F1__ #ifdef __STM32F1__
#include "../../inc/MarlinConfigPre.h" #include "../../inc/MarlinConfig.h"
#include <pwm.h> #include <pwm.h>
#include "HAL.h"
#include "timers.h"
#define NR_TIMERS TERN(STM32_XL_DENSITY, 14, 8) // Maple timers, 14 for STM32_XL_DENSITY (F/G chips), 8 for HIGH density (C D E) #define NR_TIMERS TERN(STM32_XL_DENSITY, 14, 8) // Maple timers, 14 for STM32_XL_DENSITY (F/G chips), 8 for HIGH density (C D E)
@@ -38,7 +36,7 @@ inline uint8_t timer_and_index_for_pin(const pin_t pin, timer_dev **timer_ptr) {
return 0; return 0;
} }
void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) {
if (!PWM_PIN(pin)) return; if (!PWM_PIN(pin)) return;
timer_dev *timer; UNUSED(timer); timer_dev *timer; UNUSED(timer);
@@ -51,7 +49,7 @@ void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255
timer_set_mode(timer, channel, TIMER_PWM); // PWM Output Mode timer_set_mode(timer, channel, TIMER_PWM); // PWM Output Mode
} }
void set_pwm_frequency(const pin_t pin, int f_desired) { void MarlinHAL::set_pwm_frequency(const pin_t pin, int f_desired) {
if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer
timer_dev *timer; UNUSED(timer); timer_dev *timer; UNUSED(timer);

View File

@@ -188,7 +188,7 @@ FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) {
} }
} }
#define HAL_timer_isr_epilogue(T) #define HAL_timer_isr_epilogue(T) NOOP
// No command is available in framework to turn off ARPE bit, which is turned on by default in libmaple. // No command is available in framework to turn off ARPE bit, which is turned on by default in libmaple.
// Needed here to reset ARPE=0 for stepper timer // Needed here to reset ARPE=0 for stepper timer

View File

@@ -31,6 +31,10 @@
#include <Wire.h> #include <Wire.h>
// ------------------------
// Serial ports
// ------------------------
#define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X) #define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X)
#define IMPLEMENT_SERIAL(X) _IMPLEMENT_SERIAL(X) #define IMPLEMENT_SERIAL(X) _IMPLEMENT_SERIAL(X)
#if WITHIN(SERIAL_PORT, 0, 3) #if WITHIN(SERIAL_PORT, 0, 3)
@@ -40,45 +44,9 @@
#endif #endif
USBSerialType USBSerial(false, SerialUSB); USBSerialType USBSerial(false, SerialUSB);
uint16_t HAL_adc_result; // ------------------------
// Class Utilities
static const uint8_t pin2sc1a[] = { // ------------------------
5, 14, 8, 9, 13, 12, 6, 7, 15, 4, 0, 19, 3, 31, // 0-13, we treat them as A0-A13
5, 14, 8, 9, 13, 12, 6, 7, 15, 4, // 14-23 (A0-A9)
31, 31, 31, 31, 31, 31, 31, 31, 31, 31, // 24-33
0+64, 19+64, 3+64, 31+64, // 34-37 (A10-A13)
26, 22, 23, 27, 29, 30 // 38-43: temp. sensor, VREF_OUT, A14, bandgap, VREFH, VREFL. A14 isn't connected to anything in Teensy 3.0.
};
/*
// disable interrupts
void cli() { noInterrupts(); }
// enable interrupts
void sei() { interrupts(); }
*/
void HAL_adc_init() {
analog_init();
while (ADC0_SC3 & ADC_SC3_CAL) {}; // Wait for calibration to finish
NVIC_ENABLE_IRQ(IRQ_FTM1);
}
void HAL_clear_reset_source() { }
uint8_t HAL_get_reset_source() {
switch (RCM_SRS0) {
case 128: return RST_POWER_ON; break;
case 64: return RST_EXTERNAL; break;
case 32: return RST_WATCHDOG; break;
// case 8: return RST_LOSS_OF_LOCK; break;
// case 4: return RST_LOSS_OF_CLOCK; break;
// case 2: return RST_LOW_VOLTAGE; break;
}
return 0;
}
void HAL_reboot() { _reboot_Teensyduino_(); }
extern "C" { extern "C" {
extern char __bss_end; extern char __bss_end;
@@ -95,8 +63,43 @@ extern "C" {
} }
} }
void HAL_adc_start_conversion(const uint8_t adc_pin) { ADC0_SC1A = pin2sc1a[adc_pin]; } // ------------------------
// MarlinHAL Class
// ------------------------
uint16_t HAL_adc_get_result() { return ADC0_RA; } void MarlinHAL::reboot() { _reboot_Teensyduino_(); }
uint8_t MarlinHAL::get_reset_source() {
switch (RCM_SRS0) {
case 128: return RST_POWER_ON; break;
case 64: return RST_EXTERNAL; break;
case 32: return RST_WATCHDOG; break;
// case 8: return RST_LOSS_OF_LOCK; break;
// case 4: return RST_LOSS_OF_CLOCK; break;
// case 2: return RST_LOW_VOLTAGE; break;
}
return 0;
}
// ADC
void MarlinHAL::adc_init() {
analog_init();
while (ADC0_SC3 & ADC_SC3_CAL) {}; // Wait for calibration to finish
NVIC_ENABLE_IRQ(IRQ_FTM1);
}
void MarlinHAL::adc_start(const pin_t pin) {
static const uint8_t pin2sc1a[] = {
5, 14, 8, 9, 13, 12, 6, 7, 15, 4, 0, 19, 3, 31, // 0-13, we treat them as A0-A13
5, 14, 8, 9, 13, 12, 6, 7, 15, 4, // 14-23 (A0-A9)
31, 31, 31, 31, 31, 31, 31, 31, 31, 31, // 24-33
0+64, 19+64, 3+64, 31+64, // 34-37 (A10-A13)
26, 22, 23, 27, 29, 30 // 38-43: temp. sensor, VREF_OUT, A14, bandgap, VREFH, VREFL. A14 isn't connected to anything in Teensy 3.0.
};
ADC0_SC1A = pin2sc1a[pin];
}
uint16_t MarlinHAL::adc_value() { return ADC0_RA; }
#endif // __MK20DX256__ #endif // __MK20DX256__

View File

@@ -36,12 +36,9 @@
#include <stdint.h> #include <stdint.h>
#define CPU_ST7920_DELAY_1 600 // ------------------------
#define CPU_ST7920_DELAY_2 750 // Defines
#define CPU_ST7920_DELAY_3 750 // ------------------------
//#undef MOTHERBOARD
//#define MOTHERBOARD BOARD_TEENSY31_32
#define IS_32BIT_TEENSY 1 #define IS_32BIT_TEENSY 1
#define IS_TEENSY_31_32 1 #define IS_TEENSY_31_32 1
@@ -49,6 +46,14 @@
#define IS_TEENSY32 1 #define IS_TEENSY32 1
#endif #endif
#define CPU_ST7920_DELAY_1 600
#define CPU_ST7920_DELAY_2 750
#define CPU_ST7920_DELAY_3 750
// ------------------------
// Serial ports
// ------------------------
#include "../../core/serial_hook.h" #include "../../core/serial_hook.h"
#define Serial0 Serial #define Serial0 Serial
@@ -72,31 +77,46 @@ extern USBSerialType USBSerial;
#error "The required SERIAL_PORT must be from 0 to 3, or -1 for Native USB." #error "The required SERIAL_PORT must be from 0 to 3, or -1 for Native USB."
#endif #endif
#define HAL_SERVO_LIB libServo // ------------------------
// Types
// ------------------------
class libServo;
typedef libServo hal_servo_t;
typedef int8_t pin_t; typedef int8_t pin_t;
// ------------------------
// Interrupts
// ------------------------
uint32_t __get_PRIMASK(void); // CMSIS
#define CRITICAL_SECTION_START() const bool irqon = !__get_PRIMASK(); __disable_irq()
#define CRITICAL_SECTION_END() if (irqon) __enable_irq()
// ------------------------
// ADC
// ------------------------
#ifndef analogInputToDigitalPin #ifndef analogInputToDigitalPin
#define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1) #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1)
#endif #endif
#define CRITICAL_SECTION_START() uint32_t primask = __get_PRIMASK(); __disable_irq() #define HAL_ADC_VREF 3.3
#define CRITICAL_SECTION_END() if (!primask) __enable_irq() #define HAL_ADC_RESOLUTION 10
#define ISRS_ENABLED() (!__get_PRIMASK())
#define ENABLE_ISRS() __enable_irq()
#define DISABLE_ISRS() __disable_irq()
inline void HAL_init() {} #define HAL_ANALOG_SELECT(pin)
// Clear the reset reason //
void HAL_clear_reset_source(); // Pin Mapping for M42, M43, M226
//
#define GET_PIN_MAP_PIN(index) index
#define GET_PIN_MAP_INDEX(pin) pin
#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
// Get the reason for the reset // ------------------------
uint8_t HAL_get_reset_source(); // Class Utilities
// ------------------------
void HAL_reboot();
FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); }
#pragma GCC diagnostic push #pragma GCC diagnostic push
#if GCC_VERSION <= 50000 #if GCC_VERSION <= 50000
@@ -107,27 +127,64 @@ extern "C" int freeMemory();
#pragma GCC diagnostic pop #pragma GCC diagnostic pop
// ADC // ------------------------
// MarlinHAL Class
// ------------------------
void HAL_adc_init(); class MarlinHAL {
public:
#define HAL_ADC_VREF 3.3 // Earliest possible init, before setup()
#define HAL_ADC_RESOLUTION 10 MarlinHAL() {}
#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) static inline void init() {} // Called early in setup()
static inline void init_board() {} // Called less early in setup()
static void reboot(); // Restart the firmware from 0x0
void HAL_adc_start_conversion(const uint8_t adc_pin); static inline bool isr_state() { return !__get_PRIMASK(); }
uint16_t HAL_adc_get_result(); static inline void isr_on() { __enable_irq(); }
static inline void isr_off() { __disable_irq(); }
// PWM static inline void delay_ms(const int ms) { delay(ms); }
inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } // Tasks, called from idle()
static inline void idletask() {}
// Pin Map // Reset
static uint8_t get_reset_source();
static inline void clear_reset_source() {}
#define GET_PIN_MAP_PIN(index) index // Free SRAM
#define GET_PIN_MAP_INDEX(pin) pin static inline int freeMemory() { return freeMemory(); }
#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
//
// ADC Methods
//
// Called by Temperature::init once at startup
static void adc_init();
// Called by Temperature::init for each sensor at startup
static void adc_enable(const pin_t ch);
// Begin ADC sampling on the given channel
static void adc_start(const pin_t ch);
// Is the ADC ready for reading?
static inline bool adc_ready() { return true; }
// The current value of the ADC register
static uint16_t adc_value();
/**
* Set the PWM duty cycle for the pin to the given value.
* No option to invert the duty cycle [default = false]
* No option to change the scale of the provided value to enable finer PWM duty control [default = 255]
*/
static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) {
analogWrite(pin, v);
}
};
extern MarlinHAL hal;

View File

@@ -110,4 +110,4 @@ void HAL_timer_disable_interrupt(const uint8_t timer_num);
bool HAL_timer_interrupt_enabled(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_prologue(const uint8_t timer_num);
#define HAL_timer_isr_epilogue(T) #define HAL_timer_isr_epilogue(T) NOOP

View File

@@ -31,6 +31,10 @@
#include <Wire.h> #include <Wire.h>
// ------------------------
// Serial ports
// ------------------------
#define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X) #define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X)
#define IMPLEMENT_SERIAL(X) _IMPLEMENT_SERIAL(X) #define IMPLEMENT_SERIAL(X) _IMPLEMENT_SERIAL(X)
#if WITHIN(SERIAL_PORT, 0, 3) #if WITHIN(SERIAL_PORT, 0, 3)
@@ -39,54 +43,9 @@
USBSerialType USBSerial(false, SerialUSB); USBSerialType USBSerial(false, SerialUSB);
uint16_t HAL_adc_result, HAL_adc_select; // ------------------------
// Class Utilities
static const uint8_t pin2sc1a[] = { // ------------------------
5, 14, 8, 9, 13, 12, 6, 7, 15, 4, 3, 19+128, 14+128, 15+128, // 0-13 -> A0-A13
5, 14, 8, 9, 13, 12, 6, 7, 15, 4, // 14-23 are A0-A9
255, 255, 255, 255, 255, 255, 255, // 24-30 are digital only
14+128, 15+128, 17, 18, 4+128, 5+128, 6+128, 7+128, 17+128, // 31-39 are A12-A20
255, 255, 255, 255, 255, 255, 255, 255, 255, // 40-48 are digital only
10+128, 11+128, // 49-50 are A23-A24
255, 255, 255, 255, 255, 255, 255, // 51-57 are digital only
255, 255, 255, 255, 255, 255, // 58-63 (sd card pins) are digital only
3, 19+128, // 64-65 are A10-A11
23, 23+128,// 66-67 are A21-A22 (DAC pins)
1, 1+128, // 68-69 are A25-A26 (unused USB host port on Teensy 3.5)
26, // 70 is Temperature Sensor
18+128 // 71 is Vref
};
/*
// disable interrupts
void cli() { noInterrupts(); }
// enable interrupts
void sei() { interrupts(); }
*/
void HAL_adc_init() {
analog_init();
while (ADC0_SC3 & ADC_SC3_CAL) {}; // Wait for calibration to finish
while (ADC1_SC3 & ADC_SC3_CAL) {}; // Wait for calibration to finish
NVIC_ENABLE_IRQ(IRQ_FTM1);
}
void HAL_clear_reset_source() { }
uint8_t HAL_get_reset_source() {
switch (RCM_SRS0) {
case 128: return RST_POWER_ON; break;
case 64: return RST_EXTERNAL; break;
case 32: return RST_WATCHDOG; break;
// case 8: return RST_LOSS_OF_LOCK; break;
// case 4: return RST_LOSS_OF_CLOCK; break;
// case 2: return RST_LOW_VOLTAGE; break;
}
return 0;
}
void HAL_reboot() { _reboot_Teensyduino_(); }
extern "C" { extern "C" {
extern char __bss_end; extern char __bss_end;
@@ -103,24 +62,69 @@ extern "C" {
} }
} }
void HAL_adc_start_conversion(const uint8_t adc_pin) { // ------------------------
// MarlinHAL Class
// ------------------------
void MarlinHAL::reboot() { _reboot_Teensyduino_(); }
// Reset
uint8_t MarlinHAL::get_reset_source() {
switch (RCM_SRS0) {
case 128: return RST_POWER_ON; break;
case 64: return RST_EXTERNAL; break;
case 32: return RST_WATCHDOG; break;
// case 8: return RST_LOSS_OF_LOCK; break;
// case 4: return RST_LOSS_OF_CLOCK; break;
// case 2: return RST_LOW_VOLTAGE; break;
}
return 0;
}
// ADC
int8_t MarlinHAL::adc_select;
void MarlinHAL::adc_init() {
analog_init();
while (ADC0_SC3 & ADC_SC3_CAL) { /* Wait for calibration to finish */ }
while (ADC1_SC3 & ADC_SC3_CAL) { /* Wait for calibration to finish */ }
NVIC_ENABLE_IRQ(IRQ_FTM1);
}
void MarlinHAL::adc_start(const pin_t adc_pin) {
static const uint8_t pin2sc1a[] = {
5, 14, 8, 9, 13, 12, 6, 7, 15, 4, 3, 19+128, 14+128, 15+128, // 0-13 -> A0-A13
5, 14, 8, 9, 13, 12, 6, 7, 15, 4, // 14-23 are A0-A9
255, 255, 255, 255, 255, 255, 255, // 24-30 are digital only
14+128, 15+128, 17, 18, 4+128, 5+128, 6+128, 7+128, 17+128, // 31-39 are A12-A20
255, 255, 255, 255, 255, 255, 255, 255, 255, // 40-48 are digital only
10+128, 11+128, // 49-50 are A23-A24
255, 255, 255, 255, 255, 255, 255, // 51-57 are digital only
255, 255, 255, 255, 255, 255, // 58-63 (sd card pins) are digital only
3, 19+128, // 64-65 are A10-A11
23, 23+128,// 66-67 are A21-A22 (DAC pins)
1, 1+128, // 68-69 are A25-A26 (unused USB host port on Teensy 3.5)
26, // 70 is Temperature Sensor
18+128 // 71 is Vref
};
const uint16_t pin = pin2sc1a[adc_pin]; const uint16_t pin = pin2sc1a[adc_pin];
if (pin == 0xFF) { if (pin == 0xFF) {
// Digital only adc_select = -1; // Digital only
HAL_adc_select = -1;
} }
else if (pin & 0x80) { else if (pin & 0x80) {
HAL_adc_select = 1; adc_select = 1;
ADC1_SC1A = pin & 0x7F; ADC1_SC1A = pin & 0x7F;
} }
else { else {
HAL_adc_select = 0; adc_select = 0;
ADC0_SC1A = pin; ADC0_SC1A = pin;
} }
} }
uint16_t HAL_adc_get_result() { uint16_t MarlinHAL::adc_value() {
switch (HAL_adc_select) { switch (adc_select) {
case 0: return ADC0_RA; case 0: return ADC0_RA;
case 1: return ADC1_RA; case 1: return ADC1_RA;
} }

View File

@@ -37,10 +37,6 @@
#include <stdint.h> #include <stdint.h>
#include <util/atomic.h> #include <util/atomic.h>
#define CPU_ST7920_DELAY_1 600
#define CPU_ST7920_DELAY_2 750
#define CPU_ST7920_DELAY_3 750
// ------------------------ // ------------------------
// Defines // Defines
// ------------------------ // ------------------------
@@ -53,6 +49,17 @@
#define IS_TEENSY35 1 #define IS_TEENSY35 1
#endif #endif
#define CPU_ST7920_DELAY_1 600
#define CPU_ST7920_DELAY_2 750
#define CPU_ST7920_DELAY_3 750
#undef sq
#define sq(x) ((x)*(x))
// ------------------------
// Serial ports
// ------------------------
#include "../../core/serial_hook.h" #include "../../core/serial_hook.h"
#define Serial0 Serial #define Serial0 Serial
@@ -76,34 +83,45 @@ extern USBSerialType USBSerial;
#error "SERIAL_PORT must be from 0 to 3, or -1 for Native USB." #error "SERIAL_PORT must be from 0 to 3, or -1 for Native USB."
#endif #endif
#define HAL_SERVO_LIB libServo // ------------------------
// Types
// ------------------------
class libServo;
typedef libServo hal_servo_t;
typedef int8_t pin_t; typedef int8_t pin_t;
// ------------------------
// Interrupts
// ------------------------
#define CRITICAL_SECTION_START() const bool irqon = !__get_primask(); __disable_irq()
#define CRITICAL_SECTION_END() if (irqon) __enable_irq()
// ------------------------
// ADC
// ------------------------
#ifndef analogInputToDigitalPin #ifndef analogInputToDigitalPin
#define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1) #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1)
#endif #endif
#define CRITICAL_SECTION_START() uint32_t primask = __get_primask(); __disable_irq() #define HAL_ADC_VREF 3.3
#define CRITICAL_SECTION_END() if (!primask) __enable_irq() #define HAL_ADC_RESOLUTION 10
#define ISRS_ENABLED() (!__get_primask())
#define ENABLE_ISRS() __enable_irq()
#define DISABLE_ISRS() __disable_irq()
#undef sq #define HAL_ANALOG_SELECT(pin)
#define sq(x) ((x)*(x))
inline void HAL_init() {} //
// Pin Mapping for M42, M43, M226
//
#define GET_PIN_MAP_PIN(index) index
#define GET_PIN_MAP_INDEX(pin) pin
#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
// Clear reset reason // ------------------------
void HAL_clear_reset_source(); // Class Utilities
// ------------------------
// Reset reason
uint8_t HAL_get_reset_source();
void HAL_reboot();
FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); }
#pragma GCC diagnostic push #pragma GCC diagnostic push
#if GCC_VERSION <= 50000 #if GCC_VERSION <= 50000
@@ -114,27 +132,66 @@ extern "C" int freeMemory();
#pragma GCC diagnostic pop #pragma GCC diagnostic pop
// ADC // ------------------------
// MarlinHAL Class
// ------------------------
void HAL_adc_init(); class MarlinHAL {
public:
#define HAL_ADC_VREF 3.3 // Earliest possible init, before setup()
#define HAL_ADC_RESOLUTION 10 MarlinHAL() {}
#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) static inline void init() {} // Called early in setup()
static inline void init_board() {} // Called less early in setup()
static void reboot(); // Restart the firmware from 0x0
void HAL_adc_start_conversion(const uint8_t adc_pin); static inline bool isr_state() { return true; }
uint16_t HAL_adc_get_result(); static inline void isr_on() { __enable_irq(); }
static inline void isr_off() { __disable_irq(); }
// PWM static inline void delay_ms(const int ms) { delay(ms); }
inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } // Tasks, called from idle()
static inline void idletask() {}
// Pin Map // Reset
static uint8_t get_reset_source();
static inline void clear_reset_source() {}
#define GET_PIN_MAP_PIN(index) index // Free SRAM
#define GET_PIN_MAP_INDEX(pin) pin static inline int freeMemory() { return freeMemory(); }
#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
//
// ADC Methods
//
static int8_t adc_select;
// Called by Temperature::init once at startup
static void adc_init();
// Called by Temperature::init for each sensor at startup
static inline void adc_enable(const pin_t) {}
// Begin ADC sampling on the given channel
static void adc_start(const pin_t pin);
// Is the ADC ready for reading?
static inline bool adc_ready() { return true; }
// The current value of the ADC register
static uint16_t adc_value();
/**
* Set the PWM duty cycle for the pin to the given value.
* No option to invert the duty cycle [default = false]
* No option to change the scale of the provided value to enable finer PWM duty control [default = 255]
*/
static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) {
analogWrite(pin, v);
}
};
extern MarlinHAL hal;

View File

@@ -109,4 +109,4 @@ void HAL_timer_disable_interrupt(const uint8_t timer_num);
bool HAL_timer_interrupt_enabled(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_prologue(const uint8_t timer_num);
#define HAL_timer_isr_epilogue(T) #define HAL_timer_isr_epilogue(T) NOOP

View File

@@ -33,6 +33,10 @@
#include "timers.h" #include "timers.h"
#include <Wire.h> #include <Wire.h>
// ------------------------
// Serial ports
// ------------------------
#define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X) #define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X)
#define IMPLEMENT_SERIAL(X) _IMPLEMENT_SERIAL(X) #define IMPLEMENT_SERIAL(X) _IMPLEMENT_SERIAL(X)
#if WITHIN(SERIAL_PORT, 0, 3) #if WITHIN(SERIAL_PORT, 0, 3)
@@ -40,8 +44,70 @@
#endif #endif
USBSerialType USBSerial(false, SerialUSB); USBSerialType USBSerial(false, SerialUSB);
uint16_t HAL_adc_result, HAL_adc_select; // ------------------------
// Class Utilities
// ------------------------
#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;
free_memory = ((uint32_t)&free_memory) - (((uint32_t)__brkval) ?: ((uint32_t)&__bss_end));
return free_memory;
}
}
// ------------------------
// FastIO
// ------------------------
bool is_output(pin_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);
}
// ------------------------
// MarlinHAL Class
// ------------------------
void MarlinHAL::reboot() { _reboot_Teensyduino_(); }
uint8_t MarlinHAL::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;
}
void MarlinHAL::clear_reset_source() {
uint32_t reset_source = SRC_SRSR;
SRC_SRSR = reset_source;
}
// ADC
int8_t MarlinHAL::adc_select;
void MarlinHAL::adc_init() {
analog_init();
while (ADC1_GC & ADC_GC_CAL) { /* wait */ }
while (ADC2_GC & ADC_GC_CAL) { /* wait */ }
}
void MarlinHAL::adc_start(const pin_t adc_pin) {
static const uint8_t pin2sc1a[] = { static const uint8_t pin2sc1a[] = {
0x07, // 0/A0 AD_B1_02 0x07, // 0/A0 AD_B1_02
0x08, // 1/A1 AD_B1_03 0x08, // 1/A1 AD_B1_03
@@ -88,90 +154,30 @@ static const uint8_t pin2sc1a[] = {
0x0A, // 41/A17 AD_B1_05 0x0A, // 41/A17 AD_B1_05
#endif #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;
}
void HAL_reboot() { _reboot_Teensyduino_(); }
#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]; const uint16_t pin = pin2sc1a[adc_pin];
if (pin == 0xFF) { if (pin == 0xFF) {
HAL_adc_select = -1; // Digital only adc_select = -1; // Digital only
} }
else if (pin & 0x80) { else if (pin & 0x80) {
HAL_adc_select = 1; adc_select = 1;
ADC2_HC0 = pin & 0x7F; ADC2_HC0 = pin & 0x7F;
} }
else { else {
HAL_adc_select = 0; adc_select = 0;
ADC1_HC0 = pin; ADC1_HC0 = pin;
} }
} }
uint16_t HAL_adc_get_result() { uint16_t MarlinHAL::adc_value() {
switch (HAL_adc_select) { switch (adc_select) {
case 0: case 0:
while (!(ADC1_HS & ADC_HS_COCO0)) ; // wait while (!(ADC1_HS & ADC_HS_COCO0)) { /* wait */ }
return ADC1_R0; return ADC1_R0;
case 1: case 1:
while (!(ADC2_HS & ADC_HS_COCO0)) ; // wait while (!(ADC2_HS & ADC_HS_COCO0)) { /* wait */ }
return ADC2_R0; return ADC2_R0;
} }
return 0; return 0;
} }
bool is_output(pin_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__ #endif // __IMXRT1062__

View File

@@ -41,10 +41,6 @@
#include "../../feature/ethernet.h" #include "../../feature/ethernet.h"
#endif #endif
#define CPU_ST7920_DELAY_1 600
#define CPU_ST7920_DELAY_2 750
#define CPU_ST7920_DELAY_3 750
// ------------------------ // ------------------------
// Defines // Defines
// ------------------------ // ------------------------
@@ -55,7 +51,23 @@
#define IS_TEENSY41 1 #define IS_TEENSY41 1
#endif #endif
#define CPU_ST7920_DELAY_1 600
#define CPU_ST7920_DELAY_2 750
#define CPU_ST7920_DELAY_3 750
#undef sq
#define sq(x) ((x)*(x))
// Don't place string constants in PROGMEM
#undef PSTR
#define PSTR(str) ({static const char *data = (str); &data[0];})
// ------------------------
// Serial ports
// ------------------------
#include "../../core/serial_hook.h" #include "../../core/serial_hook.h"
#define Serial0 Serial #define Serial0 Serial
#define _DECLARE_SERIAL(X) \ #define _DECLARE_SERIAL(X) \
typedef ForwardSerial1Class<decltype(Serial##X)> DefaultSerial##X; \ typedef ForwardSerial1Class<decltype(Serial##X)> DefaultSerial##X; \
@@ -89,41 +101,49 @@ extern USBSerialType USBSerial;
#endif #endif
#endif #endif
#define HAL_SERVO_LIB libServo // ------------------------
// Types
// ------------------------
class libServo;
typedef libServo hal_servo_t;
typedef int8_t pin_t; typedef int8_t pin_t;
// ------------------------
// Interrupts
// ------------------------
#define CRITICAL_SECTION_START() const bool irqon = !__get_primask(); __disable_irq()
#define CRITICAL_SECTION_END() if (irqon) __enable_irq()
// ------------------------
// ADC
// ------------------------
#ifndef analogInputToDigitalPin #ifndef analogInputToDigitalPin
#define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1) #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1)
#endif #endif
#define CRITICAL_SECTION_START() uint32_t primask = __get_primask(); __disable_irq() #define HAL_ADC_VREF 3.3
#define CRITICAL_SECTION_END() if (!primask) __enable_irq() #define HAL_ADC_RESOLUTION 10
#define ISRS_ENABLED() (!__get_primask()) #define HAL_ADC_FILTERED // turn off ADC oversampling
#define ENABLE_ISRS() __enable_irq()
#define DISABLE_ISRS() __disable_irq()
#undef sq #define HAL_ANALOG_SELECT(pin)
#define sq(x) ((x)*(x))
// Don't place string constants in PROGMEM //
#undef PSTR // Pin Mapping for M42, M43, M226
#define PSTR(str) ({static const char *data = (str); &data[0];}) //
#define GET_PIN_MAP_PIN(index) index
#define GET_PIN_MAP_INDEX(pin) pin
#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
// Enable hooks into idle and setup for HAL // FastIO
#define HAL_IDLETASK 1 bool is_output(pin_t pin);
FORCE_INLINE void HAL_idletask() {}
FORCE_INLINE void HAL_init() {}
// Clear reset reason // ------------------------
void HAL_clear_reset_source(); // Class Utilities
// ------------------------
// Reset reason
uint8_t HAL_get_reset_source();
void HAL_reboot();
FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); }
#pragma GCC diagnostic push #pragma GCC diagnostic push
#if GCC_VERSION <= 50000 #if GCC_VERSION <= 50000
@@ -134,30 +154,66 @@ extern "C" uint32_t freeMemory();
#pragma GCC diagnostic pop #pragma GCC diagnostic pop
// ADC // ------------------------
// MarlinHAL Class
// ------------------------
void HAL_adc_init(); class MarlinHAL {
public:
#define HAL_ADC_VREF 3.3 // Earliest possible init, before setup()
#define HAL_ADC_RESOLUTION 10 MarlinHAL() {}
#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) static inline void init() {} // Called early in setup()
static inline void init_board() {} // Called less early in setup()
static void reboot(); // Restart the firmware from 0x0
void HAL_adc_start_conversion(const uint8_t adc_pin); static inline bool isr_state() { return !__get_primask(); }
uint16_t HAL_adc_get_result(); static inline void isr_on() { __enable_irq(); }
static inline void isr_off() { __disable_irq(); }
// PWM static inline void delay_ms(const int ms) { delay(ms); }
inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } // Tasks, called from idle()
static inline void idletask() {}
// Pin Map // Reset
static uint8_t get_reset_source();
static void clear_reset_source();
#define GET_PIN_MAP_PIN(index) index // Free SRAM
#define GET_PIN_MAP_INDEX(pin) pin static inline int freeMemory() { return freeMemory(); }
#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
bool is_output(pin_t pin); //
// ADC Methods
//
static int8_t adc_select;
// Called by Temperature::init once at startup
static void adc_init();
// Called by Temperature::init for each sensor at startup
static void adc_enable(const pin_t pin);
// Begin ADC sampling on the given channel
static void adc_start(const pin_t pin);
// Is the ADC ready for reading?
static inline bool adc_ready() { return true; }
// The current value of the ADC register
static uint16_t adc_value();
/**
* Set the PWM duty cycle for the pin to the given value.
* No option to invert the duty cycle [default = false]
* No option to change the scale of the provided value to enable finer PWM duty control [default = 255]
*/
static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) {
analogWrite(pin, v);
}
};
extern MarlinHAL hal;

View File

@@ -114,4 +114,4 @@ bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
void HAL_timer_isr_prologue(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) {} //void HAL_timer_isr_epilogue(const uint8_t timer_num) {}
#define HAL_timer_isr_epilogue(T) #define HAL_timer_isr_epilogue(T) NOOP

View File

@@ -0,0 +1,36 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2021 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/>.
*
*/
/**
* HAL/shared/HAL.cpp
*/
#include "../../inc/MarlinConfig.h"
MarlinHAL hal;
#if ENABLED(SOFT_RESET_VIA_SERIAL)
// Global for use by e_parser.h
void HAL_reboot() { hal.reboot(); }
#endif

View File

@@ -92,9 +92,9 @@ uint8_t L64XX_Marlin::transfer_single(uint8_t data, int16_t ss_pin) {
// First device in chain has data sent last // First device in chain has data sent last
extDigitalWrite(ss_pin, LOW); extDigitalWrite(ss_pin, LOW);
DISABLE_ISRS(); // Disable interrupts during SPI transfer (can't allow partial command to chips) hal.isr_off(); // Disable interrupts during SPI transfer (can't allow partial command to chips)
const uint8_t data_out = L6470_SpiTransfer_Mode_3(data); const uint8_t data_out = L6470_SpiTransfer_Mode_3(data);
ENABLE_ISRS(); // Enable interrupts hal.isr_on(); // Enable interrupts
extDigitalWrite(ss_pin, HIGH); extDigitalWrite(ss_pin, HIGH);
return data_out; return data_out;
@@ -107,9 +107,9 @@ uint8_t L64XX_Marlin::transfer_chain(uint8_t data, int16_t ss_pin, uint8_t chain
extDigitalWrite(ss_pin, LOW); extDigitalWrite(ss_pin, LOW);
for (uint8_t i = L64XX::chain[0]; !L64xxManager.spi_abort && i >= 1; i--) { // Send data unless aborted for (uint8_t i = L64XX::chain[0]; !L64xxManager.spi_abort && i >= 1; i--) { // Send data unless aborted
DISABLE_ISRS(); // Disable interrupts during SPI transfer (can't allow partial command to chips) hal.isr_off(); // Disable interrupts during SPI transfer (can't allow partial command to chips)
const uint8_t temp = L6470_SpiTransfer_Mode_3(uint8_t(i == chain_position ? data : dSPIN_NOP)); const uint8_t temp = L6470_SpiTransfer_Mode_3(uint8_t(i == chain_position ? data : dSPIN_NOP));
ENABLE_ISRS(); // Enable interrupts hal.isr_on(); // Enable interrupts
if (i == chain_position) data_out = temp; if (i == chain_position) data_out = temp;
} }

View File

@@ -790,7 +790,7 @@ void idle(bool no_stepper_sleep/*=false*/) {
#endif #endif
// Run HAL idle tasks // Run HAL idle tasks
TERN_(HAL_IDLETASK, HAL_idletask()); hal.idletask();
// Check network connection // Check network connection
TERN_(HAS_ETHERNET, ethernet.check()); TERN_(HAS_ETHERNET, ethernet.check());
@@ -929,7 +929,7 @@ void minkill(const bool steppers_off/*=false*/) {
watchdog_refresh(); watchdog_refresh();
// Reboot the board // Reboot the board
HAL_reboot(); hal.reboot();
#else #else
@@ -1041,7 +1041,7 @@ inline void tmc_standby_setup() {
* • L64XX Stepper Drivers (SPI) * • L64XX Stepper Drivers (SPI)
* • Stepper Driver Reset: DISABLE * • Stepper Driver Reset: DISABLE
* • TMC Stepper Drivers (SPI) * • TMC Stepper Drivers (SPI)
* • Run BOARD_INIT if defined * • Run hal.init_board() for additional pins setup
* • ESP WiFi * • ESP WiFi
* - Get the Reset Reason and report it * - Get the Reset Reason and report it
* - Print startup messages and diagnostics * - Print startup messages and diagnostics
@@ -1119,8 +1119,8 @@ void setup() {
tmc_standby_setup(); // TMC Low Power Standby pins must be set early or they're not usable tmc_standby_setup(); // TMC Low Power Standby pins must be set early or they're not usable
// Check startup - does nothing if bootloader sets MCUSR to 0 // Check startup - does nothing if bootloader sets MCUSR to 0
const byte mcu = HAL_get_reset_source(); const byte mcu = hal.get_reset_source();
HAL_clear_reset_source(); hal.clear_reset_source();
#if ENABLED(MARLIN_DEV_MODE) #if ENABLED(MARLIN_DEV_MODE)
auto log_current_ms = [&](PGM_P const msg) { auto log_current_ms = [&](PGM_P const msg) {
@@ -1181,23 +1181,20 @@ void setup() {
JTAGSWD_RESET(); JTAGSWD_RESET();
#endif #endif
#if EITHER(DISABLE_DEBUG, DISABLE_JTAG)
delay(10);
// Disable any hardware debug to free up pins for IO // Disable any hardware debug to free up pins for IO
#if ENABLED(DISABLE_DEBUG) && defined(JTAGSWD_DISABLE) #if ENABLED(DISABLE_DEBUG) && defined(JTAGSWD_DISABLE)
delay(10);
SETUP_LOG("JTAGSWD_DISABLE"); SETUP_LOG("JTAGSWD_DISABLE");
JTAGSWD_DISABLE(); JTAGSWD_DISABLE();
#elif defined(JTAG_DISABLE) #elif ENABLED(DISABLE_JTAG) && defined(JTAG_DISABLE)
delay(10);
SETUP_LOG("JTAG_DISABLE"); SETUP_LOG("JTAG_DISABLE");
JTAG_DISABLE(); JTAG_DISABLE();
#else
#error "DISABLE_(DEBUG|JTAG) is not supported for the selected MCU/Board."
#endif
#endif #endif
TERN_(DYNAMIC_VECTORTABLE, hook_cpu_exceptions()); // If supported, install Marlin exception handlers at runtime TERN_(DYNAMIC_VECTORTABLE, hook_cpu_exceptions()); // If supported, install Marlin exception handlers at runtime
SETUP_RUN(HAL_init()); SETUP_RUN(hal.init());
// Init and disable SPI thermocouples; this is still needed // Init and disable SPI thermocouples; this is still needed
#if TEMP_SENSOR_0_IS_MAX_TC || (TEMP_SENSOR_REDUNDANT_IS_MAX_TC && REDUNDANT_TEMP_MATCH(SOURCE, E0)) #if TEMP_SENSOR_0_IS_MAX_TC || (TEMP_SENSOR_REDUNDANT_IS_MAX_TC && REDUNDANT_TEMP_MATCH(SOURCE, E0))
@@ -1243,10 +1240,7 @@ void setup() {
SETUP_RUN(tmc_init_cs_pins()); SETUP_RUN(tmc_init_cs_pins());
#endif #endif
#ifdef BOARD_INIT SETUP_RUN(hal.init_board());
SETUP_LOG("BOARD_INIT");
BOARD_INIT();
#endif
SETUP_RUN(esp_wifi_init()); SETUP_RUN(esp_wifi_init());
@@ -1266,7 +1260,7 @@ void setup() {
); );
#endif #endif
SERIAL_ECHO_MSG(" Compiled: " __DATE__); SERIAL_ECHO_MSG(" Compiled: " __DATE__);
SERIAL_ECHO_MSG(STR_FREE_MEMORY, freeMemory(), STR_PLANNER_BUFFER_BYTES, sizeof(block_t) * (BLOCK_BUFFER_SIZE)); SERIAL_ECHO_MSG(STR_FREE_MEMORY, hal.freeMemory(), STR_PLANNER_BUFFER_BYTES, sizeof(block_t) * (BLOCK_BUFFER_SIZE));
// Some HAL need precise delay adjustment // Some HAL need precise delay adjustment
calibrate_delay_loop(); calibrate_delay_loop();
@@ -1538,7 +1532,7 @@ void setup() {
#endif #endif
#if ENABLED(USE_WATCHDOG) #if ENABLED(USE_WATCHDOG)
SETUP_RUN(watchdog_init()); // Reinit watchdog after HAL_get_reset_source call SETUP_RUN(watchdog_init()); // Reinit watchdog after hal.get_reset_source call
#endif #endif
#if ENABLED(EXTERNAL_CLOSED_LOOP_CONTROLLER) #if ENABLED(EXTERNAL_CLOSED_LOOP_CONTROLLER)

View File

@@ -69,7 +69,7 @@ void CaseLight::update(const bool sflag) {
#if CASELIGHT_USES_BRIGHTNESS #if CASELIGHT_USES_BRIGHTNESS
if (pin_is_pwm()) if (pin_is_pwm())
set_pwm_duty(pin_t(CASE_LIGHT_PIN), ( hal.set_pwm_duty(pin_t(CASE_LIGHT_PIN), (
#if CASE_LIGHT_MAX_PWM == 255 #if CASE_LIGHT_MAX_PWM == 255
n10ct n10ct
#else #else

View File

@@ -76,7 +76,7 @@ void ControllerFan::update() {
thermalManager.soft_pwm_controller_speed = speed; thermalManager.soft_pwm_controller_speed = speed;
#else #else
if (PWM_PIN(CONTROLLER_FAN_PIN)) if (PWM_PIN(CONTROLLER_FAN_PIN))
set_pwm_duty(pin_t(CONTROLLER_FAN_PIN), speed); hal.set_pwm_duty(pin_t(CONTROLLER_FAN_PIN), speed);
else else
WRITE(CONTROLLER_FAN_PIN, speed > 0); WRITE(CONTROLLER_FAN_PIN, speed > 0);
#endif #endif

View File

@@ -41,7 +41,9 @@ extern bool wait_for_user, wait_for_heatup;
void quickresume_stepper(); void quickresume_stepper();
#endif #endif
#if ENABLED(SOFT_RESET_VIA_SERIAL)
void HAL_reboot(); void HAL_reboot();
#endif
class EmergencyParser { class EmergencyParser {

View File

@@ -123,7 +123,7 @@ void LEDLights::set_color(const LEDColor &incol
// If the pins can do PWM then their intensity will be set. // If the pins can do PWM then their intensity will be set.
#define _UPDATE_RGBW(C,c) do { \ #define _UPDATE_RGBW(C,c) do { \
if (PWM_PIN(RGB_LED_##C##_PIN)) \ if (PWM_PIN(RGB_LED_##C##_PIN)) \
set_pwm_duty(pin_t(RGB_LED_##C##_PIN), c); \ hal.set_pwm_duty(pin_t(RGB_LED_##C##_PIN), c); \
else \ else \
WRITE(RGB_LED_##C##_PIN, c ? HIGH : LOW); \ WRITE(RGB_LED_##C##_PIN, c ? HIGH : LOW); \
}while(0) }while(0)

View File

@@ -66,10 +66,10 @@ void SpindleLaser::init() {
#endif #endif
#if ENABLED(SPINDLE_LASER_USE_PWM) #if ENABLED(SPINDLE_LASER_USE_PWM)
SET_PWM(SPINDLE_LASER_PWM_PIN); SET_PWM(SPINDLE_LASER_PWM_PIN);
set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_PWM_OFF); // Set to lowest speed hal.set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_PWM_OFF); // Set to lowest speed
#endif #endif
#if ENABLED(HAL_CAN_SET_PWM_FREQ) && defined(SPINDLE_LASER_FREQUENCY) #if ENABLED(HAL_CAN_SET_PWM_FREQ) && defined(SPINDLE_LASER_FREQUENCY)
set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_FREQUENCY); hal.set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_FREQUENCY);
TERN_(MARLIN_DEV_MODE, frequency = SPINDLE_LASER_FREQUENCY); TERN_(MARLIN_DEV_MODE, frequency = SPINDLE_LASER_FREQUENCY);
#endif #endif
#if ENABLED(AIR_EVACUATION) #if ENABLED(AIR_EVACUATION)
@@ -90,10 +90,10 @@ void SpindleLaser::init() {
* @param ocr Power value * @param ocr Power value
*/ */
void SpindleLaser::_set_ocr(const uint8_t ocr) { void SpindleLaser::_set_ocr(const uint8_t ocr) {
#if NEEDS_HARDWARE_PWM && SPINDLE_LASER_FREQUENCY #if BOTH(NEEDS_HARDWARE_PWM, HAL_CAN_SET_PWM_FREQ) && SPINDLE_LASER_FREQUENCY
set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), TERN(MARLIN_DEV_MODE, frequency, SPINDLE_LASER_FREQUENCY)); hal.set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), TERN(MARLIN_DEV_MODE, frequency, SPINDLE_LASER_FREQUENCY));
#endif #endif
set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), ocr ^ SPINDLE_LASER_PWM_OFF); hal.set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), ocr ^ SPINDLE_LASER_PWM_OFF);
} }
void SpindleLaser::set_ocr(const uint8_t ocr) { void SpindleLaser::set_ocr(const uint8_t ocr) {

View File

@@ -103,7 +103,7 @@ public:
static void init(); static void init();
#if ENABLED(MARLIN_DEV_MODE) #if ENABLED(MARLIN_DEV_MODE)
static inline void refresh_frequency() { set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), frequency); } static inline void refresh_frequency() { hal.set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), frequency); }
#endif #endif
// Modifying this function should update everywhere // Modifying this function should update everywhere

View File

@@ -126,10 +126,10 @@ void GcodeSuite::M42() {
extDigitalWrite(pin, pin_status); extDigitalWrite(pin, pin_status);
#ifdef ARDUINO_ARCH_STM32 #ifdef ARDUINO_ARCH_STM32
// A simple I/O will be set to 0 by set_pwm_duty() // A simple I/O will be set to 0 by hal.set_pwm_duty()
if (pin_status <= 1 && !PWM_PIN(pin)) return; if (pin_status <= 1 && !PWM_PIN(pin)) return;
#endif #endif
set_pwm_duty(pin, pin_status); hal.set_pwm_duty(pin, pin_status);
} }
#endif // DIRECT_PIN_CONTROL #endif // DIRECT_PIN_CONTROL

View File

@@ -38,7 +38,7 @@
#include "../sd/cardreader.h" #include "../sd/cardreader.h"
#include "../MarlinCore.h" // for kill #include "../MarlinCore.h" // for kill
extern void dump_delay_accuracy_check(); void dump_delay_accuracy_check();
/** /**
* Dn: G-code for development and testing * Dn: G-code for development and testing
@@ -54,7 +54,7 @@ void GcodeSuite::D(const int16_t dcode) {
for (;;) { /* loop forever (watchdog reset) */ } for (;;) { /* loop forever (watchdog reset) */ }
case 0: case 0:
HAL_reboot(); hal.reboot();
break; break;
case 10: case 10:
@@ -74,7 +74,7 @@ void GcodeSuite::D(const int16_t dcode) {
settings.reset(); settings.reset();
settings.save(); settings.save();
#endif #endif
HAL_reboot(); hal.reboot();
} break; } break;
case 2: { // D2 Read / Write SRAM case 2: { // D2 Read / Write SRAM
@@ -189,12 +189,12 @@ void GcodeSuite::D(const int16_t dcode) {
SERIAL_ECHOLNPGM("(USE_WATCHDOG " TERN(USE_WATCHDOG, "ENABLED", "DISABLED") ")"); SERIAL_ECHOLNPGM("(USE_WATCHDOG " TERN(USE_WATCHDOG, "ENABLED", "DISABLED") ")");
thermalManager.disable_all_heaters(); thermalManager.disable_all_heaters();
delay(1000); // Allow time to print delay(1000); // Allow time to print
DISABLE_ISRS(); hal.isr_off();
// Use a low-level delay that does not rely on interrupts to function // Use a low-level delay that does not rely on interrupts to function
// Do not spin forever, to avoid thermal risks if heaters are enabled and // Do not spin forever, to avoid thermal risks if heaters are enabled and
// watchdog does not work. // watchdog does not work.
for (int i = 10000; i--;) DELAY_US(1000UL); for (int i = 10000; i--;) DELAY_US(1000UL);
ENABLE_ISRS(); hal.isr_on();
SERIAL_ECHOLNPGM("FAILURE: Watchdog did not trigger board reset."); SERIAL_ECHOLNPGM("FAILURE: Watchdog did not trigger board reset.");
} break; } break;

View File

@@ -3850,3 +3850,10 @@ static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive.");
#undef _TEST_PWM #undef _TEST_PWM
#undef _LINEAR_AXES_STR #undef _LINEAR_AXES_STR
#undef _LOGICAL_AXES_STR #undef _LOGICAL_AXES_STR
// JTAG support in the HAL
#if ENABLED(DISABLE_DEBUG) && !defined(JTAGSWD_DISABLE)
#error "DISABLE_DEBUG is not supported for the selected MCU/Board."
#elif ENABLED(DISABLE_JTAG) && !defined(JTAG_DISABLE)
#error "DISABLE_JTAG is not supported for the selected MCU/Board."
#endif

View File

@@ -282,9 +282,9 @@ void MarlinUI::init_lcd() {
#if PIN_EXISTS(LCD_RESET) #if PIN_EXISTS(LCD_RESET)
// Perform a clean hardware reset with needed delays // Perform a clean hardware reset with needed delays
OUT_WRITE(LCD_RESET_PIN, LOW); OUT_WRITE(LCD_RESET_PIN, LOW);
_delay_ms(5); hal.delay_ms(5);
WRITE(LCD_RESET_PIN, HIGH); WRITE(LCD_RESET_PIN, HIGH);
_delay_ms(5); hal.delay_ms(5);
u8g.begin(); u8g.begin();
#endif #endif

View File

@@ -2149,7 +2149,7 @@ void RebootPrinter() {
thermalManager.disable_all_heaters(); thermalManager.disable_all_heaters();
planner.finish_and_disable(); planner.finish_and_disable();
DWIN_RebootScreen(); DWIN_RebootScreen();
HAL_reboot(); hal.reboot();
} }
void Goto_InfoMenu(){ void Goto_InfoMenu(){

View File

@@ -1345,7 +1345,7 @@ void Endstops::update() {
ES_REPORT_CHANGE(K_MAX); ES_REPORT_CHANGE(K_MAX);
#endif #endif
SERIAL_ECHOLNPGM("\n"); SERIAL_ECHOLNPGM("\n");
set_pwm_duty(pin_t(LED_PIN), local_LED_status); hal.set_pwm_duty(pin_t(LED_PIN), local_LED_status);
local_LED_status ^= 255; local_LED_status ^= 255;
old_live_state_local = live_state_local; old_live_state_local = live_state_local;
} }

View File

@@ -1264,7 +1264,7 @@ void Planner::recalculate() {
#if ENABLED(FAN_SOFT_PWM) #if ENABLED(FAN_SOFT_PWM)
#define _FAN_SET(F) thermalManager.soft_pwm_amount_fan[F] = CALC_FAN_SPEED(F); #define _FAN_SET(F) thermalManager.soft_pwm_amount_fan[F] = CALC_FAN_SPEED(F);
#else #else
#define _FAN_SET(F) set_pwm_duty(pin_t(FAN##F##_PIN), CALC_FAN_SPEED(F)); #define _FAN_SET(F) hal.set_pwm_duty(pin_t(FAN##F##_PIN), CALC_FAN_SPEED(F));
#endif #endif
#define FAN_SET(F) do{ kickstart_fan(fan_speed, ms, F); _FAN_SET(F); }while(0) #define FAN_SET(F) do{ kickstart_fan(fan_speed, ms, F); _FAN_SET(F); }while(0)
@@ -1400,8 +1400,8 @@ void Planner::check_axes_activity() {
TERN_(AUTOTEMP, autotemp_task()); TERN_(AUTOTEMP, autotemp_task());
#if ENABLED(BARICUDA) #if ENABLED(BARICUDA)
TERN_(HAS_HEATER_1, set_pwm_duty(pin_t(HEATER_1_PIN), tail_valve_pressure)); TERN_(HAS_HEATER_1, hal.set_pwm_duty(pin_t(HEATER_1_PIN), tail_valve_pressure));
TERN_(HAS_HEATER_2, set_pwm_duty(pin_t(HEATER_2_PIN), tail_e_to_p_pressure)); TERN_(HAS_HEATER_2, hal.set_pwm_duty(pin_t(HEATER_2_PIN), tail_e_to_p_pressure));
#endif #endif
} }

View File

@@ -30,7 +30,7 @@
#include "servo.h" #include "servo.h"
HAL_SERVO_LIB servo[NUM_SERVOS]; hal_servo_t servo[NUM_SERVOS];
#if ENABLED(EDITABLE_SERVO_ANGLES) #if ENABLED(EDITABLE_SERVO_ANGLES)
uint16_t servo_angles[NUM_SERVOS][2]; uint16_t servo_angles[NUM_SERVOS][2];

View File

@@ -112,5 +112,5 @@
#define MOVE_SERVO(I, P) servo[I].move(P) #define MOVE_SERVO(I, P) servo[I].move(P)
#define DETACH_SERVO(I) servo[I].detach() #define DETACH_SERVO(I) servo[I].detach()
extern HAL_SERVO_LIB servo[NUM_SERVOS]; extern hal_servo_t servo[NUM_SERVOS];
void servo_init(); void servo_init();

View File

@@ -1474,7 +1474,7 @@ void Stepper::isr() {
#ifndef __AVR__ #ifndef __AVR__
// Disable interrupts, to avoid ISR preemption while we reprogram the period // Disable interrupts, to avoid ISR preemption while we reprogram the period
// (AVR enters the ISR with global interrupts disabled, so no need to do it here) // (AVR enters the ISR with global interrupts disabled, so no need to do it here)
DISABLE_ISRS(); hal.isr_off();
#endif #endif
// Program timer compare for the maximum period, so it does NOT // Program timer compare for the maximum period, so it does NOT
@@ -1492,7 +1492,7 @@ void Stepper::isr() {
hal_timer_t min_ticks; hal_timer_t min_ticks;
do { do {
// Enable ISRs to reduce USART processing latency // Enable ISRs to reduce USART processing latency
ENABLE_ISRS(); hal.isr_on();
if (!nextMainISR) pulse_phase_isr(); // 0 = Do coordinated axes Stepper pulses if (!nextMainISR) pulse_phase_isr(); // 0 = Do coordinated axes Stepper pulses
@@ -1576,7 +1576,7 @@ void Stepper::isr() {
* is less than the current count due to something preempting between the * is less than the current count due to something preempting between the
* read and the write of the new period value). * read and the write of the new period value).
*/ */
DISABLE_ISRS(); hal.isr_off();
/** /**
* Get the current tick value + margin * Get the current tick value + margin
@@ -1611,7 +1611,7 @@ void Stepper::isr() {
HAL_timer_set_compare(MF_TIMER_STEP, hal_timer_t(next_isr_ticks)); HAL_timer_set_compare(MF_TIMER_STEP, hal_timer_t(next_isr_ticks));
// Don't forget to finally reenable interrupts // Don't forget to finally reenable interrupts
ENABLE_ISRS(); hal.isr_on();
} }
#if MINIMUM_STEPPER_PULSE || MAXIMUM_STEPPER_RATE #if MINIMUM_STEPPER_PULSE || MAXIMUM_STEPPER_RATE
@@ -3261,7 +3261,7 @@ void Stepper::report_positions() {
#elif HAS_MOTOR_CURRENT_PWM #elif HAS_MOTOR_CURRENT_PWM
#define _WRITE_CURRENT_PWM(P) set_pwm_duty(pin_t(MOTOR_CURRENT_PWM_## P ##_PIN), 255L * current / (MOTOR_CURRENT_PWM_RANGE)) #define _WRITE_CURRENT_PWM(P) hal.set_pwm_duty(pin_t(MOTOR_CURRENT_PWM_## P ##_PIN), 255L * current / (MOTOR_CURRENT_PWM_RANGE))
switch (driver) { switch (driver) {
case 0: case 0:
#if PIN_EXISTS(MOTOR_CURRENT_PWM_X) #if PIN_EXISTS(MOTOR_CURRENT_PWM_X)

View File

@@ -326,7 +326,7 @@ PGMSTR(str_t_heating_failed, STR_T_HEATING_FAILED);
#define _INIT_FAN_PIN(P) do{ if (PWM_PIN(P)) SET_PWM(P); else _INIT_SOFT_FAN(P); }while(0) #define _INIT_FAN_PIN(P) do{ if (PWM_PIN(P)) SET_PWM(P); else _INIT_SOFT_FAN(P); }while(0)
#endif #endif
#if ENABLED(FAST_PWM_FAN) #if ENABLED(FAST_PWM_FAN)
#define SET_FAST_PWM_FREQ(P) set_pwm_frequency(P, FAST_PWM_FAN_FREQUENCY) #define SET_FAST_PWM_FREQ(P) hal.set_pwm_frequency(pin_t(P), FAST_PWM_FAN_FREQUENCY)
#else #else
#define SET_FAST_PWM_FREQ(P) NOOP #define SET_FAST_PWM_FREQ(P) NOOP
#endif #endif
@@ -813,7 +813,7 @@ volatile bool Temperature::raw_temps_ready = false;
} }
// Run HAL idle tasks // Run HAL idle tasks
TERN_(HAL_IDLETASK, HAL_idletask()); hal.idletask();
// Run UI update // Run UI update
TERN(HAS_DWIN_E3V2_BASIC, DWIN_Update(), ui.update()); TERN(HAS_DWIN_E3V2_BASIC, DWIN_Update(), ui.update());
@@ -912,7 +912,7 @@ int16_t Temperature::getHeaterPower(const heater_id_t heater_id) {
#define _UPDATE_AUTO_FAN(P,D,A) do{ \ #define _UPDATE_AUTO_FAN(P,D,A) do{ \
if (PWM_PIN(P##_AUTO_FAN_PIN) && A < 255) \ if (PWM_PIN(P##_AUTO_FAN_PIN) && A < 255) \
set_pwm_duty(pin_t(P##_AUTO_FAN_PIN), D ? A : 0); \ hal.set_pwm_duty(pin_t(P##_AUTO_FAN_PIN), D ? A : 0); \
else \ else \
WRITE(P##_AUTO_FAN_PIN, D); \ WRITE(P##_AUTO_FAN_PIN, D); \
}while(0) }while(0)
@@ -2326,73 +2326,73 @@ void Temperature::init() {
TERN_(HAS_MAXTC_SW_SPI, max_tc_spi.init()); TERN_(HAS_MAXTC_SW_SPI, max_tc_spi.init());
HAL_adc_init(); hal.adc_init();
#if HAS_TEMP_ADC_0 #if HAS_TEMP_ADC_0
HAL_ANALOG_SELECT(TEMP_0_PIN); hal.adc_enable(TEMP_0_PIN);
#endif #endif
#if HAS_TEMP_ADC_1 #if HAS_TEMP_ADC_1
HAL_ANALOG_SELECT(TEMP_1_PIN); hal.adc_enable(TEMP_1_PIN);
#endif #endif
#if HAS_TEMP_ADC_2 #if HAS_TEMP_ADC_2
HAL_ANALOG_SELECT(TEMP_2_PIN); hal.adc_enable(TEMP_2_PIN);
#endif #endif
#if HAS_TEMP_ADC_3 #if HAS_TEMP_ADC_3
HAL_ANALOG_SELECT(TEMP_3_PIN); hal.adc_enable(TEMP_3_PIN);
#endif #endif
#if HAS_TEMP_ADC_4 #if HAS_TEMP_ADC_4
HAL_ANALOG_SELECT(TEMP_4_PIN); hal.adc_enable(TEMP_4_PIN);
#endif #endif
#if HAS_TEMP_ADC_5 #if HAS_TEMP_ADC_5
HAL_ANALOG_SELECT(TEMP_5_PIN); hal.adc_enable(TEMP_5_PIN);
#endif #endif
#if HAS_TEMP_ADC_6 #if HAS_TEMP_ADC_6
HAL_ANALOG_SELECT(TEMP_6_PIN); hal.adc_enable(TEMP_6_PIN);
#endif #endif
#if HAS_TEMP_ADC_7 #if HAS_TEMP_ADC_7
HAL_ANALOG_SELECT(TEMP_7_PIN); hal.adc_enable(TEMP_7_PIN);
#endif #endif
#if HAS_JOY_ADC_X #if HAS_JOY_ADC_X
HAL_ANALOG_SELECT(JOY_X_PIN); hal.adc_enable(JOY_X_PIN);
#endif #endif
#if HAS_JOY_ADC_Y #if HAS_JOY_ADC_Y
HAL_ANALOG_SELECT(JOY_Y_PIN); hal.adc_enable(JOY_Y_PIN);
#endif #endif
#if HAS_JOY_ADC_Z #if HAS_JOY_ADC_Z
HAL_ANALOG_SELECT(JOY_Z_PIN); hal.adc_enable(JOY_Z_PIN);
#endif #endif
#if HAS_JOY_ADC_EN #if HAS_JOY_ADC_EN
SET_INPUT_PULLUP(JOY_EN_PIN); SET_INPUT_PULLUP(JOY_EN_PIN);
#endif #endif
#if HAS_TEMP_ADC_BED #if HAS_TEMP_ADC_BED
HAL_ANALOG_SELECT(TEMP_BED_PIN); hal.adc_enable(TEMP_BED_PIN);
#endif #endif
#if HAS_TEMP_ADC_CHAMBER #if HAS_TEMP_ADC_CHAMBER
HAL_ANALOG_SELECT(TEMP_CHAMBER_PIN); hal.adc_enable(TEMP_CHAMBER_PIN);
#endif #endif
#if HAS_TEMP_ADC_COOLER #if HAS_TEMP_ADC_COOLER
HAL_ANALOG_SELECT(TEMP_COOLER_PIN); hal.adc_enable(TEMP_COOLER_PIN);
#endif #endif
#if HAS_TEMP_ADC_PROBE #if HAS_TEMP_ADC_PROBE
HAL_ANALOG_SELECT(TEMP_PROBE_PIN); hal.adc_enable(TEMP_PROBE_PIN);
#endif #endif
#if HAS_TEMP_ADC_BOARD #if HAS_TEMP_ADC_BOARD
HAL_ANALOG_SELECT(TEMP_BOARD_PIN); hal.adc_enable(TEMP_BOARD_PIN);
#endif #endif
#if HAS_TEMP_ADC_REDUNDANT #if HAS_TEMP_ADC_REDUNDANT
HAL_ANALOG_SELECT(TEMP_REDUNDANT_PIN); hal.adc_enable(TEMP_REDUNDANT_PIN);
#endif #endif
#if ENABLED(FILAMENT_WIDTH_SENSOR) #if ENABLED(FILAMENT_WIDTH_SENSOR)
HAL_ANALOG_SELECT(FILWIDTH_PIN); hal.adc_enable(FILWIDTH_PIN);
#endif #endif
#if HAS_ADC_BUTTONS #if HAS_ADC_BUTTONS
HAL_ANALOG_SELECT(ADC_KEYPAD_PIN); hal.adc_enable(ADC_KEYPAD_PIN);
#endif #endif
#if ENABLED(POWER_MONITOR_CURRENT) #if ENABLED(POWER_MONITOR_CURRENT)
HAL_ANALOG_SELECT(POWER_MONITOR_CURRENT_PIN); hal.adc_enable(POWER_MONITOR_CURRENT_PIN);
#endif #endif
#if ENABLED(POWER_MONITOR_VOLTAGE) #if ENABLED(POWER_MONITOR_VOLTAGE)
HAL_ANALOG_SELECT(POWER_MONITOR_VOLTAGE_PIN); hal.adc_enable(POWER_MONITOR_VOLTAGE_PIN);
#endif #endif
HAL_timer_start(MF_TIMER_TEMP, TEMP_TIMER_FREQUENCY); HAL_timer_start(MF_TIMER_TEMP, TEMP_TIMER_FREQUENCY);
@@ -3333,8 +3333,8 @@ void Temperature::isr() {
* This gives each ADC 0.9765ms to charge up. * This gives each ADC 0.9765ms to charge up.
*/ */
#define ACCUMULATE_ADC(obj) do{ \ #define ACCUMULATE_ADC(obj) do{ \
if (!HAL_ADC_READY()) next_sensor_state = adc_sensor_state; \ if (!hal.adc_ready()) next_sensor_state = adc_sensor_state; \
else obj.sample(HAL_READ_ADC()); \ else obj.sample(hal.adc_value()); \
}while(0) }while(0)
ADCSensorState next_sensor_state = adc_sensor_state < SensorsReady ? (ADCSensorState)(int(adc_sensor_state) + 1) : StartSampling; ADCSensorState next_sensor_state = adc_sensor_state < SensorsReady ? (ADCSensorState)(int(adc_sensor_state) + 1) : StartSampling;
@@ -3366,115 +3366,115 @@ void Temperature::isr() {
break; break;
#if HAS_TEMP_ADC_0 #if HAS_TEMP_ADC_0
case PrepareTemp_0: HAL_START_ADC(TEMP_0_PIN); break; case PrepareTemp_0: hal.adc_start(TEMP_0_PIN); break;
case MeasureTemp_0: ACCUMULATE_ADC(temp_hotend[0]); break; case MeasureTemp_0: ACCUMULATE_ADC(temp_hotend[0]); break;
#endif #endif
#if HAS_TEMP_ADC_BED #if HAS_TEMP_ADC_BED
case PrepareTemp_BED: HAL_START_ADC(TEMP_BED_PIN); break; case PrepareTemp_BED: hal.adc_start(TEMP_BED_PIN); break;
case MeasureTemp_BED: ACCUMULATE_ADC(temp_bed); break; case MeasureTemp_BED: ACCUMULATE_ADC(temp_bed); break;
#endif #endif
#if HAS_TEMP_ADC_CHAMBER #if HAS_TEMP_ADC_CHAMBER
case PrepareTemp_CHAMBER: HAL_START_ADC(TEMP_CHAMBER_PIN); break; case PrepareTemp_CHAMBER: hal.adc_start(TEMP_CHAMBER_PIN); break;
case MeasureTemp_CHAMBER: ACCUMULATE_ADC(temp_chamber); break; case MeasureTemp_CHAMBER: ACCUMULATE_ADC(temp_chamber); break;
#endif #endif
#if HAS_TEMP_ADC_COOLER #if HAS_TEMP_ADC_COOLER
case PrepareTemp_COOLER: HAL_START_ADC(TEMP_COOLER_PIN); break; case PrepareTemp_COOLER: hal.adc_start(TEMP_COOLER_PIN); break;
case MeasureTemp_COOLER: ACCUMULATE_ADC(temp_cooler); break; case MeasureTemp_COOLER: ACCUMULATE_ADC(temp_cooler); break;
#endif #endif
#if HAS_TEMP_ADC_PROBE #if HAS_TEMP_ADC_PROBE
case PrepareTemp_PROBE: HAL_START_ADC(TEMP_PROBE_PIN); break; case PrepareTemp_PROBE: hal.adc_start(TEMP_PROBE_PIN); break;
case MeasureTemp_PROBE: ACCUMULATE_ADC(temp_probe); break; case MeasureTemp_PROBE: ACCUMULATE_ADC(temp_probe); break;
#endif #endif
#if HAS_TEMP_ADC_BOARD #if HAS_TEMP_ADC_BOARD
case PrepareTemp_BOARD: HAL_START_ADC(TEMP_BOARD_PIN); break; case PrepareTemp_BOARD: hal.adc_start(TEMP_BOARD_PIN); break;
case MeasureTemp_BOARD: ACCUMULATE_ADC(temp_board); break; case MeasureTemp_BOARD: ACCUMULATE_ADC(temp_board); break;
#endif #endif
#if HAS_TEMP_ADC_REDUNDANT #if HAS_TEMP_ADC_REDUNDANT
case PrepareTemp_REDUNDANT: HAL_START_ADC(TEMP_REDUNDANT_PIN); break; case PrepareTemp_REDUNDANT: hal.adc_start(TEMP_REDUNDANT_PIN); break;
case MeasureTemp_REDUNDANT: ACCUMULATE_ADC(temp_redundant); break; case MeasureTemp_REDUNDANT: ACCUMULATE_ADC(temp_redundant); break;
#endif #endif
#if HAS_TEMP_ADC_1 #if HAS_TEMP_ADC_1
case PrepareTemp_1: HAL_START_ADC(TEMP_1_PIN); break; case PrepareTemp_1: hal.adc_start(TEMP_1_PIN); break;
case MeasureTemp_1: ACCUMULATE_ADC(temp_hotend[1]); break; case MeasureTemp_1: ACCUMULATE_ADC(temp_hotend[1]); break;
#endif #endif
#if HAS_TEMP_ADC_2 #if HAS_TEMP_ADC_2
case PrepareTemp_2: HAL_START_ADC(TEMP_2_PIN); break; case PrepareTemp_2: hal.adc_start(TEMP_2_PIN); break;
case MeasureTemp_2: ACCUMULATE_ADC(temp_hotend[2]); break; case MeasureTemp_2: ACCUMULATE_ADC(temp_hotend[2]); break;
#endif #endif
#if HAS_TEMP_ADC_3 #if HAS_TEMP_ADC_3
case PrepareTemp_3: HAL_START_ADC(TEMP_3_PIN); break; case PrepareTemp_3: hal.adc_start(TEMP_3_PIN); break;
case MeasureTemp_3: ACCUMULATE_ADC(temp_hotend[3]); break; case MeasureTemp_3: ACCUMULATE_ADC(temp_hotend[3]); break;
#endif #endif
#if HAS_TEMP_ADC_4 #if HAS_TEMP_ADC_4
case PrepareTemp_4: HAL_START_ADC(TEMP_4_PIN); break; case PrepareTemp_4: hal.adc_start(TEMP_4_PIN); break;
case MeasureTemp_4: ACCUMULATE_ADC(temp_hotend[4]); break; case MeasureTemp_4: ACCUMULATE_ADC(temp_hotend[4]); break;
#endif #endif
#if HAS_TEMP_ADC_5 #if HAS_TEMP_ADC_5
case PrepareTemp_5: HAL_START_ADC(TEMP_5_PIN); break; case PrepareTemp_5: hal.adc_start(TEMP_5_PIN); break;
case MeasureTemp_5: ACCUMULATE_ADC(temp_hotend[5]); break; case MeasureTemp_5: ACCUMULATE_ADC(temp_hotend[5]); break;
#endif #endif
#if HAS_TEMP_ADC_6 #if HAS_TEMP_ADC_6
case PrepareTemp_6: HAL_START_ADC(TEMP_6_PIN); break; case PrepareTemp_6: hal.adc_start(TEMP_6_PIN); break;
case MeasureTemp_6: ACCUMULATE_ADC(temp_hotend[6]); break; case MeasureTemp_6: ACCUMULATE_ADC(temp_hotend[6]); break;
#endif #endif
#if HAS_TEMP_ADC_7 #if HAS_TEMP_ADC_7
case PrepareTemp_7: HAL_START_ADC(TEMP_7_PIN); break; case PrepareTemp_7: hal.adc_start(TEMP_7_PIN); break;
case MeasureTemp_7: ACCUMULATE_ADC(temp_hotend[7]); break; case MeasureTemp_7: ACCUMULATE_ADC(temp_hotend[7]); break;
#endif #endif
#if ENABLED(FILAMENT_WIDTH_SENSOR) #if ENABLED(FILAMENT_WIDTH_SENSOR)
case Prepare_FILWIDTH: HAL_START_ADC(FILWIDTH_PIN); break; case Prepare_FILWIDTH: hal.adc_start(FILWIDTH_PIN); break;
case Measure_FILWIDTH: case Measure_FILWIDTH:
if (!HAL_ADC_READY()) next_sensor_state = adc_sensor_state; // Redo this state if (!hal.adc_ready()) next_sensor_state = adc_sensor_state; // Redo this state
else filwidth.accumulate(HAL_READ_ADC()); else filwidth.accumulate(hal.adc_value());
break; break;
#endif #endif
#if ENABLED(POWER_MONITOR_CURRENT) #if ENABLED(POWER_MONITOR_CURRENT)
case Prepare_POWER_MONITOR_CURRENT: case Prepare_POWER_MONITOR_CURRENT:
HAL_START_ADC(POWER_MONITOR_CURRENT_PIN); hal.adc_start(POWER_MONITOR_CURRENT_PIN);
break; break;
case Measure_POWER_MONITOR_CURRENT: case Measure_POWER_MONITOR_CURRENT:
if (!HAL_ADC_READY()) next_sensor_state = adc_sensor_state; // Redo this state if (!hal.adc_ready()) next_sensor_state = adc_sensor_state; // Redo this state
else power_monitor.add_current_sample(HAL_READ_ADC()); else power_monitor.add_current_sample(hal.adc_value());
break; break;
#endif #endif
#if ENABLED(POWER_MONITOR_VOLTAGE) #if ENABLED(POWER_MONITOR_VOLTAGE)
case Prepare_POWER_MONITOR_VOLTAGE: case Prepare_POWER_MONITOR_VOLTAGE:
HAL_START_ADC(POWER_MONITOR_VOLTAGE_PIN); hal.adc_start(POWER_MONITOR_VOLTAGE_PIN);
break; break;
case Measure_POWER_MONITOR_VOLTAGE: case Measure_POWER_MONITOR_VOLTAGE:
if (!HAL_ADC_READY()) next_sensor_state = adc_sensor_state; // Redo this state if (!hal.adc_ready()) next_sensor_state = adc_sensor_state; // Redo this state
else power_monitor.add_voltage_sample(HAL_READ_ADC()); else power_monitor.add_voltage_sample(hal.adc_value());
break; break;
#endif #endif
#if HAS_JOY_ADC_X #if HAS_JOY_ADC_X
case PrepareJoy_X: HAL_START_ADC(JOY_X_PIN); break; case PrepareJoy_X: hal.adc_start(JOY_X_PIN); break;
case MeasureJoy_X: ACCUMULATE_ADC(joystick.x); break; case MeasureJoy_X: ACCUMULATE_ADC(joystick.x); break;
#endif #endif
#if HAS_JOY_ADC_Y #if HAS_JOY_ADC_Y
case PrepareJoy_Y: HAL_START_ADC(JOY_Y_PIN); break; case PrepareJoy_Y: hal.adc_start(JOY_Y_PIN); break;
case MeasureJoy_Y: ACCUMULATE_ADC(joystick.y); break; case MeasureJoy_Y: ACCUMULATE_ADC(joystick.y); break;
#endif #endif
#if HAS_JOY_ADC_Z #if HAS_JOY_ADC_Z
case PrepareJoy_Z: HAL_START_ADC(JOY_Z_PIN); break; case PrepareJoy_Z: hal.adc_start(JOY_Z_PIN); break;
case MeasureJoy_Z: ACCUMULATE_ADC(joystick.z); break; case MeasureJoy_Z: ACCUMULATE_ADC(joystick.z); break;
#endif #endif
@@ -3482,12 +3482,12 @@ void Temperature::isr() {
#ifndef ADC_BUTTON_DEBOUNCE_DELAY #ifndef ADC_BUTTON_DEBOUNCE_DELAY
#define ADC_BUTTON_DEBOUNCE_DELAY 16 #define ADC_BUTTON_DEBOUNCE_DELAY 16
#endif #endif
case Prepare_ADC_KEY: HAL_START_ADC(ADC_KEYPAD_PIN); break; case Prepare_ADC_KEY: hal.adc_start(ADC_KEYPAD_PIN); break;
case Measure_ADC_KEY: case Measure_ADC_KEY:
if (!HAL_ADC_READY()) if (!hal.adc_ready())
next_sensor_state = adc_sensor_state; // redo this state next_sensor_state = adc_sensor_state; // redo this state
else if (ADCKey_count < ADC_BUTTON_DEBOUNCE_DELAY) { else if (ADCKey_count < ADC_BUTTON_DEBOUNCE_DELAY) {
raw_ADCKey_value = HAL_READ_ADC(); raw_ADCKey_value = hal.adc_value();
if (raw_ADCKey_value <= 900UL * HAL_ADC_RANGE / 1024UL) { if (raw_ADCKey_value <= 900UL * HAL_ADC_RANGE / 1024UL) {
NOMORE(current_ADCKey_raw, raw_ADCKey_value); NOMORE(current_ADCKey_raw, raw_ADCKey_value);
ADCKey_count++; ADCKey_count++;

View File

@@ -34,14 +34,14 @@ src_filter = ${common.default_src_filter} +<src/HAL/LINUX>
[simulator_common] [simulator_common]
platform = native platform = native
framework = framework =
build_flags = ${common.build_flags} -std=gnu++17 -D__PLAT_NATIVE_SIM__ -DU8G_HAL_LINKS -I/usr/include/SDL2 -IMarlin -IMarlin/src/HAL/NATIVE_SIM/include -IMarlin/src/HAL/NATIVE_SIM/u8g build_flags = ${common.build_flags} -std=gnu++17 -D__PLAT_NATIVE_SIM__ -DU8G_HAL_LINKS -I/usr/include/SDL2 -IMarlin -IMarlin/src/HAL/NATIVE_SIM/u8g
src_build_flags = -Wall -Wno-expansion-to-defined -Wcast-align src_build_flags = -Wall -Wno-expansion-to-defined -Wcast-align
release_flags = -g0 -O3 -flto release_flags = -g0 -O3 -flto
debug_build_flags = -fstack-protector-strong -g -g3 -ggdb debug_build_flags = -fstack-protector-strong -g -g3 -ggdb
lib_compat_mode = off lib_compat_mode = off
src_filter = ${common.default_src_filter} +<src/HAL/NATIVE_SIM> src_filter = ${common.default_src_filter} +<src/HAL/NATIVE_SIM>
lib_deps = ${common.lib_deps} lib_deps = ${common.lib_deps}
MarlinSimUI=https://github.com/p3p/MarlinSimUI/archive/master.zip MarlinSimUI=https://github.com/thinkyhead/MarlinSimUI/archive/updated_marlin_hal_2093.zip
Adafruit NeoPixel=https://github.com/p3p/Adafruit_NeoPixel/archive/marlin_sim_native.zip Adafruit NeoPixel=https://github.com/p3p/Adafruit_NeoPixel/archive/marlin_sim_native.zip
LiquidCrystal=https://github.com/p3p/LiquidCrystal/archive/master.zip LiquidCrystal=https://github.com/p3p/LiquidCrystal/archive/master.zip
extra_scripts = ${common.extra_scripts} extra_scripts = ${common.extra_scripts}