✨ ESP32 Panda_ZHU and Panda_M4 (#22644)
This commit is contained in:
parent
f395198e14
commit
4e9ae9449f
|
@ -34,7 +34,9 @@
|
|||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
void spiBegin() {
|
||||
OUT_WRITE(SD_SS_PIN, HIGH);
|
||||
#if PIN_EXISTS(SD_SS)
|
||||
OUT_WRITE(SD_SS_PIN, HIGH);
|
||||
#endif
|
||||
SET_OUTPUT(SD_SCK_PIN);
|
||||
SET_INPUT(SD_MISO_PIN);
|
||||
SET_OUTPUT(SD_MOSI_PIN);
|
||||
|
|
|
@ -28,6 +28,10 @@
|
|||
#include <esp_adc_cal.h>
|
||||
#include <HardwareSerial.h>
|
||||
|
||||
#if ENABLED(USE_ESP32_TASK_WDT)
|
||||
#include <esp_task_wdt.h>
|
||||
#endif
|
||||
|
||||
#if ENABLED(WIFISUPPORT)
|
||||
#include <ESPAsyncWebServer.h>
|
||||
#include "wifi.h"
|
||||
|
@ -90,8 +94,24 @@ volatile int numPWMUsed = 0,
|
|||
|
||||
#endif
|
||||
|
||||
void HAL_init_board() {
|
||||
#if ENABLED(USE_ESP32_EXIO)
|
||||
HardwareSerial YSerial2(2);
|
||||
|
||||
void Write_EXIO(uint8_t IO, uint8_t v) {
|
||||
if (ISRS_ENABLED()) {
|
||||
DISABLE_ISRS();
|
||||
YSerial2.write(0x80 | (((char)v) << 5) | (IO - 100));
|
||||
ENABLE_ISRS();
|
||||
}
|
||||
else
|
||||
YSerial2.write(0x80 | (((char)v) << 5) | (IO - 100));
|
||||
}
|
||||
#endif
|
||||
|
||||
void HAL_init_board() {
|
||||
#if ENABLED(USE_ESP32_TASK_WDT)
|
||||
esp_task_wdt_init(10, true);
|
||||
#endif
|
||||
#if ENABLED(ESP3D_WIFISUPPORT)
|
||||
esp3dlib.init();
|
||||
#elif ENABLED(WIFISUPPORT)
|
||||
|
@ -127,7 +147,11 @@ void HAL_init_board() {
|
|||
// Initialize the i2s peripheral only if the I2S stepper stream is enabled.
|
||||
// The following initialization is performed after Serial1 and Serial2 are defined as
|
||||
// their native pins might conflict with the i2s stream even when they are remapped.
|
||||
TERN_(I2S_STEPPER_STREAM, i2s_init());
|
||||
#if ENABLED(USE_ESP32_EXIO)
|
||||
YSerial2.begin(460800 * 3, SERIAL_8N1, 16, 17);
|
||||
#elif ENABLED(I2S_STEPPER_STREAM)
|
||||
i2s_init();
|
||||
#endif
|
||||
}
|
||||
|
||||
void HAL_idletask() {
|
||||
|
|
|
@ -142,6 +142,10 @@ void HAL_idletask();
|
|||
inline void HAL_init() {}
|
||||
void HAL_init_board();
|
||||
|
||||
#if ENABLED(USE_ESP32_EXIO)
|
||||
void Write_EXIO(uint8_t IO, uint8_t v);
|
||||
#endif
|
||||
|
||||
//
|
||||
// Delay in cycles (used by DELAY_NS / DELAY_US)
|
||||
//
|
||||
|
|
|
@ -53,11 +53,9 @@ static SPISettings spiConfig;
|
|||
// ------------------------
|
||||
|
||||
void spiBegin() {
|
||||
#if !PIN_EXISTS(SD_SS)
|
||||
#error "SD_SS_PIN not defined!"
|
||||
#if ENABLED(SDSUPPORT) && PIN_EXISTS(SD_SS)
|
||||
OUT_WRITE(SD_SS_PIN, HIGH);
|
||||
#endif
|
||||
|
||||
OUT_WRITE(SD_SS_PIN, HIGH);
|
||||
}
|
||||
|
||||
void spiInit(uint8_t spiRate) {
|
||||
|
|
6
Marlin/src/HAL/ESP32/esp32.csv
Normal file
6
Marlin/src/HAL/ESP32/esp32.csv
Normal file
|
@ -0,0 +1,6 @@
|
|||
# Name, Type, SubType, Offset, Size, Flags
|
||||
nvs, data, nvs, 0x9000, 0x5000,
|
||||
otadata, data, ota, 0xe000, 0x2000,
|
||||
app0, app, ota_0, 0x10000, 0x180000,
|
||||
app1, app, ota_1, 0x190000, 0x180000,
|
||||
spiffs, data, spiffs, 0x310000, 0xF0000,
|
|
|
@ -40,13 +40,19 @@
|
|||
// Set pin as input with pullup mode
|
||||
#define _PULLUP(IO, v) pinMode(IO, v ? INPUT_PULLUP : INPUT)
|
||||
|
||||
// Read a pin wrapper
|
||||
#define READ(IO) (IS_I2S_EXPANDER_PIN(IO) ? i2s_state(I2S_EXPANDER_PIN_INDEX(IO)) : digitalRead(IO))
|
||||
#if ENABLED(USE_ESP32_EXIO)
|
||||
// Read a pin wrapper
|
||||
#define READ(IO) digitalRead(IO)
|
||||
// Write to a pin wrapper
|
||||
#define WRITE(IO, v) (IO >= 100 ? Write_EXIO(IO, v) : digitalWrite(IO, v))
|
||||
#else
|
||||
// Read a pin wrapper
|
||||
#define READ(IO) (IS_I2S_EXPANDER_PIN(IO) ? i2s_state(I2S_EXPANDER_PIN_INDEX(IO)) : digitalRead(IO))
|
||||
// Write to a pin wrapper
|
||||
#define WRITE(IO, v) (IS_I2S_EXPANDER_PIN(IO) ? i2s_write(I2S_EXPANDER_PIN_INDEX(IO), v) : digitalWrite(IO, v))
|
||||
#endif
|
||||
|
||||
// Write to a pin wrapper
|
||||
#define WRITE(IO, v) (IS_I2S_EXPANDER_PIN(IO) ? i2s_write(I2S_EXPANDER_PIN_INDEX(IO), v) : digitalWrite(IO, v))
|
||||
|
||||
// Set pin as input wrapper
|
||||
// Set pin as input wrapper (0x80 | (v << 5) | (IO - 100))
|
||||
#define SET_INPUT(IO) _SET_INPUT(IO)
|
||||
|
||||
// Set pin as input with pullup wrapper
|
||||
|
|
|
@ -23,6 +23,8 @@
|
|||
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if DISABLED(USE_ESP32_EXIO)
|
||||
|
||||
#include "i2s.h"
|
||||
|
||||
#include "../shared/Marduino.h"
|
||||
|
@ -340,4 +342,5 @@ void i2s_push_sample() {
|
|||
dma.current[dma.rw_pos++] = i2s_port_data;
|
||||
}
|
||||
|
||||
#endif // !USE_ESP32_EXIO
|
||||
#endif // ARDUINO_ARCH_ESP32
|
||||
|
|
|
@ -25,7 +25,7 @@
|
|||
extern "C" {
|
||||
#endif
|
||||
|
||||
esp_err_t esp_task_wdt_reset();
|
||||
esp_err_t esp_task_wdt_reset();
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
|
|
|
@ -47,7 +47,9 @@ static SPISettings spiConfig;
|
|||
#include "../shared/Delay.h"
|
||||
|
||||
void spiBegin(void) {
|
||||
OUT_WRITE(SD_SS_PIN, HIGH);
|
||||
#if PIN_EXISTS(SD_SS)
|
||||
OUT_WRITE(SD_SS_PIN, HIGH);
|
||||
#endif
|
||||
OUT_WRITE(SD_SCK_PIN, HIGH);
|
||||
SET_INPUT(SD_MISO_PIN);
|
||||
OUT_WRITE(SD_MOSI_PIN, HIGH);
|
||||
|
|
|
@ -36,10 +36,9 @@ static SPISettings spiConfig;
|
|||
|
||||
// Initialize SPI bus
|
||||
void spiBegin() {
|
||||
#if !PIN_EXISTS(SD_SS)
|
||||
#error "SD_SS_PIN not defined!"
|
||||
#if PIN_EXISTS(SD_SS)
|
||||
OUT_WRITE(SD_SS_PIN, HIGH);
|
||||
#endif
|
||||
OUT_WRITE(SD_SS_PIN, HIGH);
|
||||
SET_OUTPUT(SD_SCK_PIN);
|
||||
SET_INPUT(SD_MISO_PIN);
|
||||
SET_OUTPUT(SD_MOSI_PIN);
|
||||
|
|
|
@ -36,10 +36,9 @@
|
|||
static SPISettings spiConfig;
|
||||
|
||||
void spiBegin() {
|
||||
#if !PIN_EXISTS(SD_SS)
|
||||
#error "SD_SS_PIN not defined!"
|
||||
#if PIN_EXISTS(SD_SS)
|
||||
OUT_WRITE(SD_SS_PIN, HIGH);
|
||||
#endif
|
||||
OUT_WRITE(SD_SS_PIN, HIGH);
|
||||
SET_OUTPUT(SD_SCK_PIN);
|
||||
SET_INPUT(SD_MISO_PIN);
|
||||
SET_OUTPUT(SD_MOSI_PIN);
|
||||
|
|
|
@ -51,12 +51,9 @@ static SPISettings spiConfig;
|
|||
// ------------------------
|
||||
|
||||
void spiBegin() {
|
||||
#ifndef SD_SS_PIN
|
||||
#error "SD_SS_PIN is not defined!"
|
||||
#if PIN_EXISTS(SD_SS)
|
||||
OUT_WRITE(SD_SS_PIN, HIGH);
|
||||
#endif
|
||||
|
||||
OUT_WRITE(SD_SS_PIN, HIGH);
|
||||
|
||||
//SET_OUTPUT(SD_SCK_PIN);
|
||||
//SET_INPUT(SD_MISO_PIN);
|
||||
//SET_OUTPUT(SD_MOSI_PIN);
|
||||
|
|
|
@ -422,6 +422,8 @@
|
|||
#define BOARD_MRR_ESPE 6002 // MRR ESPE based on ESP32 (with I2S stepper stream)
|
||||
#define BOARD_E4D_BOX 6003 // E4d@BOX
|
||||
#define BOARD_FYSETC_E4 6004 // FYSETC E4
|
||||
#define BOARD_PANDA_ZHU 6005 // Panda_ZHU
|
||||
#define BOARD_PANDA_M4 6006 // Panda_M4
|
||||
|
||||
//
|
||||
// SAMD51 ARM Cortex M4
|
||||
|
|
|
@ -27,6 +27,7 @@
|
|||
#include "../gcode.h"
|
||||
#include "../../module/planner.h"
|
||||
#include "../../module/printcounter.h"
|
||||
#include "../../module/temperature.h"
|
||||
#include "../../sd/cardreader.h"
|
||||
|
||||
#ifdef SD_FINISHED_RELEASECOMMAND
|
||||
|
|
|
@ -597,9 +597,9 @@
|
|||
#error "SPINDLE_LASER_PWM (true) is now set with SPINDLE_LASER_USE_PWM (enabled)."
|
||||
#endif
|
||||
|
||||
#if MOTHERBOARD == BOARD_DUE3DOM_MINI && PIN_EXISTS(TEMP_2) && DISABLED(TEMP_SENSOR_BOARD)
|
||||
#if MB(DUE3DOM_MINI) && PIN_EXISTS(TEMP_2) && DISABLED(TEMP_SENSOR_BOARD)
|
||||
#warning "Onboard temperature sensor for BOARD_DUE3DOM_MINI has moved from TEMP_SENSOR_2 (TEMP_2_PIN) to TEMP_SENSOR_BOARD (TEMP_BOARD_PIN)."
|
||||
#elif MOTHERBOARD == BOARD_BTT_SKR_E3_TURBO && PIN_EXISTS(TEMP_2) && DISABLED(TEMP_SENSOR_BOARD)
|
||||
#elif MB(BTT_SKR_E3_TURBO) && PIN_EXISTS(TEMP_2) && DISABLED(TEMP_SENSOR_BOARD)
|
||||
#warning "Onboard temperature sensor for BOARD_BTT_SKR_E3_TURBO has moved from TEMP_SENSOR_2 (TEMP_2_PIN) to TEMP_SENSOR_BOARD (TEMP_BOARD_PIN)."
|
||||
#endif
|
||||
|
||||
|
|
38
Marlin/src/pins/esp32/pins_PANDA_M4.h
Normal file
38
Marlin/src/pins/esp32/pins_PANDA_M4.h
Normal file
|
@ -0,0 +1,38 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* Panda M4 pin assignments
|
||||
*/
|
||||
|
||||
#define BOARD_INFO_NAME "Panda_M4"
|
||||
|
||||
#include "pins_PANDA_common.h"
|
||||
|
||||
//
|
||||
// Steppers
|
||||
//
|
||||
#define X_ENABLE_PIN 115
|
||||
#define Y_ENABLE_PIN 114
|
||||
#define Z_ENABLE_PIN 113
|
||||
#define E0_ENABLE_PIN 112
|
61
Marlin/src/pins/esp32/pins_PANDA_ZHU.h
Normal file
61
Marlin/src/pins/esp32/pins_PANDA_ZHU.h
Normal file
|
@ -0,0 +1,61 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* Panda ZHU pin assignments
|
||||
*/
|
||||
|
||||
#define BOARD_INFO_NAME "Panda_ZHU"
|
||||
|
||||
#include "pins_PANDA_common.h"
|
||||
|
||||
//
|
||||
// Steppers
|
||||
//
|
||||
#define X_ENABLE_PIN 128 // Shared with all steppers
|
||||
#define Y_ENABLE_PIN X_ENABLE_PIN
|
||||
#define Z_ENABLE_PIN X_ENABLE_PIN
|
||||
#define E0_ENABLE_PIN X_ENABLE_PIN
|
||||
|
||||
//#define X_CS_PIN 0
|
||||
//#define Y_CS_PIN 13
|
||||
//#define Z_CS_PIN 5 // SS_PIN
|
||||
//#define E0_CS_PIN 21
|
||||
|
||||
#define E1_STEP_PIN 115
|
||||
#define E1_DIR_PIN 114
|
||||
#define E1_ENABLE_PIN X_ENABLE_PIN
|
||||
|
||||
#define E2_STEP_PIN 112
|
||||
#define E2_DIR_PIN 113
|
||||
#define E2_ENABLE_PIN X_ENABLE_PIN
|
||||
|
||||
#define E3_STEP_PIN 110
|
||||
#define E3_DIR_PIN 111
|
||||
#define E3_ENABLE_PIN X_ENABLE_PIN
|
||||
|
||||
#define E4_STEP_PIN 121
|
||||
#define E4_DIR_PIN 122
|
||||
#define E4_ENABLE_PIN X_ENABLE_PIN
|
||||
|
||||
#define HEATER_1_PIN 123
|
98
Marlin/src/pins/esp32/pins_PANDA_common.h
Normal file
98
Marlin/src/pins/esp32/pins_PANDA_common.h
Normal file
|
@ -0,0 +1,98 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* Panda common pin assignments
|
||||
*/
|
||||
|
||||
#include "env_validate.h"
|
||||
|
||||
#define DEFAULT_MACHINE_NAME BOARD_INFO_NAME
|
||||
|
||||
//
|
||||
// Servos
|
||||
//
|
||||
#define SERVO0_PIN 0
|
||||
|
||||
//
|
||||
// Limit Switches
|
||||
//
|
||||
#define X_STOP_PIN 4
|
||||
#define Y_STOP_PIN 35
|
||||
#define Z_STOP_PIN 21
|
||||
|
||||
//
|
||||
// Steppers
|
||||
//
|
||||
#define X_STEP_PIN 101
|
||||
#define X_DIR_PIN 100
|
||||
|
||||
#define Y_STEP_PIN 103
|
||||
#define Y_DIR_PIN 102
|
||||
|
||||
#define Z_STEP_PIN 105
|
||||
#define Z_DIR_PIN 104
|
||||
|
||||
#define E0_STEP_PIN 107
|
||||
#define E0_DIR_PIN 106
|
||||
|
||||
//
|
||||
// Temperature Sensors
|
||||
//
|
||||
#define TEMP_0_PIN 39 // Analog Input
|
||||
#define TEMP_BED_PIN 36 // Analog Input
|
||||
|
||||
//
|
||||
// Heaters / Fans
|
||||
//
|
||||
#define HEATER_0_PIN 108
|
||||
#define HEATER_BED_PIN 109
|
||||
#define FAN_PIN 118 // FAN0
|
||||
#define FAN1_PIN 119 // FAN1
|
||||
|
||||
#ifndef E0_AUTO_FAN_PIN
|
||||
#define E0_AUTO_FAN_PIN 120 // FAN2
|
||||
#endif
|
||||
|
||||
//
|
||||
// SD card
|
||||
//
|
||||
#if ENABLED(SDSUPPORT)
|
||||
#define SD_MOSI_PIN 23
|
||||
#define SD_MISO_PIN 19
|
||||
#define SD_SCK_PIN 18
|
||||
#define SDSS 5
|
||||
#define SD_DETECT_PIN 2
|
||||
#endif
|
||||
|
||||
#if HAS_WIRED_LCD
|
||||
#define BEEPER_PIN 129
|
||||
#define BTN_ENC 12
|
||||
|
||||
#define BTN_EN1 33
|
||||
#define BTN_EN2 32
|
||||
|
||||
#define LCD_PINS_RS 27
|
||||
#define LCD_PINS_ENABLE 26
|
||||
#define LCD_PINS_D4 14
|
||||
#endif
|
|
@ -681,6 +681,10 @@
|
|||
#include "esp32/pins_E4D.h" // ESP32 env:esp32
|
||||
#elif MB(FYSETC_E4)
|
||||
#include "esp32/pins_FYSETC_E4.h" // ESP32 env:FYSETC_E4
|
||||
#elif MB(PANDA_ZHU)
|
||||
#include "esp32/pins_PANDA_ZHU.h" // ESP32 env:PANDA
|
||||
#elif MB(PANDA_M4)
|
||||
#include "esp32/pins_PANDA_M4.h" // ESP32 env:PANDA
|
||||
|
||||
//
|
||||
// Adafruit Grand Central M4 (SAMD51 ARM Cortex-M4)
|
||||
|
|
|
@ -27,3 +27,13 @@ monitor_speed = 250000
|
|||
platform = espressif32@2.1.0
|
||||
extends = env:esp32
|
||||
board_build.partitions = default_16MB.csv
|
||||
|
||||
[env:PANDA]
|
||||
platform = espressif32@2.1.0
|
||||
extends = env:esp32
|
||||
build_flags = ${env:esp32.build_flags} -DUSE_ESP32_EXIO -DUSE_ESP32_TASK_WDT
|
||||
lib_deps = ${common.lib_deps}
|
||||
SoftwareSerialEsp32
|
||||
board_build.partitions = Marlin/src/HAL/ESP32/esp32.csv
|
||||
upload_speed = 115200
|
||||
monitor_speed = 115200
|
||||
|
|
|
@ -65,8 +65,7 @@ build_flags = ${common_stm32f1.build_flags}
|
|||
extra_scripts = ${common_stm32f1.extra_scripts}
|
||||
pre:buildroot/share/PlatformIO/scripts/STM32F1_create_variant.py
|
||||
buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP.py
|
||||
lib_deps = ${common.lib_deps}
|
||||
SoftwareSerialM
|
||||
lib_deps = ${common_stm32f1.lib_deps}
|
||||
USBComposite for STM32F1@0.91
|
||||
custom_marlin.NEOPIXEL_LED = Adafruit NeoPixel=https://github.com/ccccmagicboy/Adafruit_NeoPixel#meeb_3dp_use
|
||||
debug_tool = stlink
|
||||
|
@ -377,7 +376,8 @@ extra_scripts = ${common.extra_scripts}
|
|||
buildroot/share/PlatformIO/scripts/offset_and_rename.py
|
||||
build_flags = ${common_stm32f1.build_flags}
|
||||
-D__STM32F1__=1 -DDEBUG_LEVEL=0 -DSS_TIMER=4 -DSERIAL_USB
|
||||
lib_deps = USBComposite for STM32F1@0.91
|
||||
lib_deps = ${common_stm32f1.lib_deps}
|
||||
USBComposite for STM32F1@0.91
|
||||
lib_ignore = Adafruit NeoPixel, SPI, SailfishLCD, SailfishRGB_LED, SlowSoftI2CMaster, TMCStepper
|
||||
|
||||
[env:STM32F103RC_ZM3E2_USB_maple]
|
||||
|
|
Loading…
Reference in a new issue