HAL for Espressif ESP32 Wifi
This commit is contained in:
parent
091f742432
commit
e2aeda61ed
|
@ -1700,4 +1700,13 @@
|
|||
// Default behaviour is limited to Z axis only.
|
||||
#endif
|
||||
|
||||
/**
|
||||
* WiFi Support (Espressif ESP32 WiFi)
|
||||
*/
|
||||
//#define WIFISUPPORT
|
||||
#if ENABLED(WIFISUPPORT)
|
||||
#define WIFI_SSID "Wifi SSID"
|
||||
#define WIFI_PWD "Wifi Password"
|
||||
#endif
|
||||
|
||||
#endif // CONFIGURATION_ADV_H
|
||||
|
|
|
@ -21,14 +21,12 @@
|
|||
*/
|
||||
|
||||
/**
|
||||
|
||||
Busy wait delay Cycles routines:
|
||||
|
||||
DELAY_CYCLES(count): Delay execution in cycles
|
||||
DELAY_NS(count): Delay execution in nanoseconds
|
||||
DELAY_US(count): Delay execution in microseconds
|
||||
|
||||
*/
|
||||
* Busy wait delay cycles routines:
|
||||
*
|
||||
* DELAY_CYCLES(count): Delay execution in cycles
|
||||
* DELAY_NS(count): Delay execution in nanoseconds
|
||||
* DELAY_US(count): Delay execution in microseconds
|
||||
*/
|
||||
|
||||
#ifndef MARLIN_DELAY_H
|
||||
#define MARLIN_DELAY_H
|
||||
|
@ -37,7 +35,7 @@
|
|||
|
||||
#if defined(__arm__) || defined(__thumb__)
|
||||
|
||||
/* https://blueprints.launchpad.net/gcc-arm-embedded/+spec/delay-cycles */
|
||||
// https://blueprints.launchpad.net/gcc-arm-embedded/+spec/delay-cycles
|
||||
|
||||
#define nop() __asm__ __volatile__("nop;\n\t":::)
|
||||
|
||||
|
@ -60,7 +58,7 @@
|
|||
);
|
||||
}
|
||||
|
||||
/* ---------------- Delay in cycles */
|
||||
// Delay in cycles
|
||||
FORCE_INLINE static void DELAY_CYCLES(uint32_t x) {
|
||||
|
||||
if (__builtin_constant_p(x)) {
|
||||
|
@ -98,7 +96,7 @@
|
|||
);
|
||||
}
|
||||
|
||||
/* ---------------- Delay in cycles */
|
||||
// Delay in cycles
|
||||
FORCE_INLINE static void DELAY_CYCLES(uint16_t x) {
|
||||
|
||||
if (__builtin_constant_p(x)) {
|
||||
|
@ -121,15 +119,30 @@
|
|||
}
|
||||
#undef nop
|
||||
|
||||
#elif defined(ESP32)
|
||||
|
||||
FORCE_INLINE static void DELAY_CYCLES(uint32_t x) {
|
||||
unsigned long ccount, stop;
|
||||
|
||||
__asm__ __volatile__ ( "rsr %0, ccount" : "=a" (ccount) );
|
||||
|
||||
stop = ccount + x; // This can overflow
|
||||
|
||||
while (ccount < stop) { // This doesn't deal with overflows
|
||||
__asm__ __volatile__ ( "rsr %0, ccount" : "=a" (ccount) );
|
||||
}
|
||||
}
|
||||
|
||||
#else
|
||||
|
||||
#error "Unsupported MCU architecture"
|
||||
|
||||
#endif
|
||||
|
||||
/* ---------------- Delay in nanoseconds */
|
||||
// Delay in nanoseconds
|
||||
#define DELAY_NS(x) DELAY_CYCLES( (x) * (F_CPU/1000000L) / 1000L )
|
||||
|
||||
/* ---------------- Delay in microseconds */
|
||||
// Delay in microseconds
|
||||
#define DELAY_US(x) DELAY_CYCLES( (x) * (F_CPU/1000000L) )
|
||||
|
||||
#endif // MARLIN_DELAY_H
|
||||
|
||||
|
|
155
Marlin/src/HAL/HAL_ESP32/HAL.cpp
Normal file
155
Marlin/src/HAL/HAL_ESP32/HAL.cpp
Normal file
|
@ -0,0 +1,155 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 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
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Includes
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
#include "HAL.h"
|
||||
#include <rom/rtc.h>
|
||||
#include <driver/adc.h>
|
||||
#include <esp_adc_cal.h>
|
||||
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if ENABLED(WIFISUPPORT)
|
||||
#include "ota.h"
|
||||
#endif
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Externals
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
portMUX_TYPE spinlock = portMUX_INITIALIZER_UNLOCKED;
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Local defines
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
#define V_REF 1100
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Types
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Variables
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Public Variables
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
uint16_t HAL_adc_result;
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Private Variables
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
esp_adc_cal_characteristics_t characteristics;
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Function prototypes
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Private functions
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Public functions
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
void HAL_init(void) {
|
||||
#if ENABLED(WIFISUPPORT)
|
||||
OTA_init();
|
||||
#endif
|
||||
}
|
||||
|
||||
void HAL_idletask(void) {
|
||||
#if ENABLED(WIFISUPPORT)
|
||||
OTA_handle();
|
||||
#endif
|
||||
}
|
||||
|
||||
void HAL_clear_reset_source(void) { }
|
||||
|
||||
uint8_t HAL_get_reset_source (void) {
|
||||
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 36: return ADC1_GPIO36_CHANNEL;
|
||||
case 39: return ADC1_GPIO39_CHANNEL;
|
||||
}
|
||||
|
||||
return ADC1_CHANNEL_MAX;
|
||||
}
|
||||
|
||||
void HAL_adc_init() {
|
||||
// Configure ADC
|
||||
adc1_config_width(ADC_WIDTH_12Bit);
|
||||
adc1_config_channel_atten(get_channel(36), ADC_ATTEN_11db);
|
||||
adc1_config_channel_atten(get_channel(39), ADC_ATTEN_11db);
|
||||
|
||||
// Calculate ADC characteristics i.e. gain and offset factors
|
||||
esp_adc_cal_characterize(ADC_UNIT_1, ADC_ATTEN_DB_11, ADC_WIDTH_BIT_12, V_REF, &characteristics);
|
||||
}
|
||||
|
||||
void HAL_adc_start_conversion (uint8_t adc_pin) {
|
||||
uint32_t mv;
|
||||
esp_adc_cal_get_voltage((adc_channel_t)get_channel(adc_pin), &characteristics, &mv);
|
||||
|
||||
HAL_adc_result = mv*1023.0/3300.0;
|
||||
}
|
||||
|
||||
int pin_to_channel[40] = {};
|
||||
int cnt_channel = 1;
|
||||
void analogWrite(int pin, int value) {
|
||||
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);
|
||||
}
|
||||
#endif // ARDUINO_ARCH_ESP32
|
126
Marlin/src/HAL/HAL_ESP32/HAL.h
Normal file
126
Marlin/src/HAL/HAL_ESP32/HAL.h
Normal file
|
@ -0,0 +1,126 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 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/>.
|
||||
*/
|
||||
|
||||
/**
|
||||
* Description: HAL for Espressif ESP32 WiFi
|
||||
*/
|
||||
|
||||
#ifndef _HAL_ESP32_H
|
||||
#define _HAL_ESP32_H
|
||||
|
||||
#define CPU_32_BIT
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Includes
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#undef DISABLED
|
||||
#undef _BV
|
||||
|
||||
#include <Arduino.h>
|
||||
|
||||
#undef DISABLED
|
||||
#define DISABLED(b) (!_CAT(SWITCH_ENABLED_, b))
|
||||
|
||||
#include "../math_32bit.h"
|
||||
#include "../HAL_SPI.h"
|
||||
|
||||
#include "fastio_ESP32.h"
|
||||
#include "watchdog_ESP32.h"
|
||||
|
||||
#include "HAL_timers_ESP32.h"
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Defines
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
extern portMUX_TYPE spinlock;
|
||||
|
||||
#define NUM_SERIAL 1
|
||||
#define MYSERIAL0 Serial
|
||||
|
||||
#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;
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Public Variables
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
/** result of last ADC conversion */
|
||||
extern uint16_t HAL_adc_result;
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Public functions
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
// clear reset reason
|
||||
void HAL_clear_reset_source (void);
|
||||
|
||||
// reset reason
|
||||
uint8_t HAL_get_reset_source (void);
|
||||
|
||||
void _delay_ms(int delay);
|
||||
|
||||
int freeMemory(void);
|
||||
|
||||
void analogWrite(int pin, int value);
|
||||
|
||||
// EEPROM
|
||||
void eeprom_write_byte(unsigned char *pos, unsigned char value);
|
||||
unsigned char eeprom_read_byte(unsigned char *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(void);
|
||||
|
||||
#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin)
|
||||
#define HAL_READ_ADC HAL_adc_result
|
||||
|
||||
void HAL_adc_start_conversion (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 HAL_INIT 1
|
||||
void HAL_idletask(void);
|
||||
void HAL_init(void);
|
||||
|
||||
#endif // _HAL_ESP32_H
|
109
Marlin/src/HAL/HAL_ESP32/HAL_spi_ESP32.cpp
Normal file
109
Marlin/src/HAL/HAL_ESP32/HAL_spi_ESP32.cpp
Normal file
|
@ -0,0 +1,109 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 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
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Includes
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
#include "HAL.h"
|
||||
#include "../HAL_SPI.h"
|
||||
#include "pins_arduino.h"
|
||||
#include "spi_pins.h"
|
||||
#include "../../core/macros.h"
|
||||
#include <SPI.h>
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Public Variables
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
static SPISettings spiConfig;
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Public functions
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Hardware SPI
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
void spiBegin() {
|
||||
#if !PIN_EXISTS(SS)
|
||||
#error "SS_PIN not defined!"
|
||||
#endif
|
||||
|
||||
WRITE(SS_PIN, HIGH);
|
||||
SET_OUTPUT(SS_PIN);
|
||||
}
|
||||
|
||||
void spiInit(uint8_t spiRate) {
|
||||
uint32_t clock;
|
||||
|
||||
switch (spiRate) {
|
||||
case SPI_FULL_SPEED: clock = SPI_CLOCK_DIV2 ; break;
|
||||
case SPI_HALF_SPEED: clock = SPI_CLOCK_DIV4 ; break;
|
||||
case SPI_QUARTER_SPEED: clock = SPI_CLOCK_DIV8 ; break;
|
||||
case SPI_EIGHTH_SPEED: clock = SPI_CLOCK_DIV16; break;
|
||||
case SPI_SPEED_5: clock = SPI_CLOCK_DIV32; break;
|
||||
case SPI_SPEED_6: clock = SPI_CLOCK_DIV64; break;
|
||||
default: clock = SPI_CLOCK_DIV2; // Default from the SPI library
|
||||
}
|
||||
|
||||
spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0);
|
||||
SPI.begin();
|
||||
}
|
||||
|
||||
uint8_t spiRec(void) {
|
||||
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 // ARDUINO_ARCH_ESP32
|
202
Marlin/src/HAL/HAL_ESP32/HAL_timers_ESP32.cpp
Normal file
202
Marlin/src/HAL/HAL_ESP32/HAL_timers_ESP32.cpp
Normal file
|
@ -0,0 +1,202 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 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
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Includes
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
#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 "HAL_timers_ESP32.h"
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Externals
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Local defines
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
#define NUM_HARDWARE_TIMERS 4
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Types
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Public Variables
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// 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, 1, NULL }, // 2
|
||||
{ TIMER_GROUP_1, TIMER_1, 1, NULL }, // 3
|
||||
};
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Function prototypes
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Private functions
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Public functions
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
void IRAM_ATTR timer_group0_isr(void *para) {
|
||||
const int timer_idx = (int)para;
|
||||
|
||||
// Retrieve the interrupt status and the counter value
|
||||
// from the timer that reported the interrupt
|
||||
uint32_t intr_status = TIMERG0.int_st_timers.val;
|
||||
TIMERG0.hw_timer[timer_idx].update = 1;
|
||||
|
||||
// Clear the interrupt
|
||||
if (intr_status & BIT(timer_idx)) {
|
||||
switch (timer_idx) {
|
||||
case TIMER_0: TIMERG0.int_clr_timers.t0 = 1; break;
|
||||
case TIMER_1: TIMERG0.int_clr_timers.t1 = 1; break;
|
||||
}
|
||||
}
|
||||
|
||||
const tTimerConfig timer = TimerConfig[timer_idx];
|
||||
timer.fn();
|
||||
|
||||
// After the alarm has been triggered
|
||||
// Enable it again so it gets triggered the next time
|
||||
TIMERG0.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 = STEPPER_TIMER_PRESCALE;
|
||||
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);
|
||||
|
||||
// TODO need to deal with timer_group1_isr
|
||||
timer_isr_register(timer.group, timer.idx, timer_group0_isr, (void*)timer.idx, NULL, NULL);
|
||||
|
||||
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
|
114
Marlin/src/HAL/HAL_ESP32/HAL_timers_ESP32.h
Normal file
114
Marlin/src/HAL/HAL_ESP32/HAL_timers_ESP32.h
Normal file
|
@ -0,0 +1,114 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 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/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef _HAL_TIMERS_ESP32_H
|
||||
#define _HAL_TIMERS_ESP32_H
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Includes
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
#include <stdint.h>
|
||||
#include "driver/timer.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 PULSE_TIMER_NUM STEP_TIMER_NUM
|
||||
|
||||
#define HAL_TIMER_RATE APB_CLK_FREQ // frequency of timer peripherals
|
||||
|
||||
#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
|
||||
|
||||
#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 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(void)
|
||||
#define HAL_STEP_TIMER_ISR extern "C" void stepTC_Handler(void)
|
||||
|
||||
extern "C" void tempTC_Handler(void);
|
||||
extern "C" void stepTC_Handler(void);
|
||||
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Types
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
typedef struct {
|
||||
timer_group_t group;
|
||||
timer_idx_t idx;
|
||||
uint32_t divider;
|
||||
void (*fn)(void);
|
||||
} 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);
|
||||
|
||||
// if counter too high then bump up compare
|
||||
FORCE_INLINE static void HAL_timer_restrain(const uint8_t timer_num, const uint16_t interval_ticks) {
|
||||
const hal_timer_t mincmp = HAL_timer_get_count(timer_num) + interval_ticks;
|
||||
if (HAL_timer_get_compare(timer_num) < mincmp) HAL_timer_set_compare(timer_num, mincmp);
|
||||
}
|
||||
|
||||
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)
|
||||
|
||||
#endif // _HAL_TIMERS_ESP32_H
|
25
Marlin/src/HAL/HAL_ESP32/SanityCheck.h
Normal file
25
Marlin/src/HAL/HAL_ESP32/SanityCheck.h
Normal file
|
@ -0,0 +1,25 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016, 2017 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/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#if ENABLED(EMERGENCY_PARSER)
|
||||
#error "EMERGENCY_PARSER is not yet implemented for ESP32. Disable EMERGENCY_PARSER to continue."
|
||||
#endif
|
77
Marlin/src/HAL/HAL_ESP32/endstop_interrupts.h
Normal file
77
Marlin/src/HAL/HAL_ESP32/endstop_interrupts.h
Normal file
|
@ -0,0 +1,77 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 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/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* 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)
|
||||
*/
|
||||
|
||||
#ifndef _ENDSTOP_INTERRUPTS_H_
|
||||
#define _ENDSTOP_INTERRUPTS_H_
|
||||
|
||||
#include "../../module/endstops.h"
|
||||
|
||||
// One ISR for all EXT-Interrupts
|
||||
void ICACHE_RAM_ATTR endstop_ISR(void) {
|
||||
endstops.check_possible_change();
|
||||
}
|
||||
|
||||
void setup_endstop_interrupts(void) {
|
||||
#if HAS_X_MAX
|
||||
attachInterrupt(digitalPinToInterrupt(X_MAX_PIN), endstop_ISR, CHANGE);
|
||||
#endif
|
||||
#if HAS_X_MIN
|
||||
attachInterrupt(digitalPinToInterrupt(X_MIN_PIN), endstop_ISR, CHANGE);
|
||||
#endif
|
||||
#if HAS_Y_MAX
|
||||
attachInterrupt(digitalPinToInterrupt(Y_MAX_PIN), endstop_ISR, CHANGE);
|
||||
#endif
|
||||
#if HAS_Y_MIN
|
||||
attachInterrupt(digitalPinToInterrupt(Y_MIN_PIN), endstop_ISR, CHANGE);
|
||||
#endif
|
||||
#if HAS_Z_MAX
|
||||
attachInterrupt(digitalPinToInterrupt(Z_MAX_PIN), endstop_ISR, CHANGE);
|
||||
#endif
|
||||
#if HAS_Z_MIN
|
||||
attachInterrupt(digitalPinToInterrupt(Z_MIN_PIN), endstop_ISR, CHANGE);
|
||||
#endif
|
||||
#if HAS_Z2_MAX
|
||||
attachInterrupt(digitalPinToInterrupt(Z2_MAX_PIN), endstop_ISR, CHANGE);
|
||||
#endif
|
||||
#if HAS_Z2_MIN
|
||||
attachInterrupt(digitalPinToInterrupt(Z2_MIN_PIN), endstop_ISR, CHANGE);
|
||||
#endif
|
||||
#if HAS_Z_MIN_PROBE_PIN
|
||||
attachInterrupt(digitalPinToInterrupt(Z_MIN_PROBE_PIN), endstop_ISR, CHANGE);
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif //_ENDSTOP_INTERRUPTS_H_
|
72
Marlin/src/HAL/HAL_ESP32/fastio_ESP32.h
Normal file
72
Marlin/src/HAL/HAL_ESP32/fastio_ESP32.h
Normal file
|
@ -0,0 +1,72 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 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/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef _FASTIO_ESP32_H
|
||||
#define _FASTIO_ESP32_H
|
||||
|
||||
/**
|
||||
* Utility functions
|
||||
*/
|
||||
|
||||
// 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) digitalRead(IO)
|
||||
|
||||
// Write to a pin wrapper
|
||||
#define WRITE(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); WRITE(IO, LOW); }while(0)
|
||||
|
||||
#define OUT_WRITE(IO,V) do{ _SET_OUTPUT(IO); WRITE(IO,V); }while(0)
|
||||
|
||||
//
|
||||
// ports and functions
|
||||
//
|
||||
|
||||
// UART
|
||||
#define RXD 3
|
||||
#define TXD 1
|
||||
|
||||
// TWI (I2C)
|
||||
#define SCL 5
|
||||
#define SDA 4
|
||||
|
||||
//
|
||||
// pins
|
||||
//
|
||||
|
||||
#endif // _FASTIO_ESP32_H
|
81
Marlin/src/HAL/HAL_ESP32/ota.cpp
Normal file
81
Marlin/src/HAL/HAL_ESP32/ota.cpp
Normal file
|
@ -0,0 +1,81 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 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 ENABLED(WIFISUPPORT)
|
||||
|
||||
#include <WiFi.h>
|
||||
#include <ESPmDNS.h>
|
||||
#include <WiFiUdp.h>
|
||||
#include <ArduinoOTA.h>
|
||||
#include "driver/timer.h"
|
||||
|
||||
void OTA_init() {
|
||||
WiFi.mode(WIFI_STA);
|
||||
WiFi.begin(WIFI_SSID, WIFI_PWD);
|
||||
|
||||
while (WiFi.waitForConnectResult() != WL_CONNECTED) {
|
||||
Serial.println("Connection Failed! Rebooting...");
|
||||
delay(5000);
|
||||
ESP.restart();
|
||||
}
|
||||
|
||||
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
|
||||
|
||||
#endif // ARDUINO_ARCH_ESP32
|
26
Marlin/src/HAL/HAL_ESP32/ota.h
Normal file
26
Marlin/src/HAL/HAL_ESP32/ota.h
Normal file
|
@ -0,0 +1,26 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 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/>.
|
||||
*/
|
||||
|
||||
#ifndef _HAL_OTA_H
|
||||
#define _HAL_OTA_H
|
||||
|
||||
void OTA_init();
|
||||
void OTA_handle();
|
||||
|
||||
#endif
|
21
Marlin/src/HAL/HAL_ESP32/servotimers.h
Normal file
21
Marlin/src/HAL/HAL_ESP32/servotimers.h
Normal file
|
@ -0,0 +1,21 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 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/>.
|
||||
*
|
||||
*/
|
28
Marlin/src/HAL/HAL_ESP32/spi_pins.h
Normal file
28
Marlin/src/HAL/HAL_ESP32/spi_pins.h
Normal file
|
@ -0,0 +1,28 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 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/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef SPI_PINS_H_
|
||||
#define SPI_PINS_H_
|
||||
|
||||
#define SS_PIN 5
|
||||
#define SCK_PIN 18
|
||||
#define MISO_PIN 19
|
||||
#define MOSI_PIN 23
|
||||
|
||||
#endif // SPI_PINS_H_
|
41
Marlin/src/HAL/HAL_ESP32/watchdog_ESP32.cpp
Normal file
41
Marlin/src/HAL/HAL_ESP32/watchdog_ESP32.cpp
Normal file
|
@ -0,0 +1,41 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 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_ESP32.h"
|
||||
|
||||
void watchdogSetup(void) {
|
||||
// do whatever. don't remove this function.
|
||||
}
|
||||
|
||||
void watchdog_init(void) {
|
||||
// TODO
|
||||
}
|
||||
|
||||
#endif // USE_WATCHDOG
|
||||
|
||||
#endif // ARDUINO_ARCH_ESP32
|
32
Marlin/src/HAL/HAL_ESP32/watchdog_ESP32.h
Normal file
32
Marlin/src/HAL/HAL_ESP32/watchdog_ESP32.h
Normal file
|
@ -0,0 +1,32 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 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/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef WATCHDOG_ESP32_H
|
||||
#define WATCHDOG_ESP32_H
|
||||
|
||||
// Initialize watchdog with a 4 second interrupt time
|
||||
void watchdog_init();
|
||||
|
||||
// Reset watchdog.
|
||||
inline void watchdog_reset() {};
|
||||
|
||||
#endif // WATCHDOG_ESP32_H
|
|
@ -17,6 +17,8 @@
|
|||
#define HAL_PLATFORM HAL_STM32F4
|
||||
#elif defined(STM32F7)
|
||||
#define HAL_PLATFORM HAL_STM32F7
|
||||
#elif defined(ARDUINO_ARCH_ESP32)
|
||||
#define HAL_PLATFORM HAL_ESP32
|
||||
#else
|
||||
#error "Unsupported Platform!"
|
||||
#endif
|
||||
|
|
|
@ -702,10 +702,10 @@ void setup() {
|
|||
|
||||
#if NUM_SERIAL > 0
|
||||
uint32_t serial_connect_timeout = millis() + 1000UL;
|
||||
while(!MYSERIAL0 && PENDING(millis(), serial_connect_timeout)) { /*nada*/ }
|
||||
while (!MYSERIAL0 && PENDING(millis(), serial_connect_timeout)) { /*nada*/ }
|
||||
#if NUM_SERIAL > 1
|
||||
serial_connect_timeout = millis() + 1000UL;
|
||||
while(!MYSERIAL1 && PENDING(millis(), serial_connect_timeout)) { /*nada*/ }
|
||||
while (!MYSERIAL1 && PENDING(millis(), serial_connect_timeout)) { /*nada*/ }
|
||||
#endif
|
||||
#endif
|
||||
|
||||
|
|
|
@ -1700,4 +1700,13 @@
|
|||
// Default behaviour is limited to Z axis only.
|
||||
#endif
|
||||
|
||||
/**
|
||||
* WiFi Support (Espressif ESP32 WiFi)
|
||||
*/
|
||||
//#define WIFISUPPORT
|
||||
#if ENABLED(WIFISUPPORT)
|
||||
#define WIFI_SSID "Wifi SSID"
|
||||
#define WIFI_PWD "Wifi Password"
|
||||
#endif
|
||||
|
||||
#endif // CONFIGURATION_ADV_H
|
||||
|
|
|
@ -225,6 +225,10 @@
|
|||
|
||||
#define BOARD_THE_BORG 1860 // THE-BORG (Power outputs: Hotend0, Hotend1, Bed, Fan)
|
||||
|
||||
//
|
||||
// Espressif ESP32 WiFi
|
||||
//
|
||||
#define BOARD_ESP32 1900
|
||||
|
||||
#define MB(board) (defined(BOARD_##board) && MOTHERBOARD==BOARD_##board)
|
||||
|
||||
|
|
|
@ -381,6 +381,13 @@
|
|||
#elif MB(THE_BORG)
|
||||
#include "pins_THE_BORG.h" // STM32F7 env:STM32F7
|
||||
|
||||
//
|
||||
// Espressif ESP32
|
||||
//
|
||||
|
||||
#elif MB(ESP32)
|
||||
#include "pins_ESP32.h"
|
||||
|
||||
#else
|
||||
#error "Unknown MOTHERBOARD value set in Configuration.h"
|
||||
#endif
|
||||
|
|
72
Marlin/src/pins/pins_ESP32.h
Normal file
72
Marlin/src/pins/pins_ESP32.h
Normal file
|
@ -0,0 +1,72 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 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/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* Espressif ESP32 (Tensilica Xtensa LX6) pin assignments
|
||||
*/
|
||||
|
||||
#ifndef BOARD_NAME
|
||||
#define BOARD_NAME "Espressif ESP32"
|
||||
#endif
|
||||
|
||||
//
|
||||
// Limit Switches
|
||||
//
|
||||
#define X_MIN_PIN 34
|
||||
#define Y_MIN_PIN 35
|
||||
#define Z_MIN_PIN 15
|
||||
|
||||
//
|
||||
// Steppers
|
||||
//
|
||||
#define X_STEP_PIN 27
|
||||
#define X_DIR_PIN 26
|
||||
#define X_ENABLE_PIN 25
|
||||
//#define X_CS_PIN 0
|
||||
|
||||
#define Y_STEP_PIN 33
|
||||
#define Y_DIR_PIN 32
|
||||
#define Y_ENABLE_PIN X_ENABLE_PIN
|
||||
//#define Y_CS_PIN 13
|
||||
|
||||
#define Z_STEP_PIN 14
|
||||
#define Z_DIR_PIN 12
|
||||
#define Z_ENABLE_PIN X_ENABLE_PIN
|
||||
//#define Z_CS_PIN 5 // SS_PIN
|
||||
|
||||
#define E0_STEP_PIN 16
|
||||
#define E0_DIR_PIN 17
|
||||
#define E0_ENABLE_PIN X_ENABLE_PIN
|
||||
//#define E0_CS_PIN 21
|
||||
|
||||
//
|
||||
// Temperature Sensors
|
||||
//
|
||||
#define TEMP_0_PIN 36 // Analog Input
|
||||
#define TEMP_BED_PIN 39 // Analog Input
|
||||
|
||||
//
|
||||
// Heaters / Fans
|
||||
//
|
||||
#define HEATER_0_PIN 2
|
||||
#define FAN_PIN 13
|
||||
#define HEATER_BED_PIN 4
|
|
@ -318,3 +318,19 @@ lib_ignore =
|
|||
U8glib-HAL
|
||||
TMC2208Stepper
|
||||
c1921b4
|
||||
|
||||
#
|
||||
# Espressif ESP32
|
||||
#
|
||||
[env:esp32]
|
||||
platform = https://github.com/platformio/platform-espressif32.git#feature/stage
|
||||
board = esp32dev
|
||||
framework = arduino
|
||||
upload_port = COM3
|
||||
lib_ignore =
|
||||
LiquidCrystal_I2C
|
||||
LiquidCrystal
|
||||
NewliquidCrystal
|
||||
LiquidTWI2
|
||||
TMC26XStepper
|
||||
c1921b4
|
||||
|
|
Loading…
Reference in a new issue