Shorter paths to HAL, ExtUI (#17156)
This commit is contained in:
33
Marlin/src/HAL/ESP32/FlushableHardwareSerial.cpp
Normal file
33
Marlin/src/HAL/ESP32/FlushableHardwareSerial.cpp
Normal file
@ -0,0 +1,33 @@
|
||||
/**
|
||||
* 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 <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#include "FlushableHardwareSerial.h"
|
||||
|
||||
#ifdef ARDUINO_ARCH_ESP32
|
||||
|
||||
FlushableHardwareSerial::FlushableHardwareSerial(int uart_nr)
|
||||
: HardwareSerial(uart_nr)
|
||||
{}
|
||||
|
||||
FlushableHardwareSerial flushableSerial(0);
|
||||
|
||||
#endif // ARDUINO_ARCH_ESP32
|
37
Marlin/src/HAL/ESP32/FlushableHardwareSerial.h
Normal file
37
Marlin/src/HAL/ESP32/FlushableHardwareSerial.h
Normal file
@ -0,0 +1,37 @@
|
||||
/**
|
||||
* 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 <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#ifdef ARDUINO_ARCH_ESP32
|
||||
|
||||
#include <HardwareSerial.h>
|
||||
|
||||
class FlushableHardwareSerial : public HardwareSerial {
|
||||
public:
|
||||
FlushableHardwareSerial(int uart_nr);
|
||||
|
||||
inline void flushTX() { /* No need to flush the hardware serial, but defined here for compatibility. */ }
|
||||
};
|
||||
|
||||
extern FlushableHardwareSerial flushableSerial;
|
||||
|
||||
#endif // ARDUINO_ARCH_ESP32
|
303
Marlin/src/HAL/ESP32/HAL.cpp
Normal file
303
Marlin/src/HAL/ESP32/HAL.cpp
Normal file
@ -0,0 +1,303 @@
|
||||
/**
|
||||
* 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 <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifdef ARDUINO_ARCH_ESP32
|
||||
|
||||
#include "HAL.h"
|
||||
#include "timers.h"
|
||||
#include <rom/rtc.h>
|
||||
#include <driver/adc.h>
|
||||
#include <esp_adc_cal.h>
|
||||
#include <HardwareSerial.h>
|
||||
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if ENABLED(WIFISUPPORT)
|
||||
#include <ESPAsyncWebServer.h>
|
||||
#include "wifi.h"
|
||||
#if ENABLED(OTASUPPORT)
|
||||
#include "ota.h"
|
||||
#endif
|
||||
#if ENABLED(WEBSUPPORT)
|
||||
#include "spiffs.h"
|
||||
#include "web.h"
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// ------------------------
|
||||
// Externs
|
||||
// ------------------------
|
||||
|
||||
portMUX_TYPE spinlock = portMUX_INITIALIZER_UNLOCKED;
|
||||
|
||||
// ------------------------
|
||||
// Local defines
|
||||
// ------------------------
|
||||
|
||||
#define V_REF 1100
|
||||
|
||||
// ------------------------
|
||||
// Public Variables
|
||||
// ------------------------
|
||||
|
||||
uint16_t HAL_adc_result;
|
||||
|
||||
// ------------------------
|
||||
// Private Variables
|
||||
// ------------------------
|
||||
|
||||
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];
|
||||
|
||||
// ------------------------
|
||||
// Public functions
|
||||
// ------------------------
|
||||
|
||||
#if ENABLED(WIFI_CUSTOM_COMMAND)
|
||||
|
||||
bool wifi_custom_command(char * const command_ptr) {
|
||||
#if ENABLED(ESP3D_WIFISUPPORT)
|
||||
return esp3dlib.parse(command_ptr);
|
||||
#else
|
||||
UNUSED(command_ptr);
|
||||
return false;
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
void HAL_init() { i2s_init(); }
|
||||
|
||||
void HAL_init_board() {
|
||||
|
||||
#if ENABLED(ESP3D_WIFISUPPORT)
|
||||
esp3dlib.init();
|
||||
#elif ENABLED(WIFISUPPORT)
|
||||
wifi_init();
|
||||
#if ENABLED(OTASUPPORT)
|
||||
OTA_init();
|
||||
#endif
|
||||
#if ENABLED(WEBSUPPORT)
|
||||
spiffs_init();
|
||||
web_init();
|
||||
#endif
|
||||
server.begin();
|
||||
#endif
|
||||
|
||||
// ESP32 uses a GPIO matrix that allows pins to be assigned to hardware serial ports.
|
||||
// The following code initializes hardware Serial1 and Serial2 to use user-defined pins
|
||||
// if they have been defined.
|
||||
#if defined(HARDWARE_SERIAL1_RX) && defined(HARDWARE_SERIAL1_TX)
|
||||
HardwareSerial Serial1(1);
|
||||
#ifdef TMC_BAUD_RATE // use TMC_BAUD_RATE for Serial1 if defined
|
||||
Serial1.begin(TMC_BAUD_RATE, SERIAL_8N1, HARDWARE_SERIAL1_RX, HARDWARE_SERIAL1_TX);
|
||||
#else // use default BAUDRATE if TMC_BAUD_RATE not defined
|
||||
Serial1.begin(BAUDRATE, SERIAL_8N1, HARDWARE_SERIAL1_RX, HARDWARE_SERIAL1_TX);
|
||||
#endif
|
||||
#endif
|
||||
#if defined(HARDWARE_SERIAL2_RX) && defined(HARDWARE_SERIAL2_TX)
|
||||
HardwareSerial Serial2(2);
|
||||
#ifdef TMC_BAUD_RATE // use TMC_BAUD_RATE for Serial1 if defined
|
||||
Serial2.begin(TMC_BAUD_RATE, SERIAL_8N1, HARDWARE_SERIAL2_RX, HARDWARE_SERIAL2_TX);
|
||||
#else // use default BAUDRATE if TMC_BAUD_RATE not defined
|
||||
Serial2.begin(BAUDRATE, SERIAL_8N1, HARDWARE_SERIAL2_RX, HARDWARE_SERIAL2_TX);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
void HAL_idletask() {
|
||||
#if BOTH(WIFISUPPORT, OTASUPPORT)
|
||||
OTA_handle();
|
||||
#endif
|
||||
#if ENABLED(ESP3D_WIFISUPPORT)
|
||||
esp3dlib.idletask();
|
||||
#endif
|
||||
}
|
||||
|
||||
void HAL_clear_reset_source() { }
|
||||
|
||||
uint8_t HAL_get_reset_source() { return rtc_get_reset_reason(1); }
|
||||
|
||||
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(); }
|
||||
|
||||
// ------------------------
|
||||
// ADC
|
||||
// ------------------------
|
||||
#define ADC1_CHANNEL(pin) ADC1_GPIO ## pin ## _CHANNEL
|
||||
|
||||
adc1_channel_t get_channel(int pin) {
|
||||
switch (pin) {
|
||||
case 39: return ADC1_CHANNEL(39);
|
||||
case 36: return ADC1_CHANNEL(36);
|
||||
case 35: return ADC1_CHANNEL(35);
|
||||
case 34: return ADC1_CHANNEL(34);
|
||||
case 33: return ADC1_CHANNEL(33);
|
||||
case 32: return ADC1_CHANNEL(32);
|
||||
}
|
||||
return ADC1_CHANNEL_MAX;
|
||||
}
|
||||
|
||||
void adc1_set_attenuation(adc1_channel_t chan, adc_atten_t atten) {
|
||||
if (attenuations[chan] != atten) {
|
||||
adc1_config_channel_atten(chan, atten);
|
||||
attenuations[chan] = atten;
|
||||
}
|
||||
}
|
||||
|
||||
void HAL_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
|
||||
#if HAS_TEMP_ADC_0
|
||||
adc1_set_attenuation(get_channel(TEMP_0_PIN), ADC_ATTEN_11db);
|
||||
#endif
|
||||
#if HAS_TEMP_ADC_1
|
||||
adc1_set_attenuation(get_channel(TEMP_1_PIN), ADC_ATTEN_11db);
|
||||
#endif
|
||||
#if HAS_TEMP_ADC_2
|
||||
adc1_set_attenuation(get_channel(TEMP_2_PIN), ADC_ATTEN_11db);
|
||||
#endif
|
||||
#if HAS_TEMP_ADC_3
|
||||
adc1_set_attenuation(get_channel(TEMP_3_PIN), ADC_ATTEN_11db);
|
||||
#endif
|
||||
#if HAS_TEMP_ADC_4
|
||||
adc1_set_attenuation(get_channel(TEMP_4_PIN), ADC_ATTEN_11db);
|
||||
#endif
|
||||
#if HAS_TEMP_ADC_5
|
||||
adc1_set_attenuation(get_channel(TEMP_5_PIN), ADC_ATTEN_11db);
|
||||
#endif
|
||||
#if HAS_TEMP_ADC_6
|
||||
adc2_set_attenuation(get_channel(TEMP_6_PIN), ADC_ATTEN_11db);
|
||||
#endif
|
||||
#if HAS_TEMP_ADC_7
|
||||
adc3_set_attenuation(get_channel(TEMP_7_PIN), ADC_ATTEN_11db);
|
||||
#endif
|
||||
#if HAS_HEATED_BED
|
||||
adc1_set_attenuation(get_channel(TEMP_BED_PIN), ADC_ATTEN_11db);
|
||||
#endif
|
||||
#if HAS_TEMP_CHAMBER
|
||||
adc1_set_attenuation(get_channel(TEMP_CHAMBER_PIN), ADC_ATTEN_11db);
|
||||
#endif
|
||||
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||
adc1_set_attenuation(get_channel(FILWIDTH_PIN), ADC_ATTEN_11db);
|
||||
#endif
|
||||
|
||||
// Note that adc2 is shared with the WiFi module, which has higher priority, so the conversion may fail.
|
||||
// That's why we're not setting it up here.
|
||||
|
||||
// Calculate ADC characteristics (i.e., gain and offset factors for each attenuation level)
|
||||
for (int i = 0; i < ADC_ATTEN_MAX; i++) {
|
||||
esp_adc_cal_characterize(ADC_UNIT_1, (adc_atten_t)i, ADC_WIDTH_BIT_12, V_REF, &characteristics[i]);
|
||||
|
||||
// Change attenuation 100mV below the calibrated threshold
|
||||
thresholds[i] = esp_adc_cal_raw_to_voltage(4095, &characteristics[i]);
|
||||
}
|
||||
}
|
||||
|
||||
void HAL_adc_start_conversion(const uint8_t adc_pin) {
|
||||
const adc1_channel_t chan = get_channel(adc_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;
|
||||
|
||||
// Change the attenuation level based on the new reading
|
||||
adc_atten_t atten;
|
||||
if (mv < thresholds[ADC_ATTEN_DB_0] - 100)
|
||||
atten = ADC_ATTEN_DB_0;
|
||||
else if (mv > thresholds[ADC_ATTEN_DB_0] - 50 && mv < thresholds[ADC_ATTEN_DB_2_5] - 100)
|
||||
atten = ADC_ATTEN_DB_2_5;
|
||||
else if (mv > thresholds[ADC_ATTEN_DB_2_5] - 50 && mv < thresholds[ADC_ATTEN_DB_6] - 100)
|
||||
atten = ADC_ATTEN_DB_6;
|
||||
else if (mv > thresholds[ADC_ATTEN_DB_6] - 50)
|
||||
atten = ADC_ATTEN_DB_11;
|
||||
else return;
|
||||
|
||||
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++;
|
||||
}
|
||||
ledcWrite(pin_to_channel[pin], value);
|
||||
return;
|
||||
}
|
||||
|
||||
int idx = -1;
|
||||
|
||||
// Search Pin
|
||||
for (int i = 0; i < numPWMUsed; ++i)
|
||||
if (pwmPins[i] == pin) { idx = i; break; }
|
||||
|
||||
// not found ?
|
||||
if (idx < 0) {
|
||||
// No slots remaining
|
||||
if (numPWMUsed >= MAX_PWM_PINS) return;
|
||||
|
||||
// Take new slot for pin
|
||||
idx = numPWMUsed;
|
||||
pwmPins[idx] = pin;
|
||||
// Start timer on first use
|
||||
if (idx == 0) HAL_timer_start(PWM_TIMER_NUM, PWM_TIMER_FREQUENCY);
|
||||
|
||||
++numPWMUsed;
|
||||
}
|
||||
|
||||
// Use 7bit internal value - add 1 to have 100% high at 255
|
||||
pwmValues[idx] = (value + 1) / 2;
|
||||
}
|
||||
|
||||
// Handle PWM timer interrupt
|
||||
HAL_PWM_TIMER_ISR() {
|
||||
HAL_timer_isr_prologue(PWM_TIMER_NUM);
|
||||
|
||||
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);
|
||||
}
|
||||
|
||||
// 128 for 7 Bit resolution
|
||||
count = (count + 1) & 0x7F;
|
||||
|
||||
HAL_timer_isr_epilogue(PWM_TIMER_NUM);
|
||||
}
|
||||
|
||||
#endif // ARDUINO_ARCH_ESP32
|
180
Marlin/src/HAL/ESP32/HAL.h
Normal file
180
Marlin/src/HAL/ESP32/HAL.h
Normal file
@ -0,0 +1,180 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* Description: HAL for Espressif ESP32 WiFi
|
||||
*/
|
||||
|
||||
#define CPU_32_BIT
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include "../shared/Marduino.h"
|
||||
#include "../shared/math_32bit.h"
|
||||
#include "../shared/HAL_SPI.h"
|
||||
|
||||
#include "fastio.h"
|
||||
#include "watchdog.h"
|
||||
#include "i2s.h"
|
||||
|
||||
#include "timers.h"
|
||||
|
||||
#if ENABLED(WIFISUPPORT)
|
||||
#include "WebSocketSerial.h"
|
||||
#endif
|
||||
|
||||
#if ENABLED(ESP3D_WIFISUPPORT)
|
||||
#include "esp3dlib.h"
|
||||
#endif
|
||||
|
||||
#include "FlushableHardwareSerial.h"
|
||||
|
||||
// ------------------------
|
||||
// Defines
|
||||
// ------------------------
|
||||
|
||||
extern portMUX_TYPE spinlock;
|
||||
|
||||
#define MYSERIAL0 flushableSerial
|
||||
|
||||
#if EITHER(WIFISUPPORT, ESP3D_WIFISUPPORT)
|
||||
#if ENABLED(ESP3D_WIFISUPPORT)
|
||||
#define MYSERIAL1 Serial2Socket
|
||||
#else
|
||||
#define MYSERIAL1 webSocketSerial
|
||||
#endif
|
||||
#define NUM_SERIAL 2
|
||||
#else
|
||||
#define NUM_SERIAL 1
|
||||
#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)
|
||||
|
||||
// Fix bug in pgm_read_ptr
|
||||
#undef pgm_read_ptr
|
||||
#define pgm_read_ptr(addr) (*(addr))
|
||||
|
||||
// ------------------------
|
||||
// Types
|
||||
// ------------------------
|
||||
|
||||
typedef int16_t pin_t;
|
||||
|
||||
#define HAL_SERVO_LIB Servo
|
||||
|
||||
// ------------------------
|
||||
// Public Variables
|
||||
// ------------------------
|
||||
|
||||
/** result of last ADC conversion */
|
||||
extern uint16_t HAL_adc_result;
|
||||
|
||||
// ------------------------
|
||||
// Public functions
|
||||
// ------------------------
|
||||
|
||||
// clear reset reason
|
||||
void HAL_clear_reset_source();
|
||||
|
||||
// reset reason
|
||||
uint8_t HAL_get_reset_source();
|
||||
|
||||
void _delay_ms(int delay);
|
||||
|
||||
#pragma GCC diagnostic push
|
||||
#pragma GCC diagnostic ignored "-Wunused-function"
|
||||
int freeMemory();
|
||||
#pragma GCC diagnostic pop
|
||||
|
||||
void analogWrite(pin_t pin, int value);
|
||||
|
||||
// EEPROM
|
||||
void eeprom_write_byte(uint8_t *pos, unsigned char value);
|
||||
uint8_t eeprom_read_byte(uint8_t *pos);
|
||||
void eeprom_read_block (void *__dst, const void *__src, size_t __n);
|
||||
void eeprom_update_block (const void *__src, void *__dst, size_t __n);
|
||||
|
||||
// ADC
|
||||
#define HAL_ANALOG_SELECT(pin)
|
||||
|
||||
void HAL_adc_init();
|
||||
|
||||
#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin)
|
||||
#define HAL_ADC_RESOLUTION 10
|
||||
#define HAL_READ_ADC() HAL_adc_result
|
||||
#define HAL_ADC_READY() true
|
||||
|
||||
void HAL_adc_start_conversion(const uint8_t adc_pin);
|
||||
|
||||
#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();
|
||||
void HAL_init();
|
||||
void HAL_init_board();
|
||||
|
||||
//
|
||||
// Delay in cycles (used by DELAY_NS / DELAY_US)
|
||||
//
|
||||
FORCE_INLINE static void DELAY_CYCLES(uint32_t x) {
|
||||
unsigned long start, ccount, stop;
|
||||
|
||||
/**
|
||||
* It's important to care for race conditions (and overflows) here.
|
||||
* Race condition example: If `stop` calculates to being close to the upper boundary of
|
||||
* `uint32_t` and if at the same time a longer loop interruption kicks in (e.g. due to other
|
||||
* FreeRTOS tasks or interrupts), `ccount` might overflow (and therefore be below `stop` again)
|
||||
* without the loop ever being able to notice that `ccount` had already been above `stop` once
|
||||
* (and that therefore the number of cycles to delay has already passed).
|
||||
* As DELAY_CYCLES (through DELAY_NS / DELAY_US) is used by software SPI bit banging to drive
|
||||
* LCDs and therefore might be called very, very often, this seemingly improbable situation did
|
||||
* actually happen in reality. It resulted in apparently random print pauses of ~17.9 seconds
|
||||
* (0x100000000 / 240 MHz) or multiples thereof, essentially ruining the current print by causing
|
||||
* large blobs of filament.
|
||||
*/
|
||||
|
||||
__asm__ __volatile__ ( "rsr %0, ccount" : "=a" (start) );
|
||||
stop = start + x;
|
||||
ccount = start;
|
||||
|
||||
if (stop >= start) {
|
||||
// no overflow, so only loop while in between start and stop:
|
||||
// 0x00000000 -----------------start****stop-- 0xffffffff
|
||||
while (ccount >= start && ccount < stop) {
|
||||
__asm__ __volatile__ ( "rsr %0, ccount" : "=a" (ccount) );
|
||||
}
|
||||
}
|
||||
else {
|
||||
// stop did overflow, so only loop while outside of stop and start:
|
||||
// 0x00000000 **stop-------------------start** 0xffffffff
|
||||
while (ccount >= start || ccount < stop) {
|
||||
__asm__ __volatile__ ( "rsr %0, ccount" : "=a" (ccount) );
|
||||
}
|
||||
}
|
||||
|
||||
}
|
117
Marlin/src/HAL/ESP32/HAL_SPI.cpp
Normal file
117
Marlin/src/HAL/ESP32/HAL_SPI.cpp
Normal file
@ -0,0 +1,117 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
* Copyright (c) 2017 Victor Perez
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifdef ARDUINO_ARCH_ESP32
|
||||
|
||||
#include "HAL.h"
|
||||
#include "../shared/HAL_SPI.h"
|
||||
#include <pins_arduino.h>
|
||||
#include "spi_pins.h"
|
||||
#include <SPI.h>
|
||||
|
||||
#include "../../core/macros.h"
|
||||
|
||||
// ------------------------
|
||||
// Public Variables
|
||||
// ------------------------
|
||||
|
||||
static SPISettings spiConfig;
|
||||
|
||||
// ------------------------
|
||||
// Public functions
|
||||
// ------------------------
|
||||
|
||||
#if ENABLED(SOFTWARE_SPI)
|
||||
|
||||
// ------------------------
|
||||
// Software SPI
|
||||
// ------------------------
|
||||
#error "Software SPI not supported for ESP32. Use Hardware SPI."
|
||||
|
||||
#else
|
||||
|
||||
// ------------------------
|
||||
// Hardware SPI
|
||||
// ------------------------
|
||||
|
||||
void spiBegin() {
|
||||
#if !PIN_EXISTS(SS)
|
||||
#error "SS_PIN not defined!"
|
||||
#endif
|
||||
|
||||
OUT_WRITE(SS_PIN, HIGH);
|
||||
}
|
||||
|
||||
void spiInit(uint8_t spiRate) {
|
||||
uint32_t clock;
|
||||
|
||||
switch (spiRate) {
|
||||
case SPI_FULL_SPEED: clock = 16000000; break;
|
||||
case SPI_HALF_SPEED: clock = 8000000; break;
|
||||
case SPI_QUARTER_SPEED: clock = 4000000; break;
|
||||
case SPI_EIGHTH_SPEED: clock = 2000000; break;
|
||||
case SPI_SIXTEENTH_SPEED: clock = 1000000; break;
|
||||
case SPI_SPEED_5: clock = 500000; break;
|
||||
case SPI_SPEED_6: clock = 250000; break;
|
||||
default: clock = 1000000; // Default from the SPI library
|
||||
}
|
||||
|
||||
spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0);
|
||||
SPI.begin();
|
||||
}
|
||||
|
||||
uint8_t spiRec() {
|
||||
SPI.beginTransaction(spiConfig);
|
||||
uint8_t returnByte = SPI.transfer(0xFF);
|
||||
SPI.endTransaction();
|
||||
return returnByte;
|
||||
}
|
||||
|
||||
void spiRead(uint8_t* buf, uint16_t nbyte) {
|
||||
SPI.beginTransaction(spiConfig);
|
||||
SPI.transferBytes(0, buf, nbyte);
|
||||
SPI.endTransaction();
|
||||
}
|
||||
|
||||
void spiSend(uint8_t b) {
|
||||
SPI.beginTransaction(spiConfig);
|
||||
SPI.transfer(b);
|
||||
SPI.endTransaction();
|
||||
}
|
||||
|
||||
void spiSendBlock(uint8_t token, const uint8_t* buf) {
|
||||
SPI.beginTransaction(spiConfig);
|
||||
SPI.transfer(token);
|
||||
SPI.writeBytes(const_cast<uint8_t*>(buf), 512);
|
||||
SPI.endTransaction();
|
||||
}
|
||||
|
||||
void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) {
|
||||
spiConfig = SPISettings(spiClock, bitOrder, dataMode);
|
||||
|
||||
SPI.beginTransaction(spiConfig);
|
||||
}
|
||||
|
||||
#endif // !SOFTWARE_SPI
|
||||
|
||||
#endif // ARDUINO_ARCH_ESP32
|
71
Marlin/src/HAL/ESP32/Servo.cpp
Normal file
71
Marlin/src/HAL/ESP32/Servo.cpp
Normal file
@ -0,0 +1,71 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#ifdef ARDUINO_ARCH_ESP32
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#if HAS_SERVOS
|
||||
|
||||
#include "Servo.h"
|
||||
|
||||
// Adjacent channels (0/1, 2/3 etc.) share the same timer and therefore the same frequency and resolution settings on ESP32,
|
||||
// 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++;
|
||||
}
|
||||
|
||||
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;
|
||||
}
|
||||
|
||||
void Servo::detach() { ledcDetachPin(pin); }
|
||||
|
||||
int Servo::read() { return degrees; }
|
||||
|
||||
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);
|
||||
}
|
||||
|
||||
void Servo::move(const int value) {
|
||||
constexpr uint16_t servo_delay[] = SERVO_DELAY;
|
||||
static_assert(COUNT(servo_delay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long.");
|
||||
if (attach(0) >= 0) {
|
||||
write(value);
|
||||
safe_delay(servo_delay[channel]);
|
||||
#if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE)
|
||||
detach();
|
||||
#endif
|
||||
}
|
||||
}
|
||||
#endif // HAS_SERVOS
|
||||
|
||||
#endif // ARDUINO_ARCH_ESP32
|
49
Marlin/src/HAL/ESP32/Servo.h
Normal file
49
Marlin/src/HAL/ESP32/Servo.h
Normal file
@ -0,0 +1,49 @@
|
||||
/**
|
||||
* 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 <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include <Arduino.h>
|
||||
|
||||
class Servo {
|
||||
static const int MIN_ANGLE = 0,
|
||||
MAX_ANGLE = 180,
|
||||
MIN_PULSE_WIDTH = 544, // Shortest pulse sent to a servo
|
||||
MAX_PULSE_WIDTH = 2400, // Longest pulse sent to a servo
|
||||
TAU_MSEC = 20,
|
||||
TAU_USEC = (TAU_MSEC * 1000),
|
||||
MAX_COMPARE = ((1 << 16) - 1), // 65535
|
||||
CHANNEL_MAX_NUM = 16;
|
||||
|
||||
public:
|
||||
Servo();
|
||||
int8_t attach(const int pin); // attach the given pin to the next free channel, set pinMode, return channel number (-1 on fail)
|
||||
void detach();
|
||||
void write(int degrees); // set angle
|
||||
void move(const int degrees); // attach the servo, then move to value
|
||||
int read(); // returns current pulse width as an angle between 0 and 180 degrees
|
||||
|
||||
private:
|
||||
static int channel_next_free;
|
||||
int channel;
|
||||
int pin;
|
||||
int degrees;
|
||||
};
|
153
Marlin/src/HAL/ESP32/WebSocketSerial.cpp
Normal file
153
Marlin/src/HAL/ESP32/WebSocketSerial.cpp
Normal file
@ -0,0 +1,153 @@
|
||||
/**
|
||||
* 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 <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#ifdef ARDUINO_ARCH_ESP32
|
||||
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if ENABLED(WIFISUPPORT)
|
||||
|
||||
#include "WebSocketSerial.h"
|
||||
#include "wifi.h"
|
||||
#include <ESPAsyncWebServer.h>
|
||||
|
||||
WebSocketSerial webSocketSerial;
|
||||
AsyncWebSocket ws("/ws"); // TODO Move inside the class.
|
||||
|
||||
// RingBuffer impl
|
||||
|
||||
#define NEXT_INDEX(I, SIZE) ((I + 1) & (ring_buffer_pos_t)(SIZE - 1))
|
||||
|
||||
RingBuffer::RingBuffer(ring_buffer_pos_t size)
|
||||
: data(new uint8_t[size]),
|
||||
size(size),
|
||||
read_index(0),
|
||||
write_index(0)
|
||||
{}
|
||||
|
||||
RingBuffer::~RingBuffer() { delete[] data; }
|
||||
|
||||
ring_buffer_pos_t RingBuffer::write(const uint8_t c) {
|
||||
const ring_buffer_pos_t n = NEXT_INDEX(write_index, size);
|
||||
|
||||
if (n != read_index) {
|
||||
this->data[write_index] = c;
|
||||
write_index = n;
|
||||
return 1;
|
||||
}
|
||||
|
||||
// TODO: buffer is full, handle?
|
||||
return 0;
|
||||
}
|
||||
|
||||
ring_buffer_pos_t RingBuffer::write(const uint8_t *buffer, ring_buffer_pos_t size) {
|
||||
ring_buffer_pos_t written = 0;
|
||||
for (ring_buffer_pos_t i = 0; i < size; i++) {
|
||||
written += write(buffer[i]);
|
||||
}
|
||||
return written;
|
||||
}
|
||||
|
||||
int RingBuffer::available() {
|
||||
return (size - read_index + write_index) & (size - 1);
|
||||
}
|
||||
|
||||
int RingBuffer::peek() {
|
||||
return available() ? data[read_index] : -1;
|
||||
}
|
||||
|
||||
int RingBuffer::read() {
|
||||
if (available()) {
|
||||
const int ret = data[read_index];
|
||||
read_index = NEXT_INDEX(read_index, size);
|
||||
return ret;
|
||||
}
|
||||
return -1;
|
||||
}
|
||||
|
||||
ring_buffer_pos_t RingBuffer::read(uint8_t *buffer) {
|
||||
ring_buffer_pos_t len = available();
|
||||
|
||||
for(ring_buffer_pos_t i = 0; read_index != write_index; i++) {
|
||||
buffer[i] = data[read_index];
|
||||
read_index = NEXT_INDEX(read_index, size);
|
||||
}
|
||||
|
||||
return len;
|
||||
}
|
||||
|
||||
void RingBuffer::flush() { read_index = write_index; }
|
||||
|
||||
// WebSocketSerial impl
|
||||
WebSocketSerial::WebSocketSerial()
|
||||
: rx_buffer(RingBuffer(RX_BUFFER_SIZE)),
|
||||
tx_buffer(RingBuffer(TX_BUFFER_SIZE))
|
||||
{}
|
||||
|
||||
void WebSocketSerial::begin(const long baud_setting) {
|
||||
ws.onEvent([this](AsyncWebSocket *server, AsyncWebSocketClient *client, AwsEventType type, void *arg, uint8_t *data, size_t len) {
|
||||
switch (type) {
|
||||
case WS_EVT_CONNECT: client->ping(); break; // client connected
|
||||
case WS_EVT_DISCONNECT: // client disconnected
|
||||
case WS_EVT_ERROR: // error was received from the other end
|
||||
case WS_EVT_PONG: break; // pong message was received (in response to a ping request maybe)
|
||||
case WS_EVT_DATA: { // data packet
|
||||
AwsFrameInfo * info = (AwsFrameInfo*)arg;
|
||||
if (info->opcode == WS_TEXT || info->message_opcode == WS_TEXT)
|
||||
this->rx_buffer.write(data, len);
|
||||
}
|
||||
}
|
||||
});
|
||||
server.addHandler(&ws);
|
||||
}
|
||||
|
||||
void WebSocketSerial::end() { }
|
||||
int WebSocketSerial::peek() { return rx_buffer.peek(); }
|
||||
int WebSocketSerial::read() { return rx_buffer.read(); }
|
||||
int WebSocketSerial::available() { return rx_buffer.available(); }
|
||||
void WebSocketSerial::flush() { rx_buffer.flush(); }
|
||||
|
||||
size_t WebSocketSerial::write(const uint8_t c) {
|
||||
size_t ret = tx_buffer.write(c);
|
||||
|
||||
if (ret && c == '\n') {
|
||||
uint8_t tmp[TX_BUFFER_SIZE];
|
||||
ring_buffer_pos_t size = tx_buffer.read(tmp);
|
||||
ws.textAll(tmp, size);
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
size_t WebSocketSerial::write(const uint8_t* buffer, size_t size) {
|
||||
size_t written = 0;
|
||||
for(size_t i = 0; i < size; i++) {
|
||||
written += write(buffer[i]);
|
||||
}
|
||||
return written;
|
||||
}
|
||||
|
||||
void WebSocketSerial::flushTX() {
|
||||
// No need to do anything as there's no benefit to sending partial lines over the websocket connection.
|
||||
}
|
||||
|
||||
#endif // WIFISUPPORT
|
||||
#endif // ARDUINO_ARCH_ESP32
|
86
Marlin/src/HAL/ESP32/WebSocketSerial.h
Normal file
86
Marlin/src/HAL/ESP32/WebSocketSerial.h
Normal file
@ -0,0 +1,86 @@
|
||||
/**
|
||||
* 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 <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#include <Stream.h>
|
||||
|
||||
#ifndef TX_BUFFER_SIZE
|
||||
#define TX_BUFFER_SIZE 32
|
||||
#endif
|
||||
#if ENABLED(WIFISUPPORT)
|
||||
#ifndef RX_BUFFER_SIZE
|
||||
#define RX_BUFFER_SIZE 128
|
||||
#endif
|
||||
#if TX_BUFFER_SIZE <= 0
|
||||
#error "TX_BUFFER_SIZE is required for the WebSocket."
|
||||
#endif
|
||||
#endif
|
||||
|
||||
typedef uint16_t ring_buffer_pos_t;
|
||||
|
||||
class RingBuffer {
|
||||
uint8_t *data;
|
||||
ring_buffer_pos_t size, read_index, write_index;
|
||||
|
||||
public:
|
||||
RingBuffer(ring_buffer_pos_t size);
|
||||
~RingBuffer();
|
||||
|
||||
int available();
|
||||
int peek();
|
||||
int read();
|
||||
ring_buffer_pos_t read(uint8_t *buffer);
|
||||
void flush();
|
||||
ring_buffer_pos_t write(const uint8_t c);
|
||||
ring_buffer_pos_t write(const uint8_t* buffer, ring_buffer_pos_t size);
|
||||
};
|
||||
|
||||
class WebSocketSerial: public Stream {
|
||||
RingBuffer rx_buffer;
|
||||
RingBuffer tx_buffer;
|
||||
|
||||
public:
|
||||
WebSocketSerial();
|
||||
void begin(const long);
|
||||
void end();
|
||||
int available();
|
||||
int peek();
|
||||
int read();
|
||||
void flush();
|
||||
void flushTX();
|
||||
size_t write(const uint8_t c);
|
||||
size_t write(const uint8_t* buffer, size_t size);
|
||||
|
||||
operator bool() { return true; }
|
||||
|
||||
#if ENABLED(SERIAL_STATS_DROPPED_RX)
|
||||
FORCE_INLINE uint32_t dropped() { return 0; }
|
||||
#endif
|
||||
|
||||
#if ENABLED(SERIAL_STATS_MAX_RX_QUEUED)
|
||||
FORCE_INLINE int rxMaxEnqueued() { return 0; }
|
||||
#endif
|
||||
};
|
||||
|
||||
extern WebSocketSerial webSocketSerial;
|
84
Marlin/src/HAL/ESP32/endstop_interrupts.h
Normal file
84
Marlin/src/HAL/ESP32/endstop_interrupts.h
Normal file
@ -0,0 +1,84 @@
|
||||
/**
|
||||
* 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 <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* Endstop Interrupts
|
||||
*
|
||||
* Without endstop interrupts the endstop pins must be polled continually in
|
||||
* the stepper-ISR via endstops.update(), most of the time finding no change.
|
||||
* With this feature endstops.update() is called only when we know that at
|
||||
* least one endstop has changed state, saving valuable CPU cycles.
|
||||
*
|
||||
* This feature only works when all used endstop pins can generate an 'external interrupt'.
|
||||
*
|
||||
* Test whether pins issue interrupts on your board by flashing 'pin_interrupt_test.ino'.
|
||||
* (Located in Marlin/buildroot/share/pin_interrupt_test/pin_interrupt_test.ino)
|
||||
*/
|
||||
|
||||
#include "../../module/endstops.h"
|
||||
|
||||
// One ISR for all EXT-Interrupts
|
||||
void ICACHE_RAM_ATTR endstop_ISR() { endstops.update(); }
|
||||
|
||||
void setup_endstop_interrupts() {
|
||||
#define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE)
|
||||
#if HAS_X_MAX
|
||||
_ATTACH(X_MAX_PIN);
|
||||
#endif
|
||||
#if HAS_X_MIN
|
||||
_ATTACH(X_MIN_PIN);
|
||||
#endif
|
||||
#if HAS_Y_MAX
|
||||
_ATTACH(Y_MAX_PIN);
|
||||
#endif
|
||||
#if HAS_Y_MIN
|
||||
_ATTACH(Y_MIN_PIN);
|
||||
#endif
|
||||
#if HAS_Z_MAX
|
||||
_ATTACH(Z_MAX_PIN);
|
||||
#endif
|
||||
#if HAS_Z_MIN
|
||||
_ATTACH(Z_MIN_PIN);
|
||||
#endif
|
||||
#if HAS_Z2_MAX
|
||||
_ATTACH(Z2_MAX_PIN);
|
||||
#endif
|
||||
#if HAS_Z2_MIN
|
||||
_ATTACH(Z2_MIN_PIN);
|
||||
#endif
|
||||
#if HAS_Z3_MAX
|
||||
_ATTACH(Z3_MAX_PIN);
|
||||
#endif
|
||||
#if HAS_Z3_MIN
|
||||
_ATTACH(Z3_MIN_PIN);
|
||||
#endif
|
||||
#if HAS_Z4_MAX
|
||||
_ATTACH(Z4_MAX_PIN);
|
||||
#endif
|
||||
#if HAS_Z4_MIN
|
||||
_ATTACH(Z4_MIN_PIN);
|
||||
#endif
|
||||
#if HAS_Z_MIN_PROBE_PIN
|
||||
_ATTACH(Z_MIN_PROBE_PIN);
|
||||
#endif
|
||||
}
|
84
Marlin/src/HAL/ESP32/fastio.h
Normal file
84
Marlin/src/HAL/ESP32/fastio.h
Normal file
@ -0,0 +1,84 @@
|
||||
/**
|
||||
* 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 <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include "i2s.h"
|
||||
|
||||
/**
|
||||
* Utility functions
|
||||
*/
|
||||
|
||||
// I2S expander pin mapping.
|
||||
#define IS_I2S_EXPANDER_PIN(IO) TEST(IO, 7)
|
||||
#define I2S_EXPANDER_PIN_INDEX(IO) (IO & 0x7F)
|
||||
|
||||
// Set pin as input
|
||||
#define _SET_INPUT(IO) pinMode(IO, INPUT)
|
||||
|
||||
// Set pin as output
|
||||
#define _SET_OUTPUT(IO) pinMode(IO, OUTPUT)
|
||||
|
||||
// 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))
|
||||
|
||||
// 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
|
||||
#define SET_INPUT(IO) _SET_INPUT(IO)
|
||||
|
||||
// Set pin as input with pullup wrapper
|
||||
#define SET_INPUT_PULLUP(IO) do{ _SET_INPUT(IO); _PULLUP(IO, HIGH); }while(0)
|
||||
|
||||
// Set pin as output wrapper
|
||||
#define SET_OUTPUT(IO) do{ _SET_OUTPUT(IO); }while(0)
|
||||
|
||||
// Set pin as PWM
|
||||
#define SET_PWM(IO) SET_OUTPUT(IO)
|
||||
|
||||
// Set pin as output and init
|
||||
#define OUT_WRITE(IO,V) do{ _SET_OUTPUT(IO); WRITE(IO,V); }while(0)
|
||||
|
||||
// digitalRead/Write wrappers
|
||||
#define extDigitalRead(IO) digitalRead(IO)
|
||||
#define extDigitalWrite(IO,V) digitalWrite(IO,V)
|
||||
|
||||
// PWM outputs
|
||||
#define PWM_PIN(P) (P < 34 || P > 127) // NOTE Pins >= 34 are input only on ESP32, so they can't be used for output.
|
||||
|
||||
// Toggle pin value
|
||||
#define TOGGLE(IO) WRITE(IO, !READ(IO))
|
||||
|
||||
//
|
||||
// Ports and functions
|
||||
//
|
||||
|
||||
// UART
|
||||
#define RXD 3
|
||||
#define TXD 1
|
||||
|
||||
// TWI (I2C)
|
||||
#define SCL 5
|
||||
#define SDA 4
|
343
Marlin/src/HAL/ESP32/i2s.cpp
Normal file
343
Marlin/src/HAL/ESP32/i2s.cpp
Normal file
@ -0,0 +1,343 @@
|
||||
/**
|
||||
* 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 <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#ifdef ARDUINO_ARCH_ESP32
|
||||
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
|
||||
#include "i2s.h"
|
||||
|
||||
#include "../shared/Marduino.h"
|
||||
#include <driver/periph_ctrl.h>
|
||||
#include <rom/lldesc.h>
|
||||
#include <soc/i2s_struct.h>
|
||||
#include <freertos/queue.h>
|
||||
#include "../../module/stepper.h"
|
||||
|
||||
#define DMA_BUF_COUNT 8 // number of DMA buffers to store data
|
||||
#define DMA_BUF_LEN 4092 // maximum size in bytes
|
||||
#define I2S_SAMPLE_SIZE 4 // 4 bytes, 32 bits per sample
|
||||
#define DMA_SAMPLE_COUNT DMA_BUF_LEN / I2S_SAMPLE_SIZE // number of samples per buffer
|
||||
|
||||
typedef enum {
|
||||
I2S_NUM_0 = 0x0, /*!< I2S 0*/
|
||||
I2S_NUM_1 = 0x1, /*!< I2S 1*/
|
||||
I2S_NUM_MAX,
|
||||
} i2s_port_t;
|
||||
|
||||
typedef struct {
|
||||
uint32_t **buffers;
|
||||
uint32_t *current;
|
||||
uint32_t rw_pos;
|
||||
lldesc_t **desc;
|
||||
xQueueHandle queue;
|
||||
} i2s_dma_t;
|
||||
|
||||
static portMUX_TYPE i2s_spinlock[I2S_NUM_MAX] = {portMUX_INITIALIZER_UNLOCKED, portMUX_INITIALIZER_UNLOCKED};
|
||||
static i2s_dev_t* I2S[I2S_NUM_MAX] = {&I2S0, &I2S1};
|
||||
static i2s_dma_t dma;
|
||||
|
||||
// output value
|
||||
uint32_t i2s_port_data = 0;
|
||||
|
||||
#define I2S_ENTER_CRITICAL() portENTER_CRITICAL(&i2s_spinlock[i2s_num])
|
||||
#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);
|
||||
}
|
||||
}
|
||||
|
||||
static esp_err_t i2s_reset_fifo(i2s_port_t i2s_num) {
|
||||
I2S_ENTER_CRITICAL();
|
||||
I2S[i2s_num]->conf.rx_fifo_reset = 1;
|
||||
I2S[i2s_num]->conf.rx_fifo_reset = 0;
|
||||
I2S[i2s_num]->conf.tx_fifo_reset = 1;
|
||||
I2S[i2s_num]->conf.tx_fifo_reset = 0;
|
||||
I2S_EXIT_CRITICAL();
|
||||
|
||||
return ESP_OK;
|
||||
}
|
||||
|
||||
esp_err_t i2s_start(i2s_port_t i2s_num) {
|
||||
//start DMA link
|
||||
I2S_ENTER_CRITICAL();
|
||||
i2s_reset_fifo(i2s_num);
|
||||
|
||||
//reset dma
|
||||
I2S[i2s_num]->lc_conf.in_rst = 1;
|
||||
I2S[i2s_num]->lc_conf.in_rst = 0;
|
||||
I2S[i2s_num]->lc_conf.out_rst = 1;
|
||||
I2S[i2s_num]->lc_conf.out_rst = 0;
|
||||
|
||||
I2S[i2s_num]->conf.tx_reset = 1;
|
||||
I2S[i2s_num]->conf.tx_reset = 0;
|
||||
I2S[i2s_num]->conf.rx_reset = 1;
|
||||
I2S[i2s_num]->conf.rx_reset = 0;
|
||||
|
||||
I2S[i2s_num]->int_clr.val = 0xFFFFFFFF;
|
||||
I2S[i2s_num]->out_link.start = 1;
|
||||
I2S[i2s_num]->conf.tx_start = 1;
|
||||
I2S_EXIT_CRITICAL();
|
||||
|
||||
return ESP_OK;
|
||||
}
|
||||
|
||||
esp_err_t i2s_stop(i2s_port_t i2s_num) {
|
||||
I2S_ENTER_CRITICAL();
|
||||
I2S[i2s_num]->out_link.stop = 1;
|
||||
I2S[i2s_num]->conf.tx_start = 0;
|
||||
|
||||
I2S[i2s_num]->int_clr.val = I2S[i2s_num]->int_st.val; //clear pending interrupt
|
||||
I2S_EXIT_CRITICAL();
|
||||
|
||||
return ESP_OK;
|
||||
}
|
||||
|
||||
static void IRAM_ATTR i2s_intr_handler_default(void *arg) {
|
||||
int dummy;
|
||||
lldesc_t *finish_desc;
|
||||
portBASE_TYPE high_priority_task_awoken = pdFALSE;
|
||||
|
||||
if (I2S0.int_st.out_eof) {
|
||||
// Get the descriptor of the last item in the linkedlist
|
||||
finish_desc = (lldesc_t*) I2S0.out_eof_des_addr;
|
||||
|
||||
// If the queue is full it's because we have an underflow,
|
||||
// more than buf_count isr without new data, remove the front buffer
|
||||
if (xQueueIsQueueFullFromISR(dma.queue))
|
||||
xQueueReceiveFromISR(dma.queue, &dummy, &high_priority_task_awoken);
|
||||
|
||||
xQueueSendFromISR(dma.queue, (void *)(&finish_desc->buf), &high_priority_task_awoken);
|
||||
}
|
||||
|
||||
if (high_priority_task_awoken == pdTRUE) portYIELD_FROM_ISR();
|
||||
|
||||
// clear interrupt
|
||||
I2S0.int_clr.val = I2S0.int_st.val; //clear pending interrupt
|
||||
}
|
||||
|
||||
void stepperTask(void* parameter) {
|
||||
uint32_t remaining = 0;
|
||||
|
||||
while (1) {
|
||||
xQueueReceive(dma.queue, &dma.current, portMAX_DELAY);
|
||||
dma.rw_pos = 0;
|
||||
|
||||
while (dma.rw_pos < DMA_SAMPLE_COUNT) {
|
||||
// Fill with the port data post pulse_phase until the next step
|
||||
if (remaining) {
|
||||
i2s_push_sample();
|
||||
remaining--;
|
||||
}
|
||||
else {
|
||||
Stepper::pulse_phase_isr();
|
||||
remaining = Stepper::block_phase_isr();
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
int i2s_init() {
|
||||
periph_module_enable(PERIPH_I2S0_MODULE);
|
||||
|
||||
/**
|
||||
* Each i2s transfer will take
|
||||
* fpll = PLL_D2_CLK -- clka_en = 0
|
||||
*
|
||||
* fi2s = fpll / N + b/a -- N = clkm_div_num
|
||||
* fi2s = 160MHz / 2
|
||||
* fi2s = 80MHz
|
||||
*
|
||||
* fbclk = fi2s / M -- M = tx_bck_div_num
|
||||
* fbclk = 80MHz / 2
|
||||
* fbclk = 40MHz
|
||||
*
|
||||
* fwclk = fbclk / 32
|
||||
*
|
||||
* for fwclk = 250kHz (4µS pulse time)
|
||||
* N = 10
|
||||
* M = 20
|
||||
*/
|
||||
|
||||
// Allocate the array of pointers to the buffers
|
||||
dma.buffers = (uint32_t **)malloc(sizeof(uint32_t*) * DMA_BUF_COUNT);
|
||||
if (dma.buffers == nullptr) return -1;
|
||||
|
||||
// Allocate each buffer that can be used by the DMA controller
|
||||
for (int buf_idx = 0; buf_idx < DMA_BUF_COUNT; buf_idx++) {
|
||||
dma.buffers[buf_idx] = (uint32_t*) heap_caps_calloc(1, DMA_BUF_LEN, MALLOC_CAP_DMA);
|
||||
if (dma.buffers[buf_idx] == nullptr) return -1;
|
||||
}
|
||||
|
||||
// Allocate the array of DMA descriptors
|
||||
dma.desc = (lldesc_t**) malloc(sizeof(lldesc_t*) * DMA_BUF_COUNT);
|
||||
if (dma.desc == nullptr) return -1;
|
||||
|
||||
// Allocate each DMA descriptor that will be used by the DMA controller
|
||||
for (int buf_idx = 0; buf_idx < DMA_BUF_COUNT; buf_idx++) {
|
||||
dma.desc[buf_idx] = (lldesc_t*) heap_caps_malloc(sizeof(lldesc_t), MALLOC_CAP_DMA);
|
||||
if (dma.desc[buf_idx] == nullptr) return -1;
|
||||
}
|
||||
|
||||
// Initialize
|
||||
for (int buf_idx = 0; buf_idx < DMA_BUF_COUNT; buf_idx++) {
|
||||
dma.desc[buf_idx]->owner = 1;
|
||||
dma.desc[buf_idx]->eof = 1; // set to 1 will trigger the interrupt
|
||||
dma.desc[buf_idx]->sosf = 0;
|
||||
dma.desc[buf_idx]->length = DMA_BUF_LEN;
|
||||
dma.desc[buf_idx]->size = DMA_BUF_LEN;
|
||||
dma.desc[buf_idx]->buf = (uint8_t *) dma.buffers[buf_idx];
|
||||
dma.desc[buf_idx]->offset = 0;
|
||||
dma.desc[buf_idx]->empty = (uint32_t)((buf_idx < (DMA_BUF_COUNT - 1)) ? (dma.desc[buf_idx + 1]) : dma.desc[0]);
|
||||
}
|
||||
|
||||
dma.queue = xQueueCreate(DMA_BUF_COUNT, sizeof(uint32_t *));
|
||||
|
||||
// Set the first DMA descriptor
|
||||
I2S0.out_link.addr = (uint32_t)dma.desc[0];
|
||||
|
||||
// stop i2s
|
||||
i2s_stop(I2S_NUM_0);
|
||||
|
||||
// configure I2S data port interface.
|
||||
i2s_reset_fifo(I2S_NUM_0);
|
||||
|
||||
//reset i2s
|
||||
I2S0.conf.tx_reset = 1;
|
||||
I2S0.conf.tx_reset = 0;
|
||||
I2S0.conf.rx_reset = 1;
|
||||
I2S0.conf.rx_reset = 0;
|
||||
|
||||
//reset dma
|
||||
I2S0.lc_conf.in_rst = 1;
|
||||
I2S0.lc_conf.in_rst = 0;
|
||||
I2S0.lc_conf.out_rst = 1;
|
||||
I2S0.lc_conf.out_rst = 0;
|
||||
|
||||
//Enable and configure DMA
|
||||
I2S0.lc_conf.check_owner = 0;
|
||||
I2S0.lc_conf.out_loop_test = 0;
|
||||
I2S0.lc_conf.out_auto_wrback = 0;
|
||||
I2S0.lc_conf.out_data_burst_en = 0;
|
||||
I2S0.lc_conf.outdscr_burst_en = 0;
|
||||
I2S0.lc_conf.out_no_restart_clr = 0;
|
||||
I2S0.lc_conf.indscr_burst_en = 0;
|
||||
I2S0.lc_conf.out_eof_mode = 1;
|
||||
|
||||
I2S0.conf2.lcd_en = 0;
|
||||
I2S0.conf2.camera_en = 0;
|
||||
I2S0.pdm_conf.pcm2pdm_conv_en = 0;
|
||||
I2S0.pdm_conf.pdm2pcm_conv_en = 0;
|
||||
|
||||
I2S0.fifo_conf.dscr_en = 0;
|
||||
|
||||
I2S0.conf_chan.tx_chan_mod = (
|
||||
#if ENABLED(I2S_STEPPER_SPLIT_STREAM)
|
||||
4
|
||||
#else
|
||||
0
|
||||
#endif
|
||||
);
|
||||
I2S0.fifo_conf.tx_fifo_mod = 0;
|
||||
I2S0.conf.tx_mono = 0;
|
||||
|
||||
I2S0.conf_chan.rx_chan_mod = 0;
|
||||
I2S0.fifo_conf.rx_fifo_mod = 0;
|
||||
I2S0.conf.rx_mono = 0;
|
||||
|
||||
I2S0.fifo_conf.dscr_en = 1; //connect dma to fifo
|
||||
|
||||
I2S0.conf.tx_start = 0;
|
||||
I2S0.conf.rx_start = 0;
|
||||
|
||||
I2S0.conf.tx_msb_right = 1;
|
||||
I2S0.conf.tx_right_first = 1;
|
||||
|
||||
I2S0.conf.tx_slave_mod = 0; // Master
|
||||
I2S0.fifo_conf.tx_fifo_mod_force_en = 1;
|
||||
|
||||
I2S0.pdm_conf.rx_pdm_en = 0;
|
||||
I2S0.pdm_conf.tx_pdm_en = 0;
|
||||
|
||||
I2S0.conf.tx_short_sync = 0;
|
||||
I2S0.conf.rx_short_sync = 0;
|
||||
I2S0.conf.tx_msb_shift = 0;
|
||||
I2S0.conf.rx_msb_shift = 0;
|
||||
|
||||
// set clock
|
||||
I2S0.clkm_conf.clka_en = 0; // Use PLL/2 as reference
|
||||
I2S0.clkm_conf.clkm_div_num = 10; // minimum value of 2, reset value of 4, max 256
|
||||
I2S0.clkm_conf.clkm_div_a = 0; // 0 at reset, what about divide by 0? (not an issue)
|
||||
I2S0.clkm_conf.clkm_div_b = 0; // 0 at reset
|
||||
|
||||
// fbck = fi2s / tx_bck_div_num
|
||||
I2S0.sample_rate_conf.tx_bck_div_num = 2; // minimum value of 2 defaults to 6
|
||||
|
||||
// Enable TX interrupts
|
||||
I2S0.int_ena.out_eof = 1;
|
||||
I2S0.int_ena.out_dscr_err = 0;
|
||||
I2S0.int_ena.out_total_eof = 0;
|
||||
I2S0.int_ena.out_done = 0;
|
||||
|
||||
// Allocate and Enable the I2S interrupt
|
||||
intr_handle_t i2s_isr_handle;
|
||||
esp_intr_alloc(ETS_I2S0_INTR_SOURCE, 0, i2s_intr_handler_default, nullptr, &i2s_isr_handle);
|
||||
esp_intr_enable(i2s_isr_handle);
|
||||
|
||||
// Create the task that will feed the buffer
|
||||
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);
|
||||
|
||||
// Start the I2S peripheral
|
||||
return i2s_start(I2S_NUM_0);
|
||||
}
|
||||
|
||||
void i2s_write(uint8_t pin, uint8_t val) {
|
||||
#if ENABLED(I2S_STEPPER_SPLIT_STREAM)
|
||||
if (pin >= 16) {
|
||||
SET_BIT_TO(I2S0.conf_single_data, pin, val);
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
SET_BIT_TO(i2s_port_data, pin, val);
|
||||
}
|
||||
|
||||
uint8_t i2s_state(uint8_t pin) {
|
||||
#if ENABLED(I2S_STEPPER_SPLIT_STREAM)
|
||||
if (pin >= 16) return TEST(I2S0.conf_single_data, pin);
|
||||
#endif
|
||||
return TEST(i2s_port_data, pin);
|
||||
}
|
||||
|
||||
void i2s_push_sample() {
|
||||
dma.current[dma.rw_pos++] = i2s_port_data;
|
||||
}
|
||||
|
||||
#endif // ARDUINO_ARCH_ESP32
|
35
Marlin/src/HAL/ESP32/i2s.h
Normal file
35
Marlin/src/HAL/ESP32/i2s.h
Normal file
@ -0,0 +1,35 @@
|
||||
/**
|
||||
* 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 <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
// current value of the outputs provided over i2s
|
||||
extern uint32_t i2s_port_data;
|
||||
|
||||
int i2s_init();
|
||||
|
||||
uint8_t i2s_state(uint8_t pin);
|
||||
|
||||
void i2s_write(uint8_t pin, uint8_t val);
|
||||
|
||||
void i2s_push_sample();
|
22
Marlin/src/HAL/ESP32/inc/Conditionals_LCD.h
Normal file
22
Marlin/src/HAL/ESP32/inc/Conditionals_LCD.h
Normal file
@ -0,0 +1,22 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
22
Marlin/src/HAL/ESP32/inc/Conditionals_adv.h
Normal file
22
Marlin/src/HAL/ESP32/inc/Conditionals_adv.h
Normal file
@ -0,0 +1,22 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
22
Marlin/src/HAL/ESP32/inc/Conditionals_post.h
Normal file
22
Marlin/src/HAL/ESP32/inc/Conditionals_post.h
Normal file
@ -0,0 +1,22 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
38
Marlin/src/HAL/ESP32/inc/SanityCheck.h
Normal file
38
Marlin/src/HAL/ESP32/inc/SanityCheck.h
Normal file
@ -0,0 +1,38 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#if ENABLED(EMERGENCY_PARSER)
|
||||
#error "EMERGENCY_PARSER is not yet implemented for ESP32. Disable EMERGENCY_PARSER to continue."
|
||||
#endif
|
||||
|
||||
#if ENABLED(FAST_PWM_FAN)
|
||||
#error "FAST_PWM_FAN is not yet implemented for this platform."
|
||||
#endif
|
||||
|
||||
#if HAS_TMC_SW_SERIAL
|
||||
#error "TMC220x Software Serial is not supported on this platform."
|
||||
#endif
|
||||
|
||||
#if BOTH(WIFISUPPORT, ESP3D_WIFISUPPORT)
|
||||
#error "Only enable one WiFi option, either WIFISUPPORT or ESP3D_WIFISUPPORT."
|
||||
#endif
|
71
Marlin/src/HAL/ESP32/ota.cpp
Normal file
71
Marlin/src/HAL/ESP32/ota.cpp
Normal file
@ -0,0 +1,71 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#ifdef ARDUINO_ARCH_ESP32
|
||||
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if BOTH(WIFISUPPORT, OTASUPPORT)
|
||||
|
||||
#include <WiFi.h>
|
||||
#include <ESPmDNS.h>
|
||||
#include <WiFiUdp.h>
|
||||
#include <ArduinoOTA.h>
|
||||
#include <driver/timer.h>
|
||||
|
||||
void OTA_init() {
|
||||
ArduinoOTA
|
||||
.onStart([]() {
|
||||
timer_pause(TIMER_GROUP_0, TIMER_0);
|
||||
timer_pause(TIMER_GROUP_0, TIMER_1);
|
||||
|
||||
// U_FLASH or U_SPIFFS
|
||||
String type = (ArduinoOTA.getCommand() == U_FLASH) ? "sketch" : "filesystem";
|
||||
|
||||
// NOTE: if updating SPIFFS this would be the place to unmount SPIFFS using SPIFFS.end()
|
||||
Serial.println("Start updating " + type);
|
||||
})
|
||||
.onEnd([]() {
|
||||
Serial.println("\nEnd");
|
||||
})
|
||||
.onProgress([](unsigned int progress, unsigned int total) {
|
||||
Serial.printf("Progress: %u%%\r", (progress / (total / 100)));
|
||||
})
|
||||
.onError([](ota_error_t error) {
|
||||
Serial.printf("Error[%u]: ", error);
|
||||
char *str;
|
||||
switch (error) {
|
||||
case OTA_AUTH_ERROR: str = "Auth Failed"; break;
|
||||
case OTA_BEGIN_ERROR: str = "Begin Failed"; break;
|
||||
case OTA_CONNECT_ERROR: str = "Connect Failed"; break;
|
||||
case OTA_RECEIVE_ERROR: str = "Receive Failed"; break;
|
||||
case OTA_END_ERROR: str = "End Failed"; break;
|
||||
}
|
||||
Serial.println(str);
|
||||
});
|
||||
|
||||
ArduinoOTA.begin();
|
||||
}
|
||||
|
||||
void OTA_handle() {
|
||||
ArduinoOTA.handle();
|
||||
}
|
||||
|
||||
#endif // WIFISUPPORT && OTASUPPORT
|
||||
#endif // ARDUINO_ARCH_ESP32
|
22
Marlin/src/HAL/ESP32/ota.h
Normal file
22
Marlin/src/HAL/ESP32/ota.h
Normal file
@ -0,0 +1,22 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
void OTA_init();
|
||||
void OTA_handle();
|
63
Marlin/src/HAL/ESP32/persistent_store_impl.cpp
Normal file
63
Marlin/src/HAL/ESP32/persistent_store_impl.cpp
Normal file
@ -0,0 +1,63 @@
|
||||
/**
|
||||
* 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 <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifdef ARDUINO_ARCH_ESP32
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#if ENABLED(EEPROM_SETTINGS) && DISABLED(FLASH_EEPROM_EMULATION)
|
||||
|
||||
#include "../shared/persistent_store_api.h"
|
||||
#include "EEPROM.h"
|
||||
|
||||
#define EEPROM_SIZE 4096
|
||||
|
||||
bool PersistentStore::access_start() {
|
||||
return EEPROM.begin(EEPROM_SIZE);
|
||||
}
|
||||
|
||||
bool PersistentStore::access_finish() {
|
||||
EEPROM.end();
|
||||
return true;
|
||||
}
|
||||
|
||||
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
|
||||
for (size_t i = 0; i < size; i++) {
|
||||
EEPROM.write(pos++, value[i]);
|
||||
crc16(crc, &value[i], 1);
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
|
||||
for (size_t i = 0; i < size; i++) {
|
||||
uint8_t c = EEPROM.read(pos++);
|
||||
if (writing) value[i] = c;
|
||||
crc16(crc, &c, 1);
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
size_t PersistentStore::capacity() { return EEPROM_SIZE; }
|
||||
|
||||
#endif // EEPROM_SETTINGS
|
||||
#endif // ARDUINO_ARCH_ESP32
|
22
Marlin/src/HAL/ESP32/servotimers.h
Normal file
22
Marlin/src/HAL/ESP32/servotimers.h
Normal file
@ -0,0 +1,22 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
24
Marlin/src/HAL/ESP32/spi_pins.h
Normal file
24
Marlin/src/HAL/ESP32/spi_pins.h
Normal file
@ -0,0 +1,24 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#define SS_PIN SDSS
|
||||
#define SCK_PIN 18
|
||||
#define MISO_PIN 19
|
||||
#define MOSI_PIN 23
|
44
Marlin/src/HAL/ESP32/spiffs.cpp
Normal file
44
Marlin/src/HAL/ESP32/spiffs.cpp
Normal file
@ -0,0 +1,44 @@
|
||||
/**
|
||||
* 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 <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifdef ARDUINO_ARCH_ESP32
|
||||
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if BOTH(WIFISUPPORT, WEBSUPPORT)
|
||||
|
||||
#include "../../core/serial.h"
|
||||
|
||||
#include <FS.h>
|
||||
#include <SPIFFS.h>
|
||||
|
||||
bool spiffs_initialized;
|
||||
|
||||
void spiffs_init() {
|
||||
if (SPIFFS.begin(true)) // formatOnFail = true
|
||||
spiffs_initialized = true;
|
||||
else
|
||||
SERIAL_ERROR_MSG("SPIFFS mount failed");
|
||||
}
|
||||
|
||||
#endif // WIFISUPPORT && WEBSUPPORT
|
||||
#endif // ARDUINO_ARCH_ESP32
|
26
Marlin/src/HAL/ESP32/spiffs.h
Normal file
26
Marlin/src/HAL/ESP32/spiffs.h
Normal file
@ -0,0 +1,26 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
extern bool spiffs_initialized;
|
||||
|
||||
void spiffs_init();
|
174
Marlin/src/HAL/ESP32/timers.cpp
Normal file
174
Marlin/src/HAL/ESP32/timers.cpp
Normal file
@ -0,0 +1,174 @@
|
||||
/**
|
||||
* 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 <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifdef ARDUINO_ARCH_ESP32
|
||||
|
||||
#include <stdio.h>
|
||||
#include <esp_types.h>
|
||||
#include <soc/timer_group_struct.h>
|
||||
#include <driver/periph_ctrl.h>
|
||||
#include <driver/timer.h>
|
||||
|
||||
#include "HAL.h"
|
||||
|
||||
#include "timers.h"
|
||||
|
||||
// ------------------------
|
||||
// Local defines
|
||||
// ------------------------
|
||||
|
||||
#define NUM_HARDWARE_TIMERS 4
|
||||
|
||||
// ------------------------
|
||||
// Private Variables
|
||||
// ------------------------
|
||||
|
||||
static timg_dev_t *TG[2] = {&TIMERG0, &TIMERG1};
|
||||
|
||||
const tTimerConfig TimerConfig [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
|
||||
{ TIMER_GROUP_1, TIMER_1, 1, nullptr }, // 3
|
||||
};
|
||||
|
||||
// ------------------------
|
||||
// Public functions
|
||||
// ------------------------
|
||||
|
||||
void IRAM_ATTR timer_isr(void *para) {
|
||||
const tTimerConfig& timer = TimerConfig[(int)para];
|
||||
|
||||
// Retrieve the interrupt status and the counter value
|
||||
// from the timer that reported the interrupt
|
||||
uint32_t intr_status = TG[timer.group]->int_st_timers.val;
|
||||
TG[timer.group]->hw_timer[timer.idx].update = 1;
|
||||
|
||||
// Clear the interrupt
|
||||
if (intr_status & BIT(timer.idx)) {
|
||||
switch (timer.idx) {
|
||||
case TIMER_0: TG[timer.group]->int_clr_timers.t0 = 1; break;
|
||||
case TIMER_1: TG[timer.group]->int_clr_timers.t1 = 1; break;
|
||||
case TIMER_MAX: break;
|
||||
}
|
||||
}
|
||||
|
||||
timer.fn();
|
||||
|
||||
// After the alarm has been triggered
|
||||
// Enable it again so it gets triggered the next time
|
||||
TG[timer.group]->hw_timer[timer.idx].config.alarm_en = TIMER_ALARM_EN;
|
||||
}
|
||||
|
||||
/**
|
||||
* Enable and initialize the timer
|
||||
* @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];
|
||||
|
||||
timer_config_t config;
|
||||
config.divider = timer.divider;
|
||||
config.counter_dir = TIMER_COUNT_UP;
|
||||
config.counter_en = TIMER_PAUSE;
|
||||
config.alarm_en = TIMER_ALARM_EN;
|
||||
config.intr_type = TIMER_INTR_LEVEL;
|
||||
config.auto_reload = true;
|
||||
|
||||
// Select and initialize the timer
|
||||
timer_init(timer.group, timer.idx, &config);
|
||||
|
||||
// Timer counter initial value and auto reload on alarm
|
||||
timer_set_counter_value(timer.group, timer.idx, 0x00000000ULL);
|
||||
|
||||
// Configure the alam value and the interrupt on alarm
|
||||
timer_set_alarm_value(timer.group, timer.idx, (HAL_TIMER_RATE) / timer.divider / frequency - 1);
|
||||
|
||||
timer_enable_intr(timer.group, timer.idx);
|
||||
|
||||
timer_isr_register(timer.group, timer.idx, timer_isr, (void*)(uint32_t)timer_num, 0, nullptr);
|
||||
|
||||
timer_start(timer.group, timer.idx);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the upper value of the timer, when the timer reaches this upper value the
|
||||
* interrupt should be triggered and the counter reset
|
||||
* @param timer_num timer number to set the count to
|
||||
* @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];
|
||||
timer_set_alarm_value(timer.group, timer.idx, count);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the current upper value of the timer
|
||||
* @param timer_num timer number to get the count from
|
||||
* @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];
|
||||
|
||||
uint64_t alarm_value;
|
||||
timer_get_alarm_value(timer.group, timer.idx, &alarm_value);
|
||||
|
||||
return alarm_value;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the current counter value between 0 and the maximum count (HAL_timer_set_count)
|
||||
* @param timer_num timer number to get the current count
|
||||
* @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];
|
||||
uint64_t counter_value;
|
||||
timer_get_counter_value(timer.group, timer.idx, &counter_value);
|
||||
return counter_value;
|
||||
}
|
||||
|
||||
/**
|
||||
* Enable timer interrupt on the timer
|
||||
* @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];
|
||||
//timer_enable_intr(timer.group, timer.idx);
|
||||
}
|
||||
|
||||
/**
|
||||
* Disable timer interrupt on the timer
|
||||
* @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];
|
||||
//timer_disable_intr(timer.group, timer.idx);
|
||||
}
|
||||
|
||||
bool HAL_timer_interrupt_enabled(const uint8_t timer_num) {
|
||||
const tTimerConfig timer = TimerConfig[timer_num];
|
||||
return TG[timer.group]->int_ena.val | BIT(timer_num);
|
||||
}
|
||||
|
||||
#endif // ARDUINO_ARCH_ESP32
|
121
Marlin/src/HAL/ESP32/timers.h
Normal file
121
Marlin/src/HAL/ESP32/timers.h
Normal file
@ -0,0 +1,121 @@
|
||||
/**
|
||||
* 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 <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include <stdint.h>
|
||||
#include <driver/timer.h>
|
||||
|
||||
// Includes needed to get I2S_STEPPER_STREAM. Note that pins.h
|
||||
// is included in case this header is being included early.
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
#include "../../pins/pins.h"
|
||||
|
||||
// ------------------------
|
||||
// Defines
|
||||
// ------------------------
|
||||
//
|
||||
#define FORCE_INLINE __attribute__((always_inline)) inline
|
||||
|
||||
typedef uint64_t hal_timer_t;
|
||||
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFFFFFFFFFFULL
|
||||
|
||||
#define STEP_TIMER_NUM 0 // index of timer to use for stepper
|
||||
#define TEMP_TIMER_NUM 1 // index of timer to use for temperature
|
||||
#define PWM_TIMER_NUM 2 // index of timer to use for PWM outputs
|
||||
#define PULSE_TIMER_NUM STEP_TIMER_NUM
|
||||
|
||||
#define HAL_TIMER_RATE APB_CLK_FREQ // frequency of timer peripherals
|
||||
|
||||
#if ENABLED(I2S_STEPPER_STREAM)
|
||||
#define STEPPER_TIMER_PRESCALE 1
|
||||
#define STEPPER_TIMER_RATE 250000 // 250khz, 4µs pulses of i2s word clock
|
||||
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs // wrong would be 0.25
|
||||
#else
|
||||
#define STEPPER_TIMER_PRESCALE 40
|
||||
#define STEPPER_TIMER_RATE ((HAL_TIMER_RATE) / (STEPPER_TIMER_PRESCALE)) // frequency of stepper timer, 2MHz
|
||||
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs
|
||||
#endif
|
||||
|
||||
#define STEP_TIMER_MIN_INTERVAL 8 // minimum time in µs between stepper interrupts
|
||||
|
||||
#define TEMP_TIMER_PRESCALE 1000 // prescaler for setting Temp timer, 72Khz
|
||||
#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency
|
||||
|
||||
#define PWM_TIMER_PRESCALE 10
|
||||
#if ENABLED(FAST_PWM_FAN)
|
||||
#define PWM_TIMER_FREQUENCY FAST_PWM_FAN_FREQUENCY
|
||||
#else
|
||||
#define PWM_TIMER_FREQUENCY (50*128) // 50Hz and 7bit resolution
|
||||
#endif
|
||||
#define MAX_PWM_PINS 32 // Number of PWM pin-slots
|
||||
|
||||
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer
|
||||
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
|
||||
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
|
||||
|
||||
#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(STEP_TIMER_NUM)
|
||||
#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(STEP_TIMER_NUM)
|
||||
#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM)
|
||||
|
||||
#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM)
|
||||
#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM)
|
||||
|
||||
#define HAL_TEMP_TIMER_ISR() extern "C" void tempTC_Handler()
|
||||
#define HAL_STEP_TIMER_ISR() extern "C" void stepTC_Handler()
|
||||
#define HAL_PWM_TIMER_ISR() extern "C" void pwmTC_Handler()
|
||||
|
||||
extern "C" void tempTC_Handler();
|
||||
extern "C" void stepTC_Handler();
|
||||
extern "C" void pwmTC_Handler();
|
||||
|
||||
// ------------------------
|
||||
// Types
|
||||
// ------------------------
|
||||
|
||||
typedef struct {
|
||||
timer_group_t group;
|
||||
timer_idx_t idx;
|
||||
uint32_t divider;
|
||||
void (*fn)();
|
||||
} tTimerConfig;
|
||||
|
||||
// ------------------------
|
||||
// Public Variables
|
||||
// ------------------------
|
||||
|
||||
extern const tTimerConfig TimerConfig[];
|
||||
|
||||
// ------------------------
|
||||
// Public functions
|
||||
// ------------------------
|
||||
|
||||
void HAL_timer_start (const uint8_t timer_num, 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);
|
||||
|
||||
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)
|
41
Marlin/src/HAL/ESP32/watchdog.cpp
Normal file
41
Marlin/src/HAL/ESP32/watchdog.cpp
Normal file
@ -0,0 +1,41 @@
|
||||
/**
|
||||
* 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 <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifdef ARDUINO_ARCH_ESP32
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#if ENABLED(USE_WATCHDOG)
|
||||
|
||||
#include "watchdog.h"
|
||||
|
||||
void watchdogSetup() {
|
||||
// do whatever. don't remove this function.
|
||||
}
|
||||
|
||||
void watchdog_init() {
|
||||
// TODO
|
||||
}
|
||||
|
||||
#endif // USE_WATCHDOG
|
||||
|
||||
#endif // ARDUINO_ARCH_ESP32
|
38
Marlin/src/HAL/ESP32/watchdog.h
Normal file
38
Marlin/src/HAL/ESP32/watchdog.h
Normal file
@ -0,0 +1,38 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://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(); }
|
48
Marlin/src/HAL/ESP32/web.cpp
Normal file
48
Marlin/src/HAL/ESP32/web.cpp
Normal file
@ -0,0 +1,48 @@
|
||||
/**
|
||||
* 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 <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifdef ARDUINO_ARCH_ESP32
|
||||
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if BOTH(WIFISUPPORT, WEBSUPPORT)
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#undef DISABLED // esp32-hal-gpio.h
|
||||
#include <SPIFFS.h>
|
||||
#include "wifi.h"
|
||||
|
||||
AsyncEventSource events("/events"); // event source (Server-Sent events)
|
||||
|
||||
void onNotFound(AsyncWebServerRequest *request) {
|
||||
request->send(404);
|
||||
}
|
||||
|
||||
void web_init() {
|
||||
server.addHandler(&events); // attach AsyncEventSource
|
||||
server.serveStatic("/", SPIFFS, "/www").setDefaultFile("index.html");
|
||||
server.onNotFound(onNotFound);
|
||||
}
|
||||
|
||||
#endif // WIFISUPPORT && WEBSUPPORT
|
||||
#endif // ARDUINO_ARCH_ESP32
|
24
Marlin/src/HAL/ESP32/web.h
Normal file
24
Marlin/src/HAL/ESP32/web.h
Normal file
@ -0,0 +1,24 @@
|
||||
/**
|
||||
* 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 <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
void web_init();
|
67
Marlin/src/HAL/ESP32/wifi.cpp
Normal file
67
Marlin/src/HAL/ESP32/wifi.cpp
Normal file
@ -0,0 +1,67 @@
|
||||
/**
|
||||
* 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 <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifdef ARDUINO_ARCH_ESP32
|
||||
|
||||
#include "../../core/serial.h"
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if ENABLED(WIFISUPPORT)
|
||||
|
||||
#include <WiFi.h>
|
||||
#include <ESPmDNS.h>
|
||||
#include <ESPAsyncWebServer.h>
|
||||
#include "wifi.h"
|
||||
|
||||
AsyncWebServer server(80);
|
||||
|
||||
#ifndef WIFI_HOSTNAME
|
||||
#define WIFI_HOSTNAME DEFAULT_WIFI_HOSTNAME
|
||||
#endif
|
||||
|
||||
void wifi_init() {
|
||||
|
||||
SERIAL_ECHO_MSG("Starting WiFi...");
|
||||
|
||||
WiFi.mode(WIFI_STA);
|
||||
WiFi.begin(WIFI_SSID, WIFI_PWD);
|
||||
|
||||
while (WiFi.waitForConnectResult() != WL_CONNECTED) {
|
||||
SERIAL_ERROR_MSG("Unable to connect to WiFi with SSID '" WIFI_SSID "', restarting.");
|
||||
delay(5000);
|
||||
ESP.restart();
|
||||
}
|
||||
|
||||
delay(10);
|
||||
if (!MDNS.begin(WIFI_HOSTNAME)) {
|
||||
SERIAL_ERROR_MSG("Unable to start mDNS with hostname '" WIFI_HOSTNAME "', restarting.");
|
||||
delay(5000);
|
||||
ESP.restart();
|
||||
}
|
||||
|
||||
MDNS.addService("http", "tcp", 80);
|
||||
|
||||
SERIAL_ECHOLNPAIR("Successfully connected to WiFi with SSID '" WIFI_SSID "', hostname: '" WIFI_HOSTNAME "', IP address: ", WiFi.localIP().toString().c_str());
|
||||
}
|
||||
|
||||
#endif // WIFISUPPORT
|
||||
#endif // ARDUINO_ARCH_ESP32
|
30
Marlin/src/HAL/ESP32/wifi.h
Normal file
30
Marlin/src/HAL/ESP32/wifi.h
Normal file
@ -0,0 +1,30 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include <ESPAsyncWebServer.h>
|
||||
|
||||
extern AsyncWebServer server;
|
||||
|
||||
#define DEFAULT_WIFI_HOSTNAME "marlin"
|
||||
|
||||
void wifi_init();
|
Reference in New Issue
Block a user