♻️ Refactor HAL as singleton (#23357, #23871, #23897)

This commit is contained in:
Scott Lahteine
2022-02-17 18:50:31 -06:00
committed by Scott Lahteine
parent 428b67db31
commit 56cec9690a
81 changed files with 1976 additions and 1418 deletions

View File

@ -33,6 +33,10 @@
#include "timers.h"
#include <Wire.h>
// ------------------------
// Serial ports
// ------------------------
#define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X)
#define IMPLEMENT_SERIAL(X) _IMPLEMENT_SERIAL(X)
#if WITHIN(SERIAL_PORT, 0, 3)
@ -40,75 +44,42 @@
#endif
USBSerialType USBSerial(false, SerialUSB);
uint16_t HAL_adc_result, HAL_adc_select;
// ------------------------
// Class Utilities
// ------------------------
static const uint8_t pin2sc1a[] = {
0x07, // 0/A0 AD_B1_02
0x08, // 1/A1 AD_B1_03
0x0C, // 2/A2 AD_B1_07
0x0B, // 3/A3 AD_B1_06
0x06, // 4/A4 AD_B1_01
0x05, // 5/A5 AD_B1_00
0x0F, // 6/A6 AD_B1_10
0x00, // 7/A7 AD_B1_11
0x0D, // 8/A8 AD_B1_08
0x0E, // 9/A9 AD_B1_09
0x01, // 24/A10 AD_B0_12
0x02, // 25/A11 AD_B0_13
0x83, // 26/A12 AD_B1_14 - only on ADC2, 3
0x84, // 27/A13 AD_B1_15 - only on ADC2, 4
0x07, // 14/A0 AD_B1_02
0x08, // 15/A1 AD_B1_03
0x0C, // 16/A2 AD_B1_07
0x0B, // 17/A3 AD_B1_06
0x06, // 18/A4 AD_B1_01
0x05, // 19/A5 AD_B1_00
0x0F, // 20/A6 AD_B1_10
0x00, // 21/A7 AD_B1_11
0x0D, // 22/A8 AD_B1_08
0x0E, // 23/A9 AD_B1_09
0x01, // 24/A10 AD_B0_12
0x02, // 25/A11 AD_B0_13
0x83, // 26/A12 AD_B1_14 - only on ADC2, 3
0x84, // 27/A13 AD_B1_15 - only on ADC2, 4
#ifdef ARDUINO_TEENSY41
0xFF, // 28
0xFF, // 29
0xFF, // 30
0xFF, // 31
0xFF, // 32
0xFF, // 33
0xFF, // 34
0xFF, // 35
0xFF, // 36
0xFF, // 37
0x81, // 38/A14 AD_B1_12 - only on ADC2, 1
0x82, // 39/A15 AD_B1_13 - only on ADC2, 2
0x09, // 40/A16 AD_B1_04
0x0A, // 41/A17 AD_B1_05
#endif
};
#define __bss_end _ebss
/*
// disable interrupts
void cli() { noInterrupts(); }
extern "C" {
extern char __bss_end;
extern char __heap_start;
extern void* __brkval;
// enable interrupts
void sei() { interrupts(); }
*/
void HAL_adc_init() {
analog_init();
while (ADC1_GC & ADC_GC_CAL) ;
while (ADC2_GC & ADC_GC_CAL) ;
// 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;
}
}
void HAL_clear_reset_source() {
uint32_t reset_source = SRC_SRSR;
SRC_SRSR = reset_source;
// ------------------------
// 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);
}
uint8_t HAL_get_reset_source() {
// ------------------------
// 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;
@ -121,57 +92,92 @@ uint8_t HAL_get_reset_source() {
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 MarlinHAL::clear_reset_source() {
uint32_t reset_source = SRC_SRSR;
SRC_SRSR = reset_source;
}
void HAL_adc_start_conversion(const uint8_t adc_pin) {
// 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[] = {
0x07, // 0/A0 AD_B1_02
0x08, // 1/A1 AD_B1_03
0x0C, // 2/A2 AD_B1_07
0x0B, // 3/A3 AD_B1_06
0x06, // 4/A4 AD_B1_01
0x05, // 5/A5 AD_B1_00
0x0F, // 6/A6 AD_B1_10
0x00, // 7/A7 AD_B1_11
0x0D, // 8/A8 AD_B1_08
0x0E, // 9/A9 AD_B1_09
0x01, // 24/A10 AD_B0_12
0x02, // 25/A11 AD_B0_13
0x83, // 26/A12 AD_B1_14 - only on ADC2, 3
0x84, // 27/A13 AD_B1_15 - only on ADC2, 4
0x07, // 14/A0 AD_B1_02
0x08, // 15/A1 AD_B1_03
0x0C, // 16/A2 AD_B1_07
0x0B, // 17/A3 AD_B1_06
0x06, // 18/A4 AD_B1_01
0x05, // 19/A5 AD_B1_00
0x0F, // 20/A6 AD_B1_10
0x00, // 21/A7 AD_B1_11
0x0D, // 22/A8 AD_B1_08
0x0E, // 23/A9 AD_B1_09
0x01, // 24/A10 AD_B0_12
0x02, // 25/A11 AD_B0_13
0x83, // 26/A12 AD_B1_14 - only on ADC2, 3
0x84, // 27/A13 AD_B1_15 - only on ADC2, 4
#ifdef ARDUINO_TEENSY41
0xFF, // 28
0xFF, // 29
0xFF, // 30
0xFF, // 31
0xFF, // 32
0xFF, // 33
0xFF, // 34
0xFF, // 35
0xFF, // 36
0xFF, // 37
0x81, // 38/A14 AD_B1_12 - only on ADC2, 1
0x82, // 39/A15 AD_B1_13 - only on ADC2, 2
0x09, // 40/A16 AD_B1_04
0x0A, // 41/A17 AD_B1_05
#endif
};
const uint16_t pin = pin2sc1a[adc_pin];
if (pin == 0xFF) {
HAL_adc_select = -1; // Digital only
adc_select = -1; // Digital only
}
else if (pin & 0x80) {
HAL_adc_select = 1;
adc_select = 1;
ADC2_HC0 = pin & 0x7F;
}
else {
HAL_adc_select = 0;
adc_select = 0;
ADC1_HC0 = pin;
}
}
uint16_t HAL_adc_get_result() {
switch (HAL_adc_select) {
uint16_t MarlinHAL::adc_value() {
switch (adc_select) {
case 0:
while (!(ADC1_HS & ADC_HS_COCO0)) ; // wait
while (!(ADC1_HS & ADC_HS_COCO0)) { /* wait */ }
return ADC1_R0;
case 1:
while (!(ADC2_HS & ADC_HS_COCO0)) ; // wait
while (!(ADC2_HS & ADC_HS_COCO0)) { /* wait */ }
return ADC2_R0;
}
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__

View File

@ -41,10 +41,6 @@
#include "../../feature/ethernet.h"
#endif
#define CPU_ST7920_DELAY_1 600
#define CPU_ST7920_DELAY_2 750
#define CPU_ST7920_DELAY_3 750
// ------------------------
// Defines
// ------------------------
@ -55,7 +51,23 @@
#define IS_TEENSY41 1
#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"
#define Serial0 Serial
#define _DECLARE_SERIAL(X) \
typedef ForwardSerial1Class<decltype(Serial##X)> DefaultSerial##X; \
@ -89,41 +101,47 @@ extern USBSerialType USBSerial;
#endif
#endif
#define HAL_SERVO_LIB libServo
// ------------------------
// Types
// ------------------------
class libServo;
typedef libServo hal_servo_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
#define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1)
#endif
#define CRITICAL_SECTION_START() uint32_t primask = __get_primask(); __disable_irq()
#define CRITICAL_SECTION_END() if (!primask) __enable_irq()
#define ISRS_ENABLED() (!__get_primask())
#define ENABLE_ISRS() __enable_irq()
#define DISABLE_ISRS() __disable_irq()
#define HAL_ADC_VREF 3.3
#define HAL_ADC_RESOLUTION 10
#define HAL_ADC_FILTERED // turn off ADC oversampling
#undef sq
#define sq(x) ((x)*(x))
//
// 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)
// Don't place string constants in PROGMEM
#undef PSTR
#define PSTR(str) ({static const char *data = (str); &data[0];})
// FastIO
bool is_output(pin_t pin);
// Enable hooks into idle and setup for HAL
#define HAL_IDLETASK 1
FORCE_INLINE void HAL_idletask() {}
FORCE_INLINE void HAL_init() {}
// Clear reset reason
void HAL_clear_reset_source();
// Reset reason
uint8_t HAL_get_reset_source();
void HAL_reboot();
FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); }
// ------------------------
// Class Utilities
// ------------------------
#pragma GCC diagnostic push
#if GCC_VERSION <= 50000
@ -134,30 +152,65 @@ extern "C" uint32_t freeMemory();
#pragma GCC diagnostic pop
// ADC
// ------------------------
// MarlinHAL Class
// ------------------------
void HAL_adc_init();
class MarlinHAL {
public:
#define HAL_ADC_VREF 3.3
#define HAL_ADC_RESOLUTION 10
#define HAL_ADC_FILTERED // turn off ADC oversampling
#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin)
#define HAL_READ_ADC() HAL_adc_get_result()
#define HAL_ADC_READY() true
// Earliest possible init, before setup()
MarlinHAL() {}
#define HAL_ANALOG_SELECT(pin)
static void init() {} // Called early in setup()
static 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);
uint16_t HAL_adc_get_result();
// Interrupts
static bool isr_state() { return !__get_primask(); }
static void isr_on() { __enable_irq(); }
static void isr_off() { __disable_irq(); }
// PWM
static 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 void idletask() {}
// Pin Map
// Reset
static uint8_t get_reset_source();
static void clear_reset_source();
#define GET_PIN_MAP_PIN(index) index
#define GET_PIN_MAP_INDEX(pin) pin
#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
// Free SRAM
static int freeMemory() { return ::freeMemory(); }
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 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 void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) {
analogWrite(pin, v);
}
};

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_epilogue(const uint8_t timer_num) {}
#define HAL_timer_isr_epilogue(T)
#define HAL_timer_isr_epilogue(T) NOOP