Merge upstream changes from Marlin 2.1.1
This commit is contained in:
@@ -28,6 +28,10 @@
|
||||
#include <esp_adc_cal.h>
|
||||
#include <HardwareSerial.h>
|
||||
|
||||
#if ENABLED(USE_ESP32_TASK_WDT)
|
||||
#include <esp_task_wdt.h>
|
||||
#endif
|
||||
|
||||
#if ENABLED(WIFISUPPORT)
|
||||
#include <ESPAsyncWebServer.h>
|
||||
#include "wifi.h"
|
||||
@@ -48,7 +52,7 @@
|
||||
// Externs
|
||||
// ------------------------
|
||||
|
||||
portMUX_TYPE spinlock = portMUX_INITIALIZER_UNLOCKED;
|
||||
portMUX_TYPE MarlinHAL::spinlock = portMUX_INITIALIZER_UNLOCKED;
|
||||
|
||||
// ------------------------
|
||||
// Local defines
|
||||
@@ -60,7 +64,8 @@ portMUX_TYPE spinlock = portMUX_INITIALIZER_UNLOCKED;
|
||||
// Public Variables
|
||||
// ------------------------
|
||||
|
||||
uint16_t HAL_adc_result;
|
||||
uint16_t MarlinHAL::adc_result;
|
||||
pwm_pin_t MarlinHAL::pwm_pin_data[MAX_EXPANDER_BITS];
|
||||
|
||||
// ------------------------
|
||||
// Private Variables
|
||||
@@ -69,9 +74,16 @@ uint16_t HAL_adc_result;
|
||||
esp_adc_cal_characteristics_t characteristics[ADC_ATTEN_MAX];
|
||||
adc_atten_t attenuations[ADC1_CHANNEL_MAX] = {};
|
||||
uint32_t thresholds[ADC_ATTEN_MAX];
|
||||
volatile int numPWMUsed = 0,
|
||||
pwmPins[MAX_PWM_PINS],
|
||||
pwmValues[MAX_PWM_PINS];
|
||||
|
||||
volatile int numPWMUsed = 0;
|
||||
volatile struct { pin_t pin; int value; } pwmState[MAX_PWM_PINS];
|
||||
|
||||
pin_t chan_pin[CHANNEL_MAX_NUM + 1] = { 0 }; // PWM capable IOpins - not 0 or >33 on ESP32
|
||||
|
||||
struct {
|
||||
uint32_t freq; // ledcReadFreq doesn't work if a duty hasn't been set yet!
|
||||
uint16_t res;
|
||||
} pwmInfo[(CHANNEL_MAX_NUM + 1) / 2];
|
||||
|
||||
// ------------------------
|
||||
// Public functions
|
||||
@@ -90,8 +102,26 @@ volatile int numPWMUsed = 0,
|
||||
|
||||
#endif
|
||||
|
||||
void HAL_init_board() {
|
||||
#if ENABLED(USE_ESP32_EXIO)
|
||||
|
||||
HardwareSerial YSerial2(2);
|
||||
|
||||
void Write_EXIO(uint8_t IO, uint8_t v) {
|
||||
if (hal.isr_state()) {
|
||||
hal.isr_off();
|
||||
YSerial2.write(0x80 | (((char)v) << 5) | (IO - 100));
|
||||
hal.isr_on();
|
||||
}
|
||||
else
|
||||
YSerial2.write(0x80 | (((char)v) << 5) | (IO - 100));
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
void MarlinHAL::init_board() {
|
||||
#if ENABLED(USE_ESP32_TASK_WDT)
|
||||
esp_task_wdt_init(10, true);
|
||||
#endif
|
||||
#if ENABLED(ESP3D_WIFISUPPORT)
|
||||
esp3dlib.init();
|
||||
#elif ENABLED(WIFISUPPORT)
|
||||
@@ -127,30 +157,58 @@ void HAL_init_board() {
|
||||
// Initialize the i2s peripheral only if the I2S stepper stream is enabled.
|
||||
// The following initialization is performed after Serial1 and Serial2 are defined as
|
||||
// their native pins might conflict with the i2s stream even when they are remapped.
|
||||
TERN_(I2S_STEPPER_STREAM, i2s_init());
|
||||
#if ENABLED(USE_ESP32_EXIO)
|
||||
YSerial2.begin(460800 * 3, SERIAL_8N1, 16, 17);
|
||||
#elif ENABLED(I2S_STEPPER_STREAM)
|
||||
i2s_init();
|
||||
#endif
|
||||
}
|
||||
|
||||
void HAL_idletask() {
|
||||
void MarlinHAL::idletask() {
|
||||
#if BOTH(WIFISUPPORT, OTASUPPORT)
|
||||
OTA_handle();
|
||||
#endif
|
||||
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 HAL_reboot() { ESP.restart(); }
|
||||
void MarlinHAL::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
|
||||
int freeMemory() { return ESP.getFreeHeap(); }
|
||||
int MarlinHAL::freeMemory() { return ESP.getFreeHeap(); }
|
||||
|
||||
// ------------------------
|
||||
// Watchdog Timer
|
||||
// ------------------------
|
||||
|
||||
#if ENABLED(USE_WATCHDOG)
|
||||
|
||||
#define WDT_TIMEOUT_US TERN(WATCHDOG_DURATION_8S, 8000000, 4000000) // 4 or 8 second timeout
|
||||
|
||||
extern "C" {
|
||||
esp_err_t esp_task_wdt_reset();
|
||||
}
|
||||
|
||||
void watchdogSetup() {
|
||||
// do whatever. don't remove this function.
|
||||
}
|
||||
|
||||
void MarlinHAL::watchdog_init() {
|
||||
// TODO
|
||||
}
|
||||
|
||||
// Reset watchdog.
|
||||
void MarlinHAL::watchdog_refresh() { esp_task_wdt_reset(); }
|
||||
|
||||
#endif
|
||||
|
||||
// ------------------------
|
||||
// ADC
|
||||
// ------------------------
|
||||
|
||||
#define ADC1_CHANNEL(pin) ADC1_GPIO ## pin ## _CHANNEL
|
||||
|
||||
adc1_channel_t get_channel(int pin) {
|
||||
@@ -172,22 +230,24 @@ void adc1_set_attenuation(adc1_channel_t chan, adc_atten_t atten) {
|
||||
}
|
||||
}
|
||||
|
||||
void HAL_adc_init() {
|
||||
void MarlinHAL::adc_init() {
|
||||
// Configure ADC
|
||||
adc1_config_width(ADC_WIDTH_12Bit);
|
||||
|
||||
// Configure channels only if used as (re-)configuring a pin for ADC that is used elsewhere might have adverse effects
|
||||
TERN_(HAS_TEMP_ADC_0, adc1_set_attenuation(get_channel(TEMP_0_PIN), ADC_ATTEN_11db));
|
||||
TERN_(HAS_TEMP_ADC_1, adc1_set_attenuation(get_channel(TEMP_1_PIN), ADC_ATTEN_11db));
|
||||
TERN_(HAS_TEMP_ADC_2, adc1_set_attenuation(get_channel(TEMP_2_PIN), ADC_ATTEN_11db));
|
||||
TERN_(HAS_TEMP_ADC_3, adc1_set_attenuation(get_channel(TEMP_3_PIN), ADC_ATTEN_11db));
|
||||
TERN_(HAS_TEMP_ADC_4, adc1_set_attenuation(get_channel(TEMP_4_PIN), ADC_ATTEN_11db));
|
||||
TERN_(HAS_TEMP_ADC_5, adc1_set_attenuation(get_channel(TEMP_5_PIN), ADC_ATTEN_11db));
|
||||
TERN_(HAS_TEMP_ADC_6, adc2_set_attenuation(get_channel(TEMP_6_PIN), ADC_ATTEN_11db));
|
||||
TERN_(HAS_TEMP_ADC_7, adc3_set_attenuation(get_channel(TEMP_7_PIN), ADC_ATTEN_11db));
|
||||
TERN_(HAS_HEATED_BED, adc1_set_attenuation(get_channel(TEMP_BED_PIN), ADC_ATTEN_11db));
|
||||
TERN_(HAS_TEMP_CHAMBER, adc1_set_attenuation(get_channel(TEMP_CHAMBER_PIN), ADC_ATTEN_11db));
|
||||
TERN_(HAS_TEMP_COOLER, adc1_set_attenuation(get_channel(TEMP_COOLER_PIN), ADC_ATTEN_11db));
|
||||
TERN_(HAS_TEMP_ADC_0, adc1_set_attenuation(get_channel(TEMP_0_PIN), ADC_ATTEN_11db));
|
||||
TERN_(HAS_TEMP_ADC_1, adc1_set_attenuation(get_channel(TEMP_1_PIN), ADC_ATTEN_11db));
|
||||
TERN_(HAS_TEMP_ADC_2, adc1_set_attenuation(get_channel(TEMP_2_PIN), ADC_ATTEN_11db));
|
||||
TERN_(HAS_TEMP_ADC_3, adc1_set_attenuation(get_channel(TEMP_3_PIN), ADC_ATTEN_11db));
|
||||
TERN_(HAS_TEMP_ADC_4, adc1_set_attenuation(get_channel(TEMP_4_PIN), ADC_ATTEN_11db));
|
||||
TERN_(HAS_TEMP_ADC_5, adc1_set_attenuation(get_channel(TEMP_5_PIN), ADC_ATTEN_11db));
|
||||
TERN_(HAS_TEMP_ADC_6, adc2_set_attenuation(get_channel(TEMP_6_PIN), ADC_ATTEN_11db));
|
||||
TERN_(HAS_TEMP_ADC_7, adc3_set_attenuation(get_channel(TEMP_7_PIN), ADC_ATTEN_11db));
|
||||
TERN_(HAS_HEATED_BED, adc1_set_attenuation(get_channel(TEMP_BED_PIN), ADC_ATTEN_11db));
|
||||
TERN_(HAS_TEMP_CHAMBER, adc1_set_attenuation(get_channel(TEMP_CHAMBER_PIN), ADC_ATTEN_11db));
|
||||
TERN_(HAS_TEMP_PROBE, adc1_set_attenuation(get_channel(TEMP_PROBE_PIN), ADC_ATTEN_11db));
|
||||
TERN_(HAS_TEMP_COOLER, adc1_set_attenuation(get_channel(TEMP_COOLER_PIN), ADC_ATTEN_11db));
|
||||
TERN_(HAS_TEMP_BOARD, adc1_set_attenuation(get_channel(TEMP_BOARD_PIN), ADC_ATTEN_11db));
|
||||
TERN_(FILAMENT_WIDTH_SENSOR, adc1_set_attenuation(get_channel(FILWIDTH_PIN), ADC_ATTEN_11db));
|
||||
|
||||
// Note that adc2 is shared with the WiFi module, which has higher priority, so the conversion may fail.
|
||||
@@ -202,11 +262,16 @@ void HAL_adc_init() {
|
||||
}
|
||||
}
|
||||
|
||||
void HAL_adc_start_conversion(const uint8_t adc_pin) {
|
||||
const adc1_channel_t chan = get_channel(adc_pin);
|
||||
#ifndef ADC_REFERENCE_VOLTAGE
|
||||
#define ADC_REFERENCE_VOLTAGE 3.3
|
||||
#endif
|
||||
|
||||
void MarlinHAL::adc_start(const pin_t pin) {
|
||||
const adc1_channel_t chan = get_channel(pin);
|
||||
uint32_t 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 * isr_float_t(1023) / isr_float_t(ADC_REFERENCE_VOLTAGE) / isr_float_t(1000);
|
||||
|
||||
// Change the attenuation level based on the new reading
|
||||
adc_atten_t atten;
|
||||
@@ -223,25 +288,106 @@ void HAL_adc_start_conversion(const uint8_t adc_pin) {
|
||||
adc1_set_attenuation(chan, atten);
|
||||
}
|
||||
|
||||
void analogWrite(pin_t pin, int value) {
|
||||
// Use ledc hardware for internal pins
|
||||
if (pin < 34) {
|
||||
static int cnt_channel = 1, pin_to_channel[40] = { 0 };
|
||||
if (pin_to_channel[pin] == 0) {
|
||||
ledcAttachPin(pin, cnt_channel);
|
||||
ledcSetup(cnt_channel, 490, 8);
|
||||
ledcWrite(cnt_channel, value);
|
||||
pin_to_channel[pin] = cnt_channel++;
|
||||
// ------------------------
|
||||
// PWM
|
||||
// ------------------------
|
||||
|
||||
int8_t channel_for_pin(const uint8_t pin) {
|
||||
for (int i = 0; i <= CHANNEL_MAX_NUM; i++)
|
||||
if (chan_pin[i] == pin) return i;
|
||||
return -1;
|
||||
}
|
||||
|
||||
// get PWM channel for pin - if none then attach a new one
|
||||
// return -1 if fail or invalid pin#, channel # (0-15) if success
|
||||
int8_t get_pwm_channel(const pin_t pin, const uint32_t freq, const uint16_t res) {
|
||||
if (!WITHIN(pin, 1, MAX_PWM_IOPIN)) return -1; // Not a hardware PWM pin!
|
||||
int8_t cid = channel_for_pin(pin);
|
||||
if (cid >= 0) return cid;
|
||||
|
||||
// Find an empty adjacent channel (same timer & freq/res)
|
||||
for (int i = 0; i <= CHANNEL_MAX_NUM; i++) {
|
||||
if (chan_pin[i] == 0) {
|
||||
if (chan_pin[i ^ 0x1] != 0) {
|
||||
if (pwmInfo[i / 2].freq == freq && pwmInfo[i / 2].res == res) {
|
||||
chan_pin[i] = pin; // Allocate PWM to this channel
|
||||
ledcAttachPin(pin, i);
|
||||
return i;
|
||||
}
|
||||
}
|
||||
else if (cid == -1) // Pair of empty channels?
|
||||
cid = i & 0xFE; // Save lower channel number
|
||||
}
|
||||
ledcWrite(pin_to_channel[pin], value);
|
||||
}
|
||||
// not attached, is an empty timer slot avail?
|
||||
if (cid >= 0) {
|
||||
chan_pin[cid] = pin;
|
||||
pwmInfo[cid / 2].freq = freq;
|
||||
pwmInfo[cid / 2].res = res;
|
||||
ledcSetup(cid, freq, res);
|
||||
ledcAttachPin(pin, cid);
|
||||
}
|
||||
return cid; // -1 if no channel avail
|
||||
}
|
||||
|
||||
void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=_BV(PWM_RESOLUTION)-1*/, const bool invert/*=false*/) {
|
||||
#if ENABLED(I2S_STEPPER_STREAM)
|
||||
if (pin > 127) {
|
||||
const uint8_t pinlo = pin & 0x7F;
|
||||
pwm_pin_t &pindata = pwm_pin_data[pinlo];
|
||||
const uint32_t duty = map(invert ? v_size - v : v, 0, v_size, 0, pindata.pwm_cycle_ticks);
|
||||
if (duty == 0 || duty == pindata.pwm_cycle_ticks) { // max or min (i.e., on/off)
|
||||
pindata.pwm_duty_ticks = 0; // turn off PWM for this pin
|
||||
duty ? SBI32(i2s_port_data, pinlo) : CBI32(i2s_port_data, pinlo); // set pin level
|
||||
}
|
||||
else
|
||||
pindata.pwm_duty_ticks = duty; // PWM duty count = # of 4µs ticks per full PWM cycle
|
||||
}
|
||||
else
|
||||
#endif
|
||||
{
|
||||
const int8_t cid = get_pwm_channel(pin, PWM_FREQUENCY, PWM_RESOLUTION);
|
||||
if (cid >= 0) {
|
||||
const uint32_t duty = map(invert ? v_size - v : v, 0, v_size, 0, _BV(PWM_RESOLUTION)-1);
|
||||
ledcWrite(cid, duty);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
int8_t MarlinHAL::set_pwm_frequency(const pin_t pin, const uint32_t f_desired) {
|
||||
#if ENABLED(I2S_STEPPER_STREAM)
|
||||
if (pin > 127) {
|
||||
pwm_pin_data[pin & 0x7F].pwm_cycle_ticks = 1000000UL / f_desired / 4; // # of 4µs ticks per full PWM cycle
|
||||
return 0;
|
||||
}
|
||||
else
|
||||
#endif
|
||||
{
|
||||
const int8_t cid = channel_for_pin(pin);
|
||||
if (cid >= 0) {
|
||||
if (f_desired == ledcReadFreq(cid)) return cid; // no freq change
|
||||
ledcDetachPin(chan_pin[cid]);
|
||||
chan_pin[cid] = 0; // remove old freq channel
|
||||
}
|
||||
return get_pwm_channel(pin, f_desired, PWM_RESOLUTION); // try for new one
|
||||
}
|
||||
}
|
||||
|
||||
// use hardware PWM if avail, if not then ISR
|
||||
void analogWrite(const pin_t pin, const uint16_t value, const uint32_t freq/*=PWM_FREQUENCY*/, const uint16_t res/*=8*/) { // always 8 bit resolution!
|
||||
// Use ledc hardware for internal pins
|
||||
const int8_t cid = get_pwm_channel(pin, freq, res);
|
||||
if (cid >= 0) {
|
||||
ledcWrite(cid, value); // set duty value
|
||||
return;
|
||||
}
|
||||
|
||||
// not a hardware PWM pin OR no PWM channels available
|
||||
int idx = -1;
|
||||
|
||||
// Search Pin
|
||||
for (int i = 0; i < numPWMUsed; ++i)
|
||||
if (pwmPins[i] == pin) { idx = i; break; }
|
||||
if (pwmState[i].pin == pin) { idx = i; break; }
|
||||
|
||||
// not found ?
|
||||
if (idx < 0) {
|
||||
@@ -250,34 +396,34 @@ void analogWrite(pin_t pin, int value) {
|
||||
|
||||
// Take new slot for pin
|
||||
idx = numPWMUsed;
|
||||
pwmPins[idx] = pin;
|
||||
pwmState[idx].pin = pin;
|
||||
// Start timer on first use
|
||||
if (idx == 0) HAL_timer_start(PWM_TIMER_NUM, PWM_TIMER_FREQUENCY);
|
||||
if (idx == 0) HAL_timer_start(MF_TIMER_PWM, PWM_TIMER_FREQUENCY);
|
||||
|
||||
++numPWMUsed;
|
||||
}
|
||||
|
||||
// Use 7bit internal value - add 1 to have 100% high at 255
|
||||
pwmValues[idx] = (value + 1) / 2;
|
||||
pwmState[idx].value = (value + 1) / 2;
|
||||
}
|
||||
|
||||
// Handle PWM timer interrupt
|
||||
HAL_PWM_TIMER_ISR() {
|
||||
HAL_timer_isr_prologue(PWM_TIMER_NUM);
|
||||
HAL_timer_isr_prologue(MF_TIMER_PWM);
|
||||
|
||||
static uint8_t count = 0;
|
||||
|
||||
for (int i = 0; i < numPWMUsed; ++i) {
|
||||
if (count == 0) // Start of interval
|
||||
WRITE(pwmPins[i], pwmValues[i] ? HIGH : LOW);
|
||||
else if (pwmValues[i] == count) // End of duration
|
||||
WRITE(pwmPins[i], LOW);
|
||||
digitalWrite(pwmState[i].pin, pwmState[i].value ? HIGH : LOW);
|
||||
else if (pwmState[i].value == count) // End of duration
|
||||
digitalWrite(pwmState[i].pin, LOW);
|
||||
}
|
||||
|
||||
// 128 for 7 Bit resolution
|
||||
count = (count + 1) & 0x7F;
|
||||
|
||||
HAL_timer_isr_epilogue(PWM_TIMER_NUM);
|
||||
HAL_timer_isr_epilogue(MF_TIMER_PWM);
|
||||
}
|
||||
|
||||
#endif // ARDUINO_ARCH_ESP32
|
||||
|
@@ -32,7 +32,6 @@
|
||||
#include "../shared/HAL_SPI.h"
|
||||
|
||||
#include "fastio.h"
|
||||
#include "watchdog.h"
|
||||
#include "i2s.h"
|
||||
|
||||
#if ENABLED(WIFISUPPORT)
|
||||
@@ -49,8 +48,6 @@
|
||||
// Defines
|
||||
// ------------------------
|
||||
|
||||
extern portMUX_TYPE spinlock;
|
||||
|
||||
#define MYSERIAL1 flushableSerial
|
||||
|
||||
#if EITHER(WIFISUPPORT, ESP3D_WIFISUPPORT)
|
||||
@@ -63,26 +60,33 @@ extern portMUX_TYPE spinlock;
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#define CRITICAL_SECTION_START() portENTER_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)
|
||||
#define CRITICAL_SECTION_START() portENTER_CRITICAL(&hal.spinlock)
|
||||
#define CRITICAL_SECTION_END() portEXIT_CRITICAL(&hal.spinlock)
|
||||
|
||||
#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment
|
||||
#define PWM_FREQUENCY 1000u // Default PWM frequency when set_pwm_duty() is called without set_pwm_frequency()
|
||||
#define PWM_RESOLUTION 10u // Default PWM bit resolution
|
||||
#define CHANNEL_MAX_NUM 15u // max PWM channel # to allocate (7 to only use low speed, 15 to use low & high)
|
||||
#define MAX_PWM_IOPIN 33u // hardware pwm pins < 34
|
||||
#ifndef MAX_EXPANDER_BITS
|
||||
#define MAX_EXPANDER_BITS 32 // I2S expander bit width (max 32)
|
||||
#endif
|
||||
|
||||
// ------------------------
|
||||
// Types
|
||||
// ------------------------
|
||||
|
||||
typedef double isr_float_t; // FPU ops are used for single-precision, so use double for ISRs.
|
||||
typedef int16_t pin_t;
|
||||
|
||||
#define HAL_SERVO_LIB Servo
|
||||
typedef struct pwm_pin {
|
||||
uint32_t pwm_cycle_ticks = 1000000UL / (PWM_FREQUENCY) / 4; // # ticks per pwm cycle
|
||||
uint32_t pwm_tick_count = 0; // current tick count
|
||||
uint32_t pwm_duty_ticks = 0; // # of ticks for current duty cycle
|
||||
} pwm_pin_t;
|
||||
|
||||
// ------------------------
|
||||
// Public Variables
|
||||
// ------------------------
|
||||
|
||||
/** result of last ADC conversion */
|
||||
extern uint16_t HAL_adc_result;
|
||||
class Servo;
|
||||
typedef Servo hal_servo_t;
|
||||
|
||||
// ------------------------
|
||||
// Public functions
|
||||
@@ -91,56 +95,21 @@ extern uint16_t HAL_adc_result;
|
||||
//
|
||||
// Tone
|
||||
//
|
||||
void toneInit();
|
||||
void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration=0);
|
||||
void noTone(const pin_t _pin);
|
||||
int8_t get_pwm_channel(const pin_t pin, const uint32_t freq, const uint16_t res);
|
||||
void analogWrite(const pin_t pin, const uint16_t value, const uint32_t freq=PWM_FREQUENCY, const uint16_t res=8);
|
||||
|
||||
// clear reset reason
|
||||
void HAL_clear_reset_source();
|
||||
|
||||
// reset reason
|
||||
uint8_t HAL_get_reset_source();
|
||||
|
||||
void HAL_reboot();
|
||||
|
||||
void _delay_ms(int delay);
|
||||
|
||||
#if GCC_VERSION <= 50000
|
||||
#pragma GCC diagnostic push
|
||||
#pragma GCC diagnostic ignored "-Wunused-function"
|
||||
#endif
|
||||
|
||||
int freeMemory();
|
||||
|
||||
#if GCC_VERSION <= 50000
|
||||
#pragma GCC diagnostic pop
|
||||
#endif
|
||||
|
||||
void analogWrite(pin_t pin, int value);
|
||||
|
||||
// ADC
|
||||
#define HAL_ANALOG_SELECT(pin)
|
||||
|
||||
void HAL_adc_init();
|
||||
|
||||
#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);
|
||||
|
||||
//
|
||||
// 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)
|
||||
|
||||
// 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)
|
||||
void Write_EXIO(uint8_t IO, uint8_t v);
|
||||
#endif
|
||||
|
||||
//
|
||||
// Delay in cycles (used by DELAY_NS / DELAY_US)
|
||||
@@ -182,3 +151,96 @@ 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() {}
|
||||
|
||||
// Watchdog
|
||||
static void watchdog_init() IF_DISABLED(USE_WATCHDOG, {});
|
||||
static void watchdog_refresh() IF_DISABLED(USE_WATCHDOG, {});
|
||||
|
||||
static void init() {} // Called early in setup()
|
||||
static void init_board(); // Called less early in setup()
|
||||
static void reboot(); // Restart the firmware
|
||||
|
||||
// Interrupts
|
||||
static portMUX_TYPE spinlock;
|
||||
static bool isr_state() { return spinlock.owner == portMUX_FREE_VAL; }
|
||||
static void isr_on() { if (spinlock.owner != portMUX_FREE_VAL) portEXIT_CRITICAL(&spinlock); }
|
||||
static void isr_off() { portENTER_CRITICAL(&spinlock); }
|
||||
|
||||
static 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 int freeMemory();
|
||||
|
||||
static pwm_pin_t pwm_pin_data[MAX_EXPANDER_BITS];
|
||||
|
||||
//
|
||||
// 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 pin. Called from Temperature::isr!
|
||||
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() { return adc_result; }
|
||||
|
||||
/**
|
||||
* If not already allocated, allocate a hardware PWM channel
|
||||
* to the pin and set the duty cycle..
|
||||
* 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);
|
||||
|
||||
/**
|
||||
* Allocate and set the frequency of a hardware PWM pin
|
||||
* Returns -1 if no pin available.
|
||||
*/
|
||||
static int8_t set_pwm_frequency(const pin_t pin, const uint32_t f_desired);
|
||||
|
||||
};
|
||||
|
@@ -53,11 +53,9 @@ static SPISettings spiConfig;
|
||||
// ------------------------
|
||||
|
||||
void spiBegin() {
|
||||
#if !PIN_EXISTS(SD_SS)
|
||||
#error "SD_SS_PIN not defined!"
|
||||
#if ENABLED(SDSUPPORT) && PIN_EXISTS(SD_SS)
|
||||
OUT_WRITE(SD_SS_PIN, HIGH);
|
||||
#endif
|
||||
|
||||
OUT_WRITE(SD_SS_PIN, HIGH);
|
||||
}
|
||||
|
||||
void spiInit(uint8_t spiRate) {
|
||||
|
@@ -31,20 +31,18 @@
|
||||
// so we only allocate servo channels up high to avoid side effects with regards to analogWrite (fans, leds, laser pwm etc.)
|
||||
int Servo::channel_next_free = 12;
|
||||
|
||||
Servo::Servo() {
|
||||
channel = channel_next_free++;
|
||||
}
|
||||
Servo::Servo() {}
|
||||
|
||||
int8_t Servo::attach(const int inPin) {
|
||||
if (channel >= CHANNEL_MAX_NUM) return -1;
|
||||
if (inPin > 0) pin = inPin;
|
||||
|
||||
ledcSetup(channel, 50, 16); // channel X, 50 Hz, 16-bit depth
|
||||
ledcAttachPin(pin, channel);
|
||||
return true;
|
||||
channel = get_pwm_channel(pin, 50u, 16u);
|
||||
return channel; // -1 if no PWM avail.
|
||||
}
|
||||
|
||||
void Servo::detach() { ledcDetachPin(pin); }
|
||||
// leave channel connected to servo - set duty to zero
|
||||
void Servo::detach() {
|
||||
if (channel >= 0) ledcWrite(channel, 0);
|
||||
}
|
||||
|
||||
int Servo::read() { return degrees; }
|
||||
|
||||
@@ -52,7 +50,7 @@ void Servo::write(int inDegrees) {
|
||||
degrees = constrain(inDegrees, MIN_ANGLE, MAX_ANGLE);
|
||||
int us = map(degrees, MIN_ANGLE, MAX_ANGLE, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH);
|
||||
int duty = map(us, 0, TAU_USEC, 0, MAX_COMPARE);
|
||||
ledcWrite(channel, duty);
|
||||
if (channel >= 0) ledcWrite(channel, duty); // don't save duty for servos!
|
||||
}
|
||||
|
||||
void Servo::move(const int value) {
|
||||
|
@@ -30,8 +30,7 @@ class Servo {
|
||||
MAX_PULSE_WIDTH = 2400, // Longest pulse sent to a servo
|
||||
TAU_MSEC = 20,
|
||||
TAU_USEC = (TAU_MSEC * 1000),
|
||||
MAX_COMPARE = _BV(16) - 1, // 65535
|
||||
CHANNEL_MAX_NUM = 16;
|
||||
MAX_COMPARE = _BV(16) - 1; // 65535
|
||||
|
||||
public:
|
||||
Servo();
|
||||
|
@@ -35,19 +35,19 @@
|
||||
static pin_t tone_pin;
|
||||
volatile static int32_t toggles;
|
||||
|
||||
void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration) {
|
||||
void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration/*=0*/) {
|
||||
tone_pin = _pin;
|
||||
toggles = 2 * frequency * duration / 1000;
|
||||
HAL_timer_start(TONE_TIMER_NUM, 2 * frequency);
|
||||
HAL_timer_start(MF_TIMER_TONE, 2 * frequency);
|
||||
}
|
||||
|
||||
void noTone(const pin_t _pin) {
|
||||
HAL_timer_disable_interrupt(TONE_TIMER_NUM);
|
||||
HAL_timer_disable_interrupt(MF_TIMER_TONE);
|
||||
WRITE(_pin, LOW);
|
||||
}
|
||||
|
||||
HAL_TONE_TIMER_ISR() {
|
||||
HAL_timer_isr_prologue(TONE_TIMER_NUM);
|
||||
HAL_timer_isr_prologue(MF_TIMER_TONE);
|
||||
|
||||
if (toggles) {
|
||||
toggles--;
|
||||
|
@@ -65,4 +65,10 @@ void setup_endstop_interrupts() {
|
||||
TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN));
|
||||
TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN));
|
||||
TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN));
|
||||
TERN_(HAS_U_MAX, _ATTACH(U_MAX_PIN));
|
||||
TERN_(HAS_U_MIN, _ATTACH(U_MIN_PIN));
|
||||
TERN_(HAS_V_MAX, _ATTACH(V_MAX_PIN));
|
||||
TERN_(HAS_V_MIN, _ATTACH(V_MIN_PIN));
|
||||
TERN_(HAS_W_MAX, _ATTACH(W_MAX_PIN));
|
||||
TERN_(HAS_W_MIN, _ATTACH(W_MIN_PIN));
|
||||
}
|
||||
|
6
Marlin/src/HAL/ESP32/esp32.csv
Normal file
6
Marlin/src/HAL/ESP32/esp32.csv
Normal file
@@ -0,0 +1,6 @@
|
||||
# Name, Type, SubType, Offset, Size, Flags
|
||||
nvs, data, nvs, 0x9000, 0x5000,
|
||||
otadata, data, ota, 0xe000, 0x2000,
|
||||
app0, app, ota_0, 0x10000, 0x180000,
|
||||
app1, app, ota_1, 0x190000, 0x180000,
|
||||
spiffs, data, spiffs, 0x310000, 0xF0000,
|
|
@@ -40,13 +40,19 @@
|
||||
// Set pin as input with pullup mode
|
||||
#define _PULLUP(IO, v) pinMode(IO, v ? INPUT_PULLUP : INPUT)
|
||||
|
||||
// Read a pin wrapper
|
||||
#define READ(IO) (IS_I2S_EXPANDER_PIN(IO) ? i2s_state(I2S_EXPANDER_PIN_INDEX(IO)) : digitalRead(IO))
|
||||
#if ENABLED(USE_ESP32_EXIO)
|
||||
// Read a pin wrapper
|
||||
#define READ(IO) digitalRead(IO)
|
||||
// Write to a pin wrapper
|
||||
#define WRITE(IO, v) (IO >= 100 ? Write_EXIO(IO, v) : digitalWrite(IO, v))
|
||||
#else
|
||||
// Read a pin wrapper
|
||||
#define READ(IO) (IS_I2S_EXPANDER_PIN(IO) ? i2s_state(I2S_EXPANDER_PIN_INDEX(IO)) : digitalRead(IO))
|
||||
// Write to a pin wrapper
|
||||
#define WRITE(IO, v) (IS_I2S_EXPANDER_PIN(IO) ? i2s_write(I2S_EXPANDER_PIN_INDEX(IO), v) : digitalWrite(IO, v))
|
||||
#endif
|
||||
|
||||
// Write to a pin wrapper
|
||||
#define WRITE(IO, v) (IS_I2S_EXPANDER_PIN(IO) ? i2s_write(I2S_EXPANDER_PIN_INDEX(IO), v) : digitalWrite(IO, v))
|
||||
|
||||
// Set pin as input wrapper
|
||||
// Set pin as input wrapper (0x80 | (v << 5) | (IO - 100))
|
||||
#define SET_INPUT(IO) _SET_INPUT(IO)
|
||||
|
||||
// Set pin as input with pullup wrapper
|
||||
|
@@ -23,6 +23,8 @@
|
||||
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if DISABLED(USE_ESP32_EXIO)
|
||||
|
||||
#include "i2s.h"
|
||||
|
||||
#include "../shared/Marduino.h"
|
||||
@@ -62,12 +64,9 @@ uint32_t i2s_port_data = 0;
|
||||
#define I2S_EXIT_CRITICAL() portEXIT_CRITICAL(&i2s_spinlock[i2s_num])
|
||||
|
||||
static inline void gpio_matrix_out_check(uint32_t gpio, uint32_t signal_idx, bool out_inv, bool oen_inv) {
|
||||
//if pin = -1, do not need to configure
|
||||
if (gpio != -1) {
|
||||
PIN_FUNC_SELECT(GPIO_PIN_MUX_REG[gpio], PIN_FUNC_GPIO);
|
||||
gpio_set_direction((gpio_num_t)gpio, (gpio_mode_t)GPIO_MODE_DEF_OUTPUT);
|
||||
gpio_matrix_out(gpio, signal_idx, out_inv, oen_inv);
|
||||
}
|
||||
PIN_FUNC_SELECT(GPIO_PIN_MUX_REG[gpio], PIN_FUNC_GPIO);
|
||||
gpio_set_direction((gpio_num_t)gpio, (gpio_mode_t)GPIO_MODE_DEF_OUTPUT);
|
||||
gpio_matrix_out(gpio, signal_idx, out_inv, oen_inv);
|
||||
}
|
||||
|
||||
static esp_err_t i2s_reset_fifo(i2s_port_t i2s_num) {
|
||||
@@ -254,13 +253,7 @@ int i2s_init() {
|
||||
|
||||
I2S0.fifo_conf.dscr_en = 0;
|
||||
|
||||
I2S0.conf_chan.tx_chan_mod = (
|
||||
#if ENABLED(I2S_STEPPER_SPLIT_STREAM)
|
||||
4
|
||||
#else
|
||||
0
|
||||
#endif
|
||||
);
|
||||
I2S0.conf_chan.tx_chan_mod = TERN(I2S_STEPPER_SPLIT_STREAM, 4, 0);
|
||||
I2S0.fifo_conf.tx_fifo_mod = 0;
|
||||
I2S0.conf.tx_mono = 0;
|
||||
|
||||
@@ -311,9 +304,16 @@ int i2s_init() {
|
||||
xTaskCreatePinnedToCore(stepperTask, "StepperTask", 10000, nullptr, 1, nullptr, CONFIG_ARDUINO_RUNNING_CORE); // run I2S stepper task on same core as rest of Marlin
|
||||
|
||||
// Route the i2s pins to the appropriate GPIO
|
||||
gpio_matrix_out_check(I2S_DATA, I2S0O_DATA_OUT23_IDX, 0, 0);
|
||||
gpio_matrix_out_check(I2S_BCK, I2S0O_BCK_OUT_IDX, 0, 0);
|
||||
gpio_matrix_out_check(I2S_WS, I2S0O_WS_OUT_IDX, 0, 0);
|
||||
// If a pin is not defined, no need to configure
|
||||
#if defined(I2S_DATA) && I2S_DATA >= 0
|
||||
gpio_matrix_out_check(I2S_DATA, I2S0O_DATA_OUT23_IDX, 0, 0);
|
||||
#endif
|
||||
#if defined(I2S_BCK) && I2S_BCK >= 0
|
||||
gpio_matrix_out_check(I2S_BCK, I2S0O_BCK_OUT_IDX, 0, 0);
|
||||
#endif
|
||||
#if defined(I2S_WS) && I2S_WS >= 0
|
||||
gpio_matrix_out_check(I2S_WS, I2S0O_WS_OUT_IDX, 0, 0);
|
||||
#endif
|
||||
|
||||
// Start the I2S peripheral
|
||||
return i2s_start(I2S_NUM_0);
|
||||
@@ -337,7 +337,28 @@ uint8_t i2s_state(uint8_t pin) {
|
||||
}
|
||||
|
||||
void i2s_push_sample() {
|
||||
// Every 4µs (when space in DMA buffer) toggle each expander PWM output using
|
||||
// the current duty cycle/frequency so they sync with any steps (once
|
||||
// through the DMA/FIFO buffers). PWM signal inversion handled by other functions
|
||||
LOOP_L_N(p, MAX_EXPANDER_BITS) {
|
||||
if (hal.pwm_pin_data[p].pwm_duty_ticks > 0) { // pin has active pwm?
|
||||
if (hal.pwm_pin_data[p].pwm_tick_count == 0) {
|
||||
if (TEST32(i2s_port_data, p)) { // hi->lo
|
||||
CBI32(i2s_port_data, p);
|
||||
hal.pwm_pin_data[p].pwm_tick_count = hal.pwm_pin_data[p].pwm_cycle_ticks - hal.pwm_pin_data[p].pwm_duty_ticks;
|
||||
}
|
||||
else { // lo->hi
|
||||
SBI32(i2s_port_data, p);
|
||||
hal.pwm_pin_data[p].pwm_tick_count = hal.pwm_pin_data[p].pwm_duty_ticks;
|
||||
}
|
||||
}
|
||||
else
|
||||
hal.pwm_pin_data[p].pwm_tick_count--;
|
||||
}
|
||||
}
|
||||
|
||||
dma.current[dma.rw_pos++] = i2s_port_data;
|
||||
}
|
||||
|
||||
#endif // !USE_ESP32_EXIO
|
||||
#endif // ARDUINO_ARCH_ESP32
|
||||
|
@@ -20,3 +20,10 @@
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
//
|
||||
// Board-specific options need to be defined before HAL.h
|
||||
//
|
||||
#if MB(MKS_TINYBEE)
|
||||
#define MAX_EXPANDER_BITS 24 // TinyBee has 3 x HC595
|
||||
#endif
|
||||
|
@@ -25,8 +25,8 @@
|
||||
#error "EMERGENCY_PARSER is not yet implemented for ESP32. Disable EMERGENCY_PARSER to continue."
|
||||
#endif
|
||||
|
||||
#if ENABLED(FAST_PWM_FAN) || SPINDLE_LASER_FREQUENCY
|
||||
#error "Features requiring Hardware PWM (FAST_PWM_FAN, SPINDLE_LASER_FREQUENCY) are not yet supported on ESP32."
|
||||
#if (ENABLED(SPINDLE_LASER_USE_PWM) && SPINDLE_LASER_FREQUENCY > 78125) || (ENABLED(FAST_PWM_FAN_FREQUENCY) && FAST_PWM_FAN_FREQUENCY > 78125)
|
||||
#error "SPINDLE_LASER_FREQUENCY and FAST_PWM_FREQUENCY maximum value is 78125Hz for ESP32."
|
||||
#endif
|
||||
|
||||
#if HAS_TMC_SW_SERIAL
|
||||
@@ -40,3 +40,15 @@
|
||||
#if ENABLED(POSTMORTEM_DEBUGGING)
|
||||
#error "POSTMORTEM_DEBUGGING is not yet supported on ESP32."
|
||||
#endif
|
||||
|
||||
#if MB(MKS_TINYBEE) && ENABLED(FAST_PWM_FAN)
|
||||
#error "FAST_PWM_FAN is not available on TinyBee."
|
||||
#endif
|
||||
|
||||
#if USING_PULLDOWNS
|
||||
#error "PULLDOWN pin mode is not available on ESP32 boards."
|
||||
#endif
|
||||
|
||||
#if BOTH(I2S_STEPPER_STREAM, LIN_ADVANCE)
|
||||
#error "I2S stream is currently incompatible with LIN_ADVANCE."
|
||||
#endif
|
||||
|
@@ -41,7 +41,7 @@
|
||||
|
||||
static timg_dev_t *TG[2] = {&TIMERG0, &TIMERG1};
|
||||
|
||||
const tTimerConfig TimerConfig [NUM_HARDWARE_TIMERS] = {
|
||||
const tTimerConfig timer_config[NUM_HARDWARE_TIMERS] = {
|
||||
{ TIMER_GROUP_0, TIMER_0, STEPPER_TIMER_PRESCALE, stepTC_Handler }, // 0 - Stepper
|
||||
{ TIMER_GROUP_0, TIMER_1, TEMP_TIMER_PRESCALE, tempTC_Handler }, // 1 - Temperature
|
||||
{ TIMER_GROUP_1, TIMER_0, PWM_TIMER_PRESCALE, pwmTC_Handler }, // 2 - PWM
|
||||
@@ -53,7 +53,7 @@ const tTimerConfig TimerConfig [NUM_HARDWARE_TIMERS] = {
|
||||
// ------------------------
|
||||
|
||||
void IRAM_ATTR timer_isr(void *para) {
|
||||
const tTimerConfig& timer = TimerConfig[(int)para];
|
||||
const tTimerConfig& timer = timer_config[(int)para];
|
||||
|
||||
// Retrieve the interrupt status and the counter value
|
||||
// from the timer that reported the interrupt
|
||||
@@ -81,8 +81,8 @@ void IRAM_ATTR timer_isr(void *para) {
|
||||
* @param timer_num timer number to initialize
|
||||
* @param frequency frequency of the timer
|
||||
*/
|
||||
void HAL_timer_start(const uint8_t timer_num, uint32_t frequency) {
|
||||
const tTimerConfig timer = TimerConfig[timer_num];
|
||||
void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
|
||||
const tTimerConfig timer = timer_config[timer_num];
|
||||
|
||||
timer_config_t config;
|
||||
config.divider = timer.divider;
|
||||
@@ -115,7 +115,7 @@ void HAL_timer_start(const uint8_t timer_num, uint32_t frequency) {
|
||||
* @param count threshold at which the interrupt is triggered
|
||||
*/
|
||||
void HAL_timer_set_compare(const uint8_t timer_num, hal_timer_t count) {
|
||||
const tTimerConfig timer = TimerConfig[timer_num];
|
||||
const tTimerConfig timer = timer_config[timer_num];
|
||||
timer_set_alarm_value(timer.group, timer.idx, count);
|
||||
}
|
||||
|
||||
@@ -125,7 +125,7 @@ void HAL_timer_set_compare(const uint8_t timer_num, hal_timer_t count) {
|
||||
* @return the timer current threshold for the alarm to be triggered
|
||||
*/
|
||||
hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) {
|
||||
const tTimerConfig timer = TimerConfig[timer_num];
|
||||
const tTimerConfig timer = timer_config[timer_num];
|
||||
|
||||
uint64_t alarm_value;
|
||||
timer_get_alarm_value(timer.group, timer.idx, &alarm_value);
|
||||
@@ -139,7 +139,7 @@ hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) {
|
||||
* @return the current counter of the alarm
|
||||
*/
|
||||
hal_timer_t HAL_timer_get_count(const uint8_t timer_num) {
|
||||
const tTimerConfig timer = TimerConfig[timer_num];
|
||||
const tTimerConfig timer = timer_config[timer_num];
|
||||
uint64_t counter_value;
|
||||
timer_get_counter_value(timer.group, timer.idx, &counter_value);
|
||||
return counter_value;
|
||||
@@ -150,7 +150,7 @@ hal_timer_t HAL_timer_get_count(const uint8_t timer_num) {
|
||||
* @param timer_num timer number to enable interrupts on
|
||||
*/
|
||||
void HAL_timer_enable_interrupt(const uint8_t timer_num) {
|
||||
//const tTimerConfig timer = TimerConfig[timer_num];
|
||||
//const tTimerConfig timer = timer_config[timer_num];
|
||||
//timer_enable_intr(timer.group, timer.idx);
|
||||
}
|
||||
|
||||
@@ -159,12 +159,12 @@ void HAL_timer_enable_interrupt(const uint8_t timer_num) {
|
||||
* @param timer_num timer number to disable interrupts on
|
||||
*/
|
||||
void HAL_timer_disable_interrupt(const uint8_t timer_num) {
|
||||
//const tTimerConfig timer = TimerConfig[timer_num];
|
||||
//const tTimerConfig timer = timer_config[timer_num];
|
||||
//timer_disable_intr(timer.group, timer.idx);
|
||||
}
|
||||
|
||||
bool HAL_timer_interrupt_enabled(const uint8_t timer_num) {
|
||||
const tTimerConfig timer = TimerConfig[timer_num];
|
||||
const tTimerConfig timer = timer_config[timer_num];
|
||||
return TG[timer.group]->int_ena.val | BIT(timer_num);
|
||||
}
|
||||
|
||||
|
@@ -32,20 +32,20 @@
|
||||
typedef uint64_t hal_timer_t;
|
||||
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFFFFFFFFFFULL
|
||||
|
||||
#ifndef STEP_TIMER_NUM
|
||||
#define STEP_TIMER_NUM 0 // Timer Index for Stepper
|
||||
#ifndef MF_TIMER_STEP
|
||||
#define MF_TIMER_STEP 0 // Timer Index for Stepper
|
||||
#endif
|
||||
#ifndef PULSE_TIMER_NUM
|
||||
#define PULSE_TIMER_NUM STEP_TIMER_NUM
|
||||
#ifndef MF_TIMER_PULSE
|
||||
#define MF_TIMER_PULSE MF_TIMER_STEP
|
||||
#endif
|
||||
#ifndef TEMP_TIMER_NUM
|
||||
#define TEMP_TIMER_NUM 1 // Timer Index for Temperature
|
||||
#ifndef MF_TIMER_TEMP
|
||||
#define MF_TIMER_TEMP 1 // Timer Index for Temperature
|
||||
#endif
|
||||
#ifndef PWM_TIMER_NUM
|
||||
#define PWM_TIMER_NUM 2 // index of timer to use for PWM outputs
|
||||
#ifndef MF_TIMER_PWM
|
||||
#define MF_TIMER_PWM 2 // index of timer to use for PWM outputs
|
||||
#endif
|
||||
#ifndef TONE_TIMER_NUM
|
||||
#define TONE_TIMER_NUM 3 // index of timer for beeper tones
|
||||
#ifndef MF_TIMER_TONE
|
||||
#define MF_TIMER_TONE 3 // index of timer for beeper tones
|
||||
#endif
|
||||
|
||||
#define HAL_TIMER_RATE APB_CLK_FREQ // frequency of timer peripherals
|
||||
@@ -79,12 +79,12 @@ typedef uint64_t hal_timer_t;
|
||||
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
|
||||
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
|
||||
|
||||
#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(STEP_TIMER_NUM)
|
||||
#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(STEP_TIMER_NUM)
|
||||
#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM)
|
||||
#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP)
|
||||
#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP)
|
||||
#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP)
|
||||
|
||||
#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM)
|
||||
#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM)
|
||||
#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP)
|
||||
#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP)
|
||||
|
||||
#ifndef HAL_TEMP_TIMER_ISR
|
||||
#define HAL_TEMP_TIMER_ISR() extern "C" void tempTC_Handler()
|
||||
@@ -121,13 +121,13 @@ typedef struct {
|
||||
// Public Variables
|
||||
// ------------------------
|
||||
|
||||
extern const tTimerConfig TimerConfig[];
|
||||
extern const tTimerConfig timer_config[];
|
||||
|
||||
// ------------------------
|
||||
// Public functions
|
||||
// ------------------------
|
||||
|
||||
void HAL_timer_start (const uint8_t timer_num, uint32_t frequency);
|
||||
void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency);
|
||||
void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t count);
|
||||
hal_timer_t HAL_timer_get_compare(const uint8_t timer_num);
|
||||
hal_timer_t HAL_timer_get_count(const uint8_t timer_num);
|
||||
@@ -136,5 +136,5 @@ void HAL_timer_enable_interrupt(const uint8_t timer_num);
|
||||
void HAL_timer_disable_interrupt(const uint8_t timer_num);
|
||||
bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
|
||||
|
||||
#define HAL_timer_isr_prologue(TIMER_NUM)
|
||||
#define HAL_timer_isr_epilogue(TIMER_NUM)
|
||||
#define HAL_timer_isr_prologue(T) NOOP
|
||||
#define HAL_timer_isr_epilogue(T) NOOP
|
||||
|
94
Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp
Normal file
94
Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp
Normal file
@@ -0,0 +1,94 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* Copypaste of SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#ifdef ARDUINO_ARCH_ESP32
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#if EITHER(MKS_MINI_12864, FYSETC_MINI_12864_2_1)
|
||||
|
||||
#include <U8glib-HAL.h>
|
||||
#include "../shared/HAL_SPI.h"
|
||||
#include "HAL.h"
|
||||
#include "SPI.h"
|
||||
|
||||
static SPISettings spiConfig;
|
||||
|
||||
|
||||
#ifndef LCD_SPI_SPEED
|
||||
#ifdef SD_SPI_SPEED
|
||||
#define LCD_SPI_SPEED SD_SPI_SPEED // Assume SPI speed shared with SD
|
||||
#else
|
||||
#define LCD_SPI_SPEED SPI_FULL_SPEED // Use full speed if SD speed is not supplied
|
||||
#endif
|
||||
#endif
|
||||
|
||||
uint8_t u8g_eps_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) {
|
||||
static uint8_t msgInitCount = 2; // Ignore all messages until 2nd U8G_COM_MSG_INIT
|
||||
if (msgInitCount) {
|
||||
if (msg == U8G_COM_MSG_INIT) msgInitCount--;
|
||||
if (msgInitCount) return -1;
|
||||
}
|
||||
|
||||
switch (msg) {
|
||||
case U8G_COM_MSG_STOP: break;
|
||||
|
||||
case U8G_COM_MSG_INIT:
|
||||
OUT_WRITE(DOGLCD_CS, HIGH);
|
||||
OUT_WRITE(DOGLCD_A0, HIGH);
|
||||
OUT_WRITE(LCD_RESET_PIN, HIGH);
|
||||
u8g_Delay(5);
|
||||
spiBegin();
|
||||
spiInit(LCD_SPI_SPEED);
|
||||
break;
|
||||
|
||||
case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */
|
||||
WRITE(DOGLCD_A0, arg_val ? HIGH : LOW);
|
||||
break;
|
||||
|
||||
case U8G_COM_MSG_CHIP_SELECT: /* arg_val == 0 means HIGH level of U8G_PI_CS */
|
||||
WRITE(DOGLCD_CS, arg_val ? LOW : HIGH);
|
||||
break;
|
||||
|
||||
case U8G_COM_MSG_RESET:
|
||||
WRITE(LCD_RESET_PIN, arg_val);
|
||||
break;
|
||||
|
||||
case U8G_COM_MSG_WRITE_BYTE:
|
||||
spiSend((uint8_t)arg_val);
|
||||
break;
|
||||
|
||||
case U8G_COM_MSG_WRITE_SEQ:
|
||||
uint8_t *ptr = (uint8_t*) arg_ptr;
|
||||
while (arg_val > 0) {
|
||||
spiSend(*ptr++);
|
||||
arg_val--;
|
||||
}
|
||||
break;
|
||||
}
|
||||
return 1;
|
||||
}
|
||||
|
||||
#endif // EITHER(MKS_MINI_12864, FYSETC_MINI_12864_2_1)
|
||||
|
||||
#endif // ARDUINO_ARCH_ESP32
|
@@ -1,42 +0,0 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#ifdef ARDUINO_ARCH_ESP32
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#if ENABLED(USE_WATCHDOG)
|
||||
|
||||
#define WDT_TIMEOUT_US TERN(WATCHDOG_DURATION_8S, 8000000, 4000000) // 4 or 8 second timeout
|
||||
|
||||
#include "watchdog.h"
|
||||
|
||||
void watchdogSetup() {
|
||||
// do whatever. don't remove this function.
|
||||
}
|
||||
|
||||
void watchdog_init() {
|
||||
// TODO
|
||||
}
|
||||
|
||||
#endif // USE_WATCHDOG
|
||||
|
||||
#endif // ARDUINO_ARCH_ESP32
|
@@ -1,38 +0,0 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
esp_err_t esp_task_wdt_reset();
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
// Initialize watchdog with a 4 second interrupt time
|
||||
void watchdog_init();
|
||||
|
||||
// Reset watchdog.
|
||||
inline void HAL_watchdog_refresh() { esp_task_wdt_reset(); }
|
Reference in New Issue
Block a user