Merge branch 'bugfix-2.0.x' of https://github.com/MarlinFirmware/Marlin into bugfix-2.0.x
This commit is contained in:
commit
9dd4252b39
365 changed files with 15127 additions and 4499 deletions
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 0
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -462,7 +471,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1413,7 +1422,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1893,6 +1902,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2050,10 +2065,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -678,6 +692,7 @@
|
|||
* A (A shifted) B (B shifted) IC
|
||||
* Smoothie 0x2C (0x58) 0x2D (0x5A) MCP4451
|
||||
* AZTEEG_X3_PRO 0x2C (0x58) 0x2E (0x5C) MCP4451
|
||||
* AZTEEG_X5_MINI 0x2C (0x58) 0x2E (0x5C) MCP4451
|
||||
* AZTEEG_X5_MINI_WIFI 0x58 0x5C MCP4451
|
||||
* MIGHTYBOARD_REVE 0x2F (0x5E) MCP4018
|
||||
*/
|
||||
|
@ -770,8 +785,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -959,6 +977,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1000,13 +1024,15 @@
|
|||
#if ENABLED(DOUBLECLICK_FOR_Z_BABYSTEPPING)
|
||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||
// Note: Extra time may be added to mitigate controller latency.
|
||||
//#define BABYSTEP_ALWAYS_AVAILABLE // Allow babystepping at all times (not just during movement).
|
||||
#define BABYSTEP_ALWAYS_AVAILABLE // Allow babystepping at all times (not just during movement).
|
||||
//#define MOVE_Z_WHEN_IDLE // Jump to the move Z menu on doubleclick when printer is idle.
|
||||
#if ENABLED(MOVE_Z_WHEN_IDLE)
|
||||
#define MOVE_Z_IDLE_MULTIPLICATOR 1 // Multiply 1mm by this factor for the move step size.
|
||||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -739,8 +739,7 @@
|
|||
|
||||
#endif // !USBCON && (UBRRH || UBRR0H || UBRR1H || UBRR2H || UBRR3H)
|
||||
|
||||
|
||||
#if defined(INTERNAL_SERIAL_PORT)
|
||||
#ifdef INTERNAL_SERIAL_PORT
|
||||
|
||||
ISR(SERIAL_REGNAME(USART,INTERNAL_SERIAL_PORT,_RX_vect)) {
|
||||
MarlinSerial<MarlinInternalSerialCfg<INTERNAL_SERIAL_PORT>>::store_rxd_char();
|
||||
|
@ -757,6 +756,7 @@
|
|||
MarlinSerial<MarlinInternalSerialCfg<INTERNAL_SERIAL_PORT>> internalSerial;
|
||||
|
||||
#endif
|
||||
|
||||
// For AT90USB targets use the UART for BT interfacing
|
||||
#if defined(USBCON) && ENABLED(BLUETOOTH)
|
||||
HardwareSerial bluetoothSerial;
|
||||
|
|
|
@ -276,7 +276,7 @@
|
|||
#endif // !USBCON
|
||||
|
||||
|
||||
#if defined(INTERNAL_SERIAL_PORT)
|
||||
#ifdef INTERNAL_SERIAL_PORT
|
||||
template <uint8_t serial>
|
||||
struct MarlinInternalSerialCfg {
|
||||
static constexpr int PORT = serial;
|
||||
|
|
|
@ -46,8 +46,8 @@
|
|||
* Sanity checks for Spindle / Laser
|
||||
*/
|
||||
#if ENABLED(SPINDLE_LASER_ENABLE)
|
||||
#if !PIN_EXISTS(SPINDLE_LASER_ENABLE)
|
||||
#error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENABLE_PIN."
|
||||
#if !PIN_EXISTS(SPINDLE_LASER_ENA)
|
||||
#error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENA_PIN."
|
||||
#elif SPINDLE_DIR_CHANGE && !PIN_EXISTS(SPINDLE_DIR)
|
||||
#error "SPINDLE_DIR_PIN not defined."
|
||||
#elif ENABLED(SPINDLE_LASER_PWM) && PIN_EXISTS(SPINDLE_LASER_PWM)
|
||||
|
|
33
Marlin/src/HAL/HAL_ESP32/FlushableHardwareSerial.cpp
Normal file
33
Marlin/src/HAL/HAL_ESP32/FlushableHardwareSerial.cpp
Normal file
|
@ -0,0 +1,33 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2019 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
|
36
Marlin/src/HAL/HAL_ESP32/FlushableHardwareSerial.h
Normal file
36
Marlin/src/HAL/HAL_ESP32/FlushableHardwareSerial.h
Normal file
|
@ -0,0 +1,36 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2019 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 <HardwareSerial.h>
|
||||
|
||||
class FlushableHardwareSerial : public HardwareSerial {
|
||||
public:
|
||||
FlushableHardwareSerial(int uart_nr);
|
||||
|
||||
inline void flushTX(void) { /* No need to flush the hardware serial, but defined here for compatibility. */ }
|
||||
};
|
||||
|
||||
extern FlushableHardwareSerial flushableSerial;
|
||||
|
||||
#endif // ARDUINO_ARCH_ESP32
|
|
@ -41,7 +41,10 @@
|
|||
#endif
|
||||
#if ENABLED(WEBSUPPORT)
|
||||
#include "web.h"
|
||||
#include "spiffs.h"
|
||||
#endif
|
||||
#elif ENABLED(EEPROM_SETTINGS)
|
||||
#include "spiffs.h"
|
||||
#endif
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
|
@ -95,9 +98,12 @@ void HAL_init(void) {
|
|||
OTA_init();
|
||||
#endif
|
||||
#if ENABLED(WEBSUPPORT)
|
||||
spiffs_init();
|
||||
web_init();
|
||||
#endif
|
||||
server.begin();
|
||||
#elif ENABLED(EEPROM_SETTINGS)
|
||||
spiffs_init();
|
||||
#endif
|
||||
|
||||
i2s_init();
|
||||
|
|
|
@ -48,6 +48,7 @@
|
|||
#include "HAL_timers_ESP32.h"
|
||||
|
||||
#include "WebSocketSerial.h"
|
||||
#include "FlushableHardwareSerial.h"
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Defines
|
||||
|
@ -55,7 +56,7 @@
|
|||
|
||||
extern portMUX_TYPE spinlock;
|
||||
|
||||
#define MYSERIAL0 Serial
|
||||
#define MYSERIAL0 flushableSerial
|
||||
|
||||
#if ENABLED(WIFISUPPORT)
|
||||
#define NUM_SERIAL 2
|
||||
|
|
|
@ -44,6 +44,15 @@ static SPISettings spiConfig;
|
|||
// Public functions
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
#if ENABLED(SOFTWARE_SPI)
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Software SPI
|
||||
// --------------------------------------------------------------------------
|
||||
#error "Software SPI not supported for ESP32. Use Hardware SPI."
|
||||
|
||||
#else
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Hardware SPI
|
||||
// --------------------------------------------------------------------------
|
||||
|
@ -61,13 +70,14 @@ 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
|
||||
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);
|
||||
|
@ -106,4 +116,6 @@ void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode)
|
|||
SPI.beginTransaction(spiConfig);
|
||||
}
|
||||
|
||||
#endif // !SOFTWARE_SPI
|
||||
|
||||
#endif // ARDUINO_ARCH_ESP32
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
|
|
|
@ -64,6 +64,9 @@
|
|||
#define PWM_PIN(P) true
|
||||
#define USEABLE_HARDWARE_PWM(P) PWM_PIN(P)
|
||||
|
||||
// Toggle pin value
|
||||
#define TOGGLE(IO) WRITE(IO, !READ(IO))
|
||||
|
||||
//
|
||||
// Ports and functions
|
||||
//
|
||||
|
|
93
Marlin/src/HAL/HAL_ESP32/persistent_store_spiffs.cpp
Normal file
93
Marlin/src/HAL/HAL_ESP32/persistent_store_spiffs.cpp
Normal file
|
@ -0,0 +1,93 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2019 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 "SPIFFS.h"
|
||||
#include "FS.h"
|
||||
#include "spiffs.h"
|
||||
|
||||
#define HAL_ESP32_EEPROM_SIZE 4096
|
||||
|
||||
File eeprom_file;
|
||||
|
||||
bool PersistentStore::access_start() {
|
||||
if (spiffs_initialized) {
|
||||
eeprom_file = SPIFFS.open("/eeprom.dat", "r+");
|
||||
|
||||
size_t file_size = eeprom_file.size();
|
||||
if (file_size < HAL_ESP32_EEPROM_SIZE) {
|
||||
bool write_ok = eeprom_file.seek(file_size);
|
||||
|
||||
while (write_ok && file_size < HAL_ESP32_EEPROM_SIZE) {
|
||||
write_ok = eeprom_file.write(0xFF) == 1;
|
||||
file_size++;
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
bool PersistentStore::access_finish() {
|
||||
eeprom_file.close();
|
||||
return true;
|
||||
}
|
||||
|
||||
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
|
||||
if (!eeprom_file.seek(pos)) return true; // return true for any error
|
||||
if (eeprom_file.write(value, size) != size) return true;
|
||||
|
||||
crc16(crc, value, size);
|
||||
pos += size;
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
|
||||
if (!eeprom_file.seek(pos)) return true; // return true for any error
|
||||
|
||||
if (writing) {
|
||||
if (eeprom_file.read(value, size) != size) return true;
|
||||
crc16(crc, value, size);
|
||||
}
|
||||
else {
|
||||
uint8_t tmp[size];
|
||||
if (eeprom_file.read(tmp, size) != size) return true;
|
||||
crc16(crc, tmp, size);
|
||||
}
|
||||
|
||||
pos += size;
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
size_t PersistentStore::capacity() { return HAL_ESP32_EEPROM_SIZE; }
|
||||
|
||||
#endif // EEPROM_SETTINGS
|
||||
#endif // ARDUINO_ARCH_ESP32
|
|
@ -20,21 +20,25 @@
|
|||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* M49.cpp - Toggle the G26 debug flag
|
||||
*/
|
||||
#ifdef ARDUINO_ARCH_ESP32
|
||||
|
||||
#include "../../../inc/MarlinConfig.h"
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if ENABLED(G26_MESH_VALIDATION)
|
||||
#if EITHER(WEBSUPPORT, EEPROM_SETTINGS)
|
||||
|
||||
#include "../../gcode.h"
|
||||
#include "../../../feature/bedlevel/bedlevel.h"
|
||||
#include "../../core/serial.h"
|
||||
|
||||
void GcodeSuite::M49() {
|
||||
g26_debug_flag ^= true;
|
||||
SERIAL_ECHOPGM("G26 Debug: ");
|
||||
serialprintPGM(g26_debug_flag ? PSTR("On\n") : PSTR("Off\n"));
|
||||
#include "FS.h"
|
||||
#include "SPIFFS.h"
|
||||
|
||||
bool spiffs_initialized;
|
||||
|
||||
void spiffs_init() {
|
||||
if (SPIFFS.begin())
|
||||
spiffs_initialized = true;
|
||||
else
|
||||
SERIAL_ECHO_MSG("SPIFFS mount failed");
|
||||
}
|
||||
|
||||
#endif // G26_MESH_VALIDATION
|
||||
#endif // WEBSUPPORT
|
||||
#endif // ARDUINO_ARCH_ESP32
|
26
Marlin/src/HAL/HAL_ESP32/spiffs.h
Normal file
26
Marlin/src/HAL/HAL_ESP32/spiffs.h
Normal file
|
@ -0,0 +1,26 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2019 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();
|
|
@ -1,7 +1,9 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
|
||||
* Copyright (C) 2019 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
|
||||
|
@ -15,6 +17,7 @@
|
|||
*
|
||||
* 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
|
||||
|
@ -23,9 +26,6 @@
|
|||
|
||||
#if ENABLED(WEBSUPPORT)
|
||||
|
||||
#include "../../core/serial.h"
|
||||
|
||||
#include "FS.h"
|
||||
#include "SPIFFS.h"
|
||||
#include "wifi.h"
|
||||
|
||||
|
@ -37,13 +37,9 @@ void onNotFound(AsyncWebServerRequest *request){
|
|||
|
||||
void web_init() {
|
||||
server.addHandler(&events); // attach AsyncEventSource
|
||||
if (SPIFFS.begin()) {
|
||||
server.serveStatic("/", SPIFFS, "/www").setDefaultFile("index.html");
|
||||
server.onNotFound(onNotFound);
|
||||
}
|
||||
else
|
||||
SERIAL_ECHO_MSG("SPIFFS Mount Failed");
|
||||
}
|
||||
|
||||
#endif // WEBSUPPORT
|
||||
#endif // ARDUINO_ARCH_ESP32
|
||||
|
|
|
@ -1,7 +1,9 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
|
||||
* Copyright (C) 2019 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
|
||||
|
@ -15,6 +17,7 @@
|
|||
*
|
||||
* 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
|
||||
|
||||
|
|
|
@ -1,7 +1,9 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
|
||||
* Copyright (C) 2019 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
|
||||
|
@ -15,6 +17,7 @@
|
|||
*
|
||||
* 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
|
||||
|
|
|
@ -1,7 +1,9 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
|
||||
* Copyright (C) 2019 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
|
||||
|
@ -15,6 +17,7 @@
|
|||
*
|
||||
* 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
|
||||
|
||||
|
|
|
@ -25,8 +25,8 @@
|
|||
*/
|
||||
|
||||
#if ENABLED(SPINDLE_LASER_ENABLE)
|
||||
#if !PIN_EXISTS(SPINDLE_LASER_ENABLE)
|
||||
#error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENABLE_PIN."
|
||||
#if !PIN_EXISTS(SPINDLE_LASER_ENA)
|
||||
#error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENA_PIN."
|
||||
#elif SPINDLE_DIR_CHANGE && !PIN_EXISTS(SPINDLE_DIR)
|
||||
#error "SPINDLE_DIR_PIN not defined."
|
||||
#elif ENABLED(SPINDLE_LASER_PWM) && PIN_EXISTS(SPINDLE_LASER_PWM)
|
||||
|
|
|
@ -52,11 +52,13 @@ int freeMemory() {
|
|||
return result;
|
||||
}
|
||||
|
||||
// scan command line for code
|
||||
// return index into pin map array if found and the pin is valid.
|
||||
// return dval if not found or not a valid pin.
|
||||
int16_t PARSED_PIN_INDEX(const char code, const int16_t dval) {
|
||||
const uint16_t val = (uint16_t)parser.intval(code), port = val / 100, pin = val % 100;
|
||||
const int16_t ind = (port < (NUM_DIGITAL_PINS >> 5) && (pin < 32))
|
||||
? GET_PIN_MAP_INDEX(port << 5 | pin) : -2;
|
||||
return ind > -2 ? ind : dval;
|
||||
const uint16_t val = (uint16_t)parser.intval(code, -1), port = val / 100, pin = val % 100;
|
||||
const int16_t ind = (port < ((NUM_DIGITAL_PINS) >> 5) && pin < 32) ? GET_PIN_MAP_INDEX((port << 5) | pin) : -2;
|
||||
return ind > -1 ? ind : dval;
|
||||
}
|
||||
|
||||
void flashFirmware(int16_t value) {
|
||||
|
|
|
@ -25,8 +25,8 @@
|
|||
*/
|
||||
|
||||
#if ENABLED(SPINDLE_LASER_ENABLE)
|
||||
#if !PIN_EXISTS(SPINDLE_LASER_ENABLE)
|
||||
#error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENABLE_PIN."
|
||||
#if !PIN_EXISTS(SPINDLE_LASER_ENA)
|
||||
#error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENA_PIN."
|
||||
#elif SPINDLE_DIR_CHANGE && !PIN_EXISTS(SPINDLE_DIR)
|
||||
#error "SPINDLE_DIR_PIN not defined."
|
||||
#elif ENABLED(SPINDLE_LASER_PWM) && PIN_EXISTS(SPINDLE_LASER_PWM)
|
||||
|
|
|
@ -40,6 +40,12 @@
|
|||
#define PRINT_PIN(p) do {sprintf_P(buffer, PSTR("%d.%02d"), LPC1768_PIN_PORT(p), LPC1768_PIN_PIN(p)); SERIAL_ECHO(buffer);} while (0)
|
||||
#define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin
|
||||
|
||||
// pins that will cause hang/reset/disconnect in M43 Toggle and Watch utilities
|
||||
// uses pin index
|
||||
#ifndef M43_NEVER_TOUCH
|
||||
#define M43_NEVER_TOUCH(Q) ((Q) == 29 || (Q) == 30 || (Q) == 73) // USB pins
|
||||
#endif
|
||||
|
||||
// active ADC function/mode/code values for PINSEL registers
|
||||
constexpr int8_t ADC_pin_mode(pin_t pin) {
|
||||
return (LPC1768_PIN_PORT(pin) == 0 && LPC1768_PIN_PIN(pin) == 2 ? 2 :
|
||||
|
|
|
@ -74,6 +74,8 @@ void watchdog_reset() {
|
|||
|
||||
#else
|
||||
|
||||
void watchdog_init(void) {}
|
||||
void watchdog_reset(void) {}
|
||||
void HAL_clear_reset_source(void) {}
|
||||
uint8_t HAL_get_reset_source(void) { return RST_POWER_ON; }
|
||||
|
||||
|
|
|
@ -36,8 +36,10 @@
|
|||
#if ENABLED(EEPROM_EMULATED_WITH_SRAM)
|
||||
#if STM32F7xx
|
||||
#include "stm32f7xx_ll_pwr.h"
|
||||
#elif STM32F4xx
|
||||
#include "stm32f4xx_ll_pwr.h"
|
||||
#else
|
||||
#error "EEPROM_EMULATED_WITH_SRAM is currently only supported for STM32F7xx"
|
||||
#error "EEPROM_EMULATED_WITH_SRAM is currently only supported for STM32F4xx and STM32F7xx"
|
||||
#endif
|
||||
#endif // EEPROM_EMULATED_WITH_SRAM
|
||||
|
||||
|
|
|
@ -25,8 +25,8 @@
|
|||
* Test Re-ARM specific configuration values for errors at compile-time.
|
||||
*/
|
||||
#if ENABLED(SPINDLE_LASER_ENABLE)
|
||||
#if !PIN_EXISTS(SPINDLE_LASER_ENABLE)
|
||||
#error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENABLE_PIN."
|
||||
#if !PIN_EXISTS(SPINDLE_LASER_ENA)
|
||||
#error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENA_PIN."
|
||||
#elif SPINDLE_DIR_CHANGE && !PIN_EXISTS(SPINDLE_DIR)
|
||||
#error "SPINDLE_DIR_PIN not defined."
|
||||
#elif ENABLED(SPINDLE_LASER_PWM) && PIN_EXISTS(SPINDLE_LASER_PWM)
|
||||
|
|
|
@ -28,8 +28,8 @@
|
|||
* Test Re-ARM specific configuration values for errors at compile-time.
|
||||
*/
|
||||
#if ENABLED(SPINDLE_LASER_ENABLE)
|
||||
#if !PIN_EXISTS(SPINDLE_LASER_ENABLE)
|
||||
#error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENABLE_PIN."
|
||||
#if !PIN_EXISTS(SPINDLE_LASER_ENA)
|
||||
#error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENA_PIN."
|
||||
#elif SPINDLE_DIR_CHANGE && !PIN_EXISTS(SPINDLE_DIR)
|
||||
#error "SPINDLE_DIR_PIN not defined."
|
||||
#elif ENABLED(SPINDLE_LASER_PWM) && PIN_EXISTS(SPINDLE_LASER_PWM)
|
||||
|
|
|
@ -1,6 +1,5 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file EEPROM/EEPROM_Emulation/inc/eeprom.h
|
||||
/******************************************************************************
|
||||
* @file eeprom_emul.h
|
||||
* @author MCD Application Team
|
||||
* @version V1.2.6
|
||||
* @date 04-November-2016
|
||||
|
@ -43,8 +42,7 @@
|
|||
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
|
||||
* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
******************************************************************************
|
||||
*/
|
||||
******************************************************************************/
|
||||
#pragma once
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
|
|
|
@ -24,8 +24,8 @@
|
|||
* Test Re-ARM specific configuration values for errors at compile-time.
|
||||
*/
|
||||
#if ENABLED(SPINDLE_LASER_ENABLE)
|
||||
#if !PIN_EXISTS(SPINDLE_LASER_ENABLE)
|
||||
#error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENABLE_PIN."
|
||||
#if !PIN_EXISTS(SPINDLE_LASER_ENA)
|
||||
#error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENA_PIN."
|
||||
#elif SPINDLE_DIR_CHANGE && !PIN_EXISTS(SPINDLE_DIR)
|
||||
#error "SPINDLE_DIR_PIN not defined."
|
||||
#elif ENABLED(SPINDLE_LASER_PWM) && PIN_EXISTS(SPINDLE_LASER_PWM)
|
||||
|
|
|
@ -1,6 +1,5 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file EEPROM/EEPROM_Emulation/inc/eeprom.h
|
||||
/******************************************************************************
|
||||
* @file eeprom_emul.h
|
||||
* @author MCD Application Team
|
||||
* @version V1.2.6
|
||||
* @date 04-November-2016
|
||||
|
@ -43,8 +42,7 @@
|
|||
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
|
||||
* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
******************************************************************************
|
||||
*/
|
||||
*****************************************************************************/
|
||||
#pragma once
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
|
|
|
@ -24,8 +24,8 @@
|
|||
* Test Re-ARM specific configuration values for errors at compile-time.
|
||||
*/
|
||||
#if ENABLED(SPINDLE_LASER_ENABLE)
|
||||
#if !PIN_EXISTS(SPINDLE_LASER_ENABLE)
|
||||
#error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENABLE_PIN."
|
||||
#if !PIN_EXISTS(SPINDLE_LASER_ENA)
|
||||
#error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENA_PIN."
|
||||
#elif SPINDLE_DIR_CHANGE && !PIN_EXISTS(SPINDLE_DIR)
|
||||
#error "SPINDLE_DIR_PIN not defined."
|
||||
#elif ENABLED(SPINDLE_LASER_PWM) && PIN_EXISTS(SPINDLE_LASER_PWM)
|
||||
|
|
|
@ -457,7 +457,7 @@ void manage_inactivity(const bool ignore_stepper_queue/*=false*/) {
|
|||
if (stepper_inactive_time) {
|
||||
static bool already_shutdown_steppers; // = false
|
||||
if (planner.has_blocks_queued())
|
||||
gcode.previous_move_ms = ms; // reset_stepper_timeout to keep steppers powered
|
||||
gcode.reset_stepper_timeout();
|
||||
else if (MOVE_AWAY_TEST && !ignore_stepper_queue && ELAPSED(ms, gcode.previous_move_ms + stepper_inactive_time)) {
|
||||
if (!already_shutdown_steppers) {
|
||||
already_shutdown_steppers = true; // L6470 SPI will consume 99% of free time without this
|
||||
|
@ -473,15 +473,12 @@ void manage_inactivity(const bool ignore_stepper_queue/*=false*/) {
|
|||
#if ENABLED(DISABLE_INACTIVE_E)
|
||||
disable_e_steppers();
|
||||
#endif
|
||||
#if HAS_LCD_MENU
|
||||
ui.status_screen();
|
||||
#if ENABLED(AUTO_BED_LEVELING_UBL)
|
||||
#if HAS_LCD_MENU && ENABLED(AUTO_BED_LEVELING_UBL)
|
||||
if (ubl.lcd_map_control) {
|
||||
ubl.lcd_map_control = false;
|
||||
ui.defer_status_screen(false);
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
}
|
||||
else
|
||||
|
@ -617,7 +614,7 @@ void manage_inactivity(const bool ignore_stepper_queue/*=false*/) {
|
|||
}
|
||||
#endif // !SWITCHING_EXTRUDER
|
||||
|
||||
gcode.previous_move_ms = ms; // reset_stepper_timeout to keep steppers powered
|
||||
gcode.reset_stepper_timeout();
|
||||
}
|
||||
#endif // EXTRUDER_RUNOUT_PREVENT
|
||||
|
||||
|
@ -723,7 +720,7 @@ void idle(
|
|||
#endif
|
||||
|
||||
#if ENABLED(PRUSA_MMU2)
|
||||
mmu2.mmuLoop();
|
||||
mmu2.mmu_loop();
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -975,7 +972,7 @@ void setup() {
|
|||
#endif
|
||||
|
||||
#if ENABLED(SPINDLE_LASER_ENABLE)
|
||||
OUT_WRITE(SPINDLE_LASER_ENABLE_PIN, !SPINDLE_LASER_ENABLE_INVERT); // init spindle to off
|
||||
OUT_WRITE(SPINDLE_LASER_ENA_PIN, !SPINDLE_LASER_ENABLE_INVERT); // init spindle to off
|
||||
#if SPINDLE_DIR_CHANGE
|
||||
OUT_WRITE(SPINDLE_DIR_PIN, SPINDLE_INVERT_DIR ? 255 : 0); // init rotation to clockwise (M3)
|
||||
#endif
|
||||
|
@ -1045,7 +1042,7 @@ void setup() {
|
|||
ui.init();
|
||||
ui.reset_status();
|
||||
|
||||
#if ENABLED(SHOW_BOOTSCREEN)
|
||||
#if HAS_SPI_LCD && ENABLED(SHOW_BOOTSCREEN)
|
||||
ui.show_bootscreen();
|
||||
#endif
|
||||
|
||||
|
@ -1143,6 +1140,9 @@ void loop() {
|
|||
#if ENABLED(POWER_LOSS_RECOVERY)
|
||||
card.removeJobRecoveryFile();
|
||||
#endif
|
||||
#ifdef EVENT_GCODE_SD_STOP
|
||||
enqueue_and_echo_commands_P(PSTR(EVENT_GCODE_SD_STOP));
|
||||
#endif
|
||||
}
|
||||
#endif // SDSUPPORT
|
||||
|
||||
|
|
|
@ -189,10 +189,11 @@
|
|||
#define BOARD_COHESION3D_REMIX 1755 // Cohesion3D ReMix
|
||||
#define BOARD_COHESION3D_MINI 1756 // Cohesion3D Mini
|
||||
#define BOARD_SMOOTHIEBOARD 1757 // Smoothieboard
|
||||
#define BOARD_AZTEEG_X5_MINI_WIFI 1758 // Azteeg X5 Mini (Power outputs: Hotend0, Bed, Fan)
|
||||
#define BOARD_AZTEEG_X5_MINI_WIFI 1758 // Azteeg X5 Mini Wifi (Power outputs: Hotend0, Bed, Fan)
|
||||
#define BOARD_BIQU_SKR_V1_1 1759 // BIQU SKR_V1.1 (Power outputs: Hotend0,Hotend1, Fan, Bed)
|
||||
#define BOARD_BIQU_B300_V1_0 1760 // BIQU B300_V1.0 (Power outputs: Hotend0, Fan, Bed, SPI Driver)
|
||||
#define BOARD_BIGTREE_SKR_V1_3 1761 // BIGTREE SKR_V1.3 (Power outputs: Hotend0, Hotend1, Fan, Bed)
|
||||
#define BOARD_AZTEEG_X5_MINI 1762 // Azteeg X5 Mini (Power outputs: Hotend0, Bed, Fan)
|
||||
|
||||
//
|
||||
// SAM3X8E ARM Cortex M3
|
||||
|
@ -253,6 +254,8 @@
|
|||
#define BOARD_STM32F4 1804 // STM32 STM32GENERIC based STM32F4 controller
|
||||
#define BOARD_ARMED 1807 // Arm'ed STM32F4 based controller
|
||||
#define BOARD_RUMBA32 1809 // RUMBA32 STM32F4 based controller
|
||||
#define BOARD_BLACK_STM32F407VE 1810 // BLACK_STM32F407VE
|
||||
#define BOARD_BLACK_STM32F407ZE 1811 // BLACK_STM32F407ZE
|
||||
#define BOARD_STEVAL 1866 // STEVAL-3DP001V1 3D PRINTER BOARD
|
||||
|
||||
//
|
||||
|
|
|
@ -47,6 +47,7 @@
|
|||
#undef DEBUG_DELAY
|
||||
|
||||
#if DEBUG_OUT
|
||||
#define DEBUG_PRINT_P(P) serialprintPGM(P)
|
||||
#define DEBUG_ECHO_START SERIAL_ECHO_START
|
||||
#define DEBUG_ERROR_START SERIAL_ERROR_START
|
||||
#define DEBUG_CHAR SERIAL_CHAR
|
||||
|
@ -66,6 +67,7 @@
|
|||
#define DEBUG_XYZ SERIAL_XYZ
|
||||
#define DEBUG_DELAY(ms) serial_delay(ms)
|
||||
#else
|
||||
#define DEBUG_PRINT_P(P) NOOP
|
||||
#define DEBUG_ECHO_START() NOOP
|
||||
#define DEBUG_ERROR_START() NOOP
|
||||
#define DEBUG_CHAR(...) NOOP
|
||||
|
|
|
@ -65,20 +65,45 @@
|
|||
|
||||
#define AXIS_DRIVER_TYPE(A,T) AXIS_DRIVER_TYPE_##A(T)
|
||||
|
||||
#define HAS_DRIVER(T) (AXIS_DRIVER_TYPE_X(T) || AXIS_DRIVER_TYPE_X2(T) || \
|
||||
AXIS_DRIVER_TYPE_Y(T) || AXIS_DRIVER_TYPE_Y2(T) || \
|
||||
AXIS_DRIVER_TYPE_Z(T) || AXIS_DRIVER_TYPE_Z2(T) || AXIS_DRIVER_TYPE_Z3(T) || \
|
||||
AXIS_DRIVER_TYPE_E0(T) || AXIS_DRIVER_TYPE_E1(T) || \
|
||||
AXIS_DRIVER_TYPE_E2(T) || AXIS_DRIVER_TYPE_E3(T) || \
|
||||
AXIS_DRIVER_TYPE_E4(T) || AXIS_DRIVER_TYPE_E5(T) )
|
||||
#define HAS_DRIVER(T) ( AXIS_DRIVER_TYPE_X(T) || AXIS_DRIVER_TYPE_X2(T) \
|
||||
|| AXIS_DRIVER_TYPE_Y(T) || AXIS_DRIVER_TYPE_Y2(T) \
|
||||
|| AXIS_DRIVER_TYPE_Z(T) || AXIS_DRIVER_TYPE_Z2(T) || AXIS_DRIVER_TYPE_Z3(T) \
|
||||
|| AXIS_DRIVER_TYPE_E0(T) || AXIS_DRIVER_TYPE_E1(T) \
|
||||
|| AXIS_DRIVER_TYPE_E2(T) || AXIS_DRIVER_TYPE_E3(T) \
|
||||
|| AXIS_DRIVER_TYPE_E4(T) || AXIS_DRIVER_TYPE_E5(T) )
|
||||
|
||||
// Test for supported TMC drivers that require advanced configuration
|
||||
// Does not match standalone configurations
|
||||
#define HAS_TRINAMIC ( HAS_DRIVER(TMC2130) || HAS_DRIVER(TMC2160) || HAS_DRIVER(TMC2208) || HAS_DRIVER(TMC2660) || HAS_DRIVER(TMC5130) || HAS_DRIVER(TMC5160) )
|
||||
#define HAS_TRINAMIC ( HAS_DRIVER(TMC2130) \
|
||||
|| HAS_DRIVER(TMC2160) \
|
||||
|| HAS_DRIVER(TMC2208) \
|
||||
|| HAS_DRIVER(TMC2660) \
|
||||
|| HAS_DRIVER(TMC5130) \
|
||||
|| HAS_DRIVER(TMC5160) )
|
||||
|
||||
#define AXIS_IS_TMC(A) ( AXIS_DRIVER_TYPE_##A(TMC2130) || \
|
||||
AXIS_DRIVER_TYPE_##A(TMC2160) || \
|
||||
AXIS_DRIVER_TYPE_##A(TMC2208) || \
|
||||
AXIS_DRIVER_TYPE_##A(TMC2660) || \
|
||||
AXIS_DRIVER_TYPE_##A(TMC5130) || \
|
||||
AXIS_DRIVER_TYPE_##A(TMC5160))
|
||||
#define AXIS_IS_TMC(A) ( AXIS_DRIVER_TYPE(A,TMC2130) \
|
||||
|| AXIS_DRIVER_TYPE(A,TMC2160) \
|
||||
|| AXIS_DRIVER_TYPE(A,TMC2208) \
|
||||
|| AXIS_DRIVER_TYPE(A,TMC2660) \
|
||||
|| AXIS_DRIVER_TYPE(A,TMC5130) \
|
||||
|| AXIS_DRIVER_TYPE(A,TMC5160) )
|
||||
|
||||
// Test for a driver that uses SPI - this allows checking whether a _CS_ pin
|
||||
// is considered sensitive
|
||||
#define AXIS_HAS_SPI(A) ( AXIS_DRIVER_TYPE(A,TMC2130) \
|
||||
|| AXIS_DRIVER_TYPE(A,TMC2160) \
|
||||
|| AXIS_DRIVER_TYPE(A,TMC2660) \
|
||||
|| AXIS_DRIVER_TYPE(A,TMC5130) \
|
||||
|| AXIS_DRIVER_TYPE(A,TMC5160) )
|
||||
|
||||
#define AXIS_HAS_STALLGUARD(A) ( AXIS_DRIVER_TYPE(A,TMC2130) \
|
||||
|| AXIS_DRIVER_TYPE(A,TMC2160) \
|
||||
|| AXIS_DRIVER_TYPE(A,TMC2660) \
|
||||
|| AXIS_DRIVER_TYPE(A,TMC5130) \
|
||||
|| AXIS_DRIVER_TYPE(A,TMC5160) )
|
||||
|
||||
#define AXIS_HAS_STEALTHCHOP(A) ( AXIS_DRIVER_TYPE(A,TMC2130) \
|
||||
|| AXIS_DRIVER_TYPE(A,TMC2160) \
|
||||
|| AXIS_DRIVER_TYPE(A,TMC2208) \
|
||||
|| AXIS_DRIVER_TYPE(A,TMC5130) \
|
||||
|| AXIS_DRIVER_TYPE(A,TMC5160) )
|
||||
|
|
|
@ -39,6 +39,12 @@ enum AxisEnum : unsigned char {
|
|||
X_HEAD = 4,
|
||||
Y_HEAD = 5,
|
||||
Z_HEAD = 6,
|
||||
E0_AXIS = 3,
|
||||
E1_AXIS = 4,
|
||||
E2_AXIS = 5,
|
||||
E3_AXIS = 6,
|
||||
E4_AXIS = 7,
|
||||
E5_AXIS = 8,
|
||||
ALL_AXES = 0xFE,
|
||||
NO_AXIS = 0xFF
|
||||
};
|
||||
|
|
|
@ -22,6 +22,7 @@
|
|||
|
||||
#include "serial.h"
|
||||
#include "language.h"
|
||||
#include "enum.h"
|
||||
|
||||
uint8_t marlin_debug_flags = MARLIN_DEBUG_NONE;
|
||||
|
||||
|
@ -49,8 +50,14 @@ void serial_echopair_PGM(PGM_P const s_P, unsigned long v) { serialprintPGM(s_P)
|
|||
|
||||
void serial_spaces(uint8_t count) { count *= (PROPORTIONAL_FONT_RATIO); while (count--) SERIAL_CHAR(' '); }
|
||||
|
||||
void serial_ternary(const bool onoff, PGM_P const pre, PGM_P const on, PGM_P const off, PGM_P const post/*=NULL*/) {
|
||||
if (pre) serialprintPGM(pre);
|
||||
serialprintPGM(onoff ? on : off);
|
||||
if (post) serialprintPGM(post);
|
||||
}
|
||||
void serialprint_onoff(const bool onoff) { serialprintPGM(onoff ? PSTR(MSG_ON) : PSTR(MSG_OFF)); }
|
||||
void serialprintln_onoff(const bool onoff) { serialprint_onoff(onoff); SERIAL_EOL(); }
|
||||
void serialprint_truefalse(const bool tf) { serialprintPGM(tf ? PSTR("true") : PSTR("false")); }
|
||||
|
||||
void print_bin(const uint16_t val) {
|
||||
uint16_t mask = 0x8000;
|
||||
|
@ -61,10 +68,6 @@ void print_bin(const uint16_t val) {
|
|||
}
|
||||
}
|
||||
|
||||
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||
|
||||
#include "enum.h"
|
||||
|
||||
void print_xyz(PGM_P const prefix, PGM_P const suffix, const float x, const float y, const float z) {
|
||||
serialprintPGM(prefix);
|
||||
SERIAL_CHAR('(');
|
||||
|
@ -77,5 +80,3 @@ void print_bin(const uint16_t val) {
|
|||
void print_xyz(PGM_P const prefix, PGM_P const suffix, const float xyz[]) {
|
||||
print_xyz(prefix, suffix, xyz[X_AXIS], xyz[Y_AXIS], xyz[Z_AXIS]);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -174,18 +174,15 @@ inline void serial_echopair_PGM(PGM_P const s_P, void *v) { serial_echopair_PG
|
|||
void serialprintPGM(PGM_P str);
|
||||
void serial_echo_start();
|
||||
void serial_error_start();
|
||||
void serial_ternary(const bool onoff, PGM_P const pre, PGM_P const on, PGM_P const off, PGM_P const post=NULL);
|
||||
void serialprint_onoff(const bool onoff);
|
||||
void serialprintln_onoff(const bool onoff);
|
||||
void serialprint_truefalse(const bool tf);
|
||||
void serial_spaces(uint8_t count);
|
||||
|
||||
void print_bin(const uint16_t val);
|
||||
|
||||
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||
void print_xyz(PGM_P const prefix, PGM_P const suffix, const float x, const float y, const float z);
|
||||
void print_xyz(PGM_P const prefix, PGM_P const suffix, const float xyz[]);
|
||||
#define SERIAL_POS(SUFFIX,VAR) do { print_xyz(PSTR(" " STRINGIFY(VAR) "="), PSTR(" : " SUFFIX "\n"), VAR); } while(0)
|
||||
#define SERIAL_XYZ(PREFIX,...) do { print_xyz(PSTR(PREFIX), NULL, __VA_ARGS__); } while(0)
|
||||
#else
|
||||
#define SERIAL_POS(...) NOOP
|
||||
#define SERIAL_XYZ(...) NOOP
|
||||
#endif
|
||||
|
|
|
@ -58,11 +58,11 @@ void safe_delay(millis_t ms) {
|
|||
#define MINUSOR(n, alt) (n >= 0 ? (alt) : (n = -n, '-'))
|
||||
|
||||
// Convert a full-range unsigned 8bit int to a percentage
|
||||
char* ui8tostr_percent(const uint8_t i) {
|
||||
const uint8_t percent = ui8_to_percent(i);
|
||||
conv[3] = RJDIGIT(percent, 100);
|
||||
conv[4] = RJDIGIT(percent, 10);
|
||||
conv[5] = DIGIMOD(percent, 1);
|
||||
char* ui8tostr4pct(const uint8_t i) {
|
||||
const uint8_t n = ui8_to_percent(i);
|
||||
conv[3] = RJDIGIT(n, 100);
|
||||
conv[4] = RJDIGIT(n, 10);
|
||||
conv[5] = DIGIMOD(n, 1);
|
||||
conv[6] = '%';
|
||||
return &conv[3];
|
||||
}
|
||||
|
@ -214,6 +214,19 @@ void safe_delay(millis_t ms) {
|
|||
return &conv[1];
|
||||
}
|
||||
|
||||
// Convert signed float to string (5 digit) with -1.2345 / _0.0000 / +1.2345 format
|
||||
char* ftostr54sign(const float &f, char plus/*=' '*/) {
|
||||
long i = (f * 100000 + (f < 0 ? -5: 5)) / 10;
|
||||
conv[0] = i ? MINUSOR(i, plus) : ' ';
|
||||
conv[1] = DIGIMOD(i, 10000);
|
||||
conv[2] = '.';
|
||||
conv[3] = DIGIMOD(i, 1000);
|
||||
conv[4] = DIGIMOD(i, 100);
|
||||
conv[5] = DIGIMOD(i, 10);
|
||||
conv[6] = DIGIMOD(i, 1);
|
||||
return &conv[0];
|
||||
}
|
||||
|
||||
// Convert unsigned float to rj string with 12345 format
|
||||
char* ftostr5rj(const float &f) {
|
||||
const long i = ((f < 0 ? -f : f) * 10 + 5) / 10;
|
||||
|
|
|
@ -56,7 +56,7 @@ inline void serial_delay(const millis_t ms) {
|
|||
#if ANY(ULTRA_LCD, DEBUG_LEVELING_FEATURE, EXTENSIBLE_UI)
|
||||
|
||||
// Convert a full-range unsigned 8bit int to a percentage
|
||||
char* ui8tostr_percent(const uint8_t i);
|
||||
char* ui8tostr4pct(const uint8_t i);
|
||||
|
||||
// Convert uint8_t to string with 123 format
|
||||
char* ui8tostr3(const uint8_t x);
|
||||
|
@ -91,6 +91,9 @@ inline void serial_delay(const millis_t ms) {
|
|||
// Convert signed float to string (6 digit) with -1.234 / _0.000 / +1.234 format
|
||||
char* ftostr43sign(const float &x, char plus=' ');
|
||||
|
||||
// Convert signed float to string (5 digit) with -1.2345 / _0.0000 / +1.2345 format
|
||||
char* ftostr54sign(const float &x, char plus=' ');
|
||||
|
||||
// Convert unsigned float to rj string with 12345 format
|
||||
char* ftostr5rj(const float &x);
|
||||
|
||||
|
|
|
@ -38,6 +38,8 @@
|
|||
#include "../module/stepper.h"
|
||||
#include "../gcode/parser.h"
|
||||
|
||||
#include "../feature/babystep.h"
|
||||
|
||||
#include <Wire.h>
|
||||
|
||||
void I2CPositionEncoder::init(const uint8_t address, const AxisEnum axis) {
|
||||
|
@ -169,7 +171,7 @@ void I2CPositionEncoder::update() {
|
|||
const int32_t errorP = int32_t(sumP * (1.0f / (I2CPE_ERR_PRST_ARRAY_SIZE)));
|
||||
SERIAL_ECHO(axis_codes[encoderAxis]);
|
||||
SERIAL_ECHOLNPAIR(" - err detected: ", errorP * planner.steps_to_mm[encoderAxis], "mm; correcting!");
|
||||
thermalManager.babystepsTodo[encoderAxis] = -LROUND(errorP);
|
||||
babystep.add_steps(encoderAxis, -LROUND(errorP));
|
||||
errPrstIdx = 0;
|
||||
}
|
||||
}
|
||||
|
@ -180,7 +182,7 @@ void I2CPositionEncoder::update() {
|
|||
if (ABS(error) > threshold * planner.settings.axis_steps_per_mm[encoderAxis]) {
|
||||
//SERIAL_ECHOLN(error);
|
||||
//SERIAL_ECHOLN(position);
|
||||
thermalManager.babystepsTodo[encoderAxis] = -LROUND(error / 2);
|
||||
babystep.add_steps(encoderAxis, -LROUND(error / 2));
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -227,13 +229,11 @@ bool I2CPositionEncoder::passes_test(const bool report) {
|
|||
if (report) {
|
||||
if (H != I2CPE_MAG_SIG_GOOD) SERIAL_ECHOPGM("Warning. ");
|
||||
SERIAL_ECHO(axis_codes[encoderAxis]);
|
||||
SERIAL_ECHOPGM(" axis ");
|
||||
serialprintPGM(H == I2CPE_MAG_SIG_BAD ? PSTR("magnetic strip ") : PSTR("encoder "));
|
||||
serial_ternary(H == I2CPE_MAG_SIG_BAD, PSTR(" axis "), PSTR("magnetic strip "), PSTR("encoder "));
|
||||
switch (H) {
|
||||
case I2CPE_MAG_SIG_GOOD:
|
||||
case I2CPE_MAG_SIG_MID:
|
||||
SERIAL_ECHOLNPGM("passes test; field strength ");
|
||||
serialprintPGM(H == I2CPE_MAG_SIG_GOOD ? PSTR("good.\n") : PSTR("fair.\n"));
|
||||
serial_ternary(H == I2CPE_MAG_SIG_GOOD, PSTR("passes test; field strength "), PSTR("good"), PSTR("fair"), PSTR(".\n"));
|
||||
break;
|
||||
default:
|
||||
SERIAL_ECHOLNPGM("not detected!");
|
||||
|
|
|
@ -275,9 +275,8 @@ class I2CPositionEncodersMgr {
|
|||
static void enable_ec(const int8_t idx, const bool enabled, const AxisEnum axis) {
|
||||
CHECK_IDX();
|
||||
encoders[idx].set_ec_enabled(enabled);
|
||||
SERIAL_ECHOPAIR("Error correction on ", axis_codes[axis], " axis is ");
|
||||
serialprintPGM(encoders[idx].get_ec_enabled() ? PSTR("en") : PSTR("dis"));
|
||||
SERIAL_ECHOLNPGM("abled.");
|
||||
SERIAL_ECHOPAIR("Error correction on ", axis_codes[axis]);
|
||||
serial_ternary(encoders[idx].get_ec_enabled(), PSTR(" axis is "), PSTR("en"), PSTR("dis"), PSTR("abled.\n"));
|
||||
}
|
||||
|
||||
static void set_ec_threshold(const int8_t idx, const float newThreshold, const AxisEnum axis) {
|
||||
|
|
135
Marlin/src/feature/babystep.cpp
Normal file
135
Marlin/src/feature/babystep.cpp
Normal file
|
@ -0,0 +1,135 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2019 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 "../inc/MarlinConfig.h"
|
||||
|
||||
#if ENABLED(BABYSTEPPING)
|
||||
|
||||
#include "babystep.h"
|
||||
#include "../Marlin.h"
|
||||
#include "../module/planner.h"
|
||||
#include "../module/stepper.h"
|
||||
|
||||
#if ENABLED(BABYSTEP_ALWAYS_AVAILABLE)
|
||||
#include "../gcode/gcode.h"
|
||||
#endif
|
||||
|
||||
Babystep babystep;
|
||||
|
||||
volatile int16_t Babystep::todo[BS_TODO_AXIS(Z_AXIS) + 1];
|
||||
|
||||
#if HAS_LCD_MENU
|
||||
int16_t Babystep::accum;
|
||||
#if ENABLED(BABYSTEP_DISPLAY_TOTAL)
|
||||
int16_t Babystep::axis_total[BS_TOTAL_AXIS(Z_AXIS) + 1];
|
||||
#endif
|
||||
#endif
|
||||
|
||||
void Babystep::step_axis(const AxisEnum axis) {
|
||||
const int16_t curTodo = todo[BS_TODO_AXIS(axis)]; // get rid of volatile for performance
|
||||
if (curTodo) {
|
||||
stepper.babystep((AxisEnum)axis, curTodo > 0);
|
||||
if (curTodo > 0) todo[BS_TODO_AXIS(axis)]--; else todo[BS_TODO_AXIS(axis)]++;
|
||||
}
|
||||
}
|
||||
|
||||
void Babystep::task() {
|
||||
#if EITHER(BABYSTEP_XY, I2C_POSITION_ENCODERS)
|
||||
LOOP_XYZ(axis) step_axis((AxisEnum)axis);
|
||||
#else
|
||||
step_axis(Z_AXIS);
|
||||
#endif
|
||||
}
|
||||
|
||||
void Babystep::add_mm(const AxisEnum axis, const float &mm) {
|
||||
add_steps(axis, mm * planner.settings.axis_steps_per_mm[axis]);
|
||||
}
|
||||
|
||||
void Babystep::add_steps(const AxisEnum axis, const int32_t distance) {
|
||||
|
||||
#if ENABLED(BABYSTEP_WITHOUT_HOMING)
|
||||
#define CAN_BABYSTEP(AXIS) true
|
||||
#else
|
||||
extern uint8_t axis_known_position;
|
||||
#define CAN_BABYSTEP(AXIS) TEST(axis_known_position, AXIS)
|
||||
#endif
|
||||
|
||||
if (!CAN_BABYSTEP(axis)) return;
|
||||
|
||||
#if HAS_LCD_MENU
|
||||
accum += distance; // Count up babysteps for the UI
|
||||
#if ENABLED(BABYSTEP_DISPLAY_TOTAL)
|
||||
axis_total[BS_TOTAL_AXIS(axis)] += distance;
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if ENABLED(BABYSTEP_ALWAYS_AVAILABLE)
|
||||
#define BSA_ENABLE(AXIS) do{ switch (AXIS) { case X_AXIS: enable_X(); break; case Y_AXIS: enable_Y(); break; case Z_AXIS: enable_Z(); } }while(0)
|
||||
#else
|
||||
#define BSA_ENABLE(AXIS) NOOP
|
||||
#endif
|
||||
|
||||
#if IS_CORE
|
||||
#if ENABLED(BABYSTEP_XY)
|
||||
switch (axis) {
|
||||
case CORE_AXIS_1: // X on CoreXY and CoreXZ, Y on CoreYZ
|
||||
BSA_ENABLE(CORE_AXIS_1);
|
||||
BSA_ENABLE(CORE_AXIS_2);
|
||||
todo[CORE_AXIS_1] += distance * 2;
|
||||
todo[CORE_AXIS_2] += distance * 2;
|
||||
break;
|
||||
case CORE_AXIS_2: // Y on CoreXY, Z on CoreXZ and CoreYZ
|
||||
BSA_ENABLE(CORE_AXIS_1);
|
||||
BSA_ENABLE(CORE_AXIS_2);
|
||||
todo[CORE_AXIS_1] += CORESIGN(distance * 2);
|
||||
todo[CORE_AXIS_2] -= CORESIGN(distance * 2);
|
||||
break;
|
||||
case NORMAL_AXIS: // Z on CoreXY, Y on CoreXZ, X on CoreYZ
|
||||
default:
|
||||
BSA_ENABLE(NORMAL_AXIS);
|
||||
todo[NORMAL_AXIS] += distance;
|
||||
break;
|
||||
}
|
||||
#elif CORE_IS_XZ || CORE_IS_YZ
|
||||
// Only Z stepping needs to be handled here
|
||||
BSA_ENABLE(CORE_AXIS_1);
|
||||
BSA_ENABLE(CORE_AXIS_2);
|
||||
todo[CORE_AXIS_1] += CORESIGN(distance * 2);
|
||||
todo[CORE_AXIS_2] -= CORESIGN(distance * 2);
|
||||
#else
|
||||
BSA_ENABLE(Z_AXIS);
|
||||
todo[Z_AXIS] += distance;
|
||||
#endif
|
||||
#else
|
||||
#if ENABLED(BABYSTEP_XY)
|
||||
BSA_ENABLE(axis);
|
||||
#else
|
||||
BSA_ENABLE(Z_AXIS);
|
||||
#endif
|
||||
todo[BS_TODO_AXIS(axis)] += distance;
|
||||
#endif
|
||||
#if ENABLED(BABYSTEP_ALWAYS_AVAILABLE)
|
||||
gcode.reset_stepper_timeout();
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif // BABYSTEPPING
|
63
Marlin/src/feature/babystep.h
Normal file
63
Marlin/src/feature/babystep.h
Normal file
|
@ -0,0 +1,63 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2019 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/MarlinConfigPre.h"
|
||||
#include "../core/enum.h"
|
||||
|
||||
#if IS_CORE || EITHER(BABYSTEP_XY, I2C_POSITION_ENCODERS)
|
||||
#define BS_TODO_AXIS(A) A
|
||||
#else
|
||||
#define BS_TODO_AXIS(A) 0
|
||||
#endif
|
||||
|
||||
#if HAS_LCD_MENU && ENABLED(BABYSTEP_DISPLAY_TOTAL)
|
||||
#if ENABLED(BABYSTEP_XY)
|
||||
#define BS_TOTAL_AXIS(A) A
|
||||
#else
|
||||
#define BS_TOTAL_AXIS(A) 0
|
||||
#endif
|
||||
#endif
|
||||
|
||||
class Babystep {
|
||||
public:
|
||||
static volatile int16_t todo[BS_TODO_AXIS(Z_AXIS) + 1];
|
||||
#if HAS_LCD_MENU
|
||||
static int16_t accum; // Total babysteps in current edit
|
||||
#if ENABLED(BABYSTEP_DISPLAY_TOTAL)
|
||||
static int16_t axis_total[BS_TOTAL_AXIS(Z_AXIS) + 1]; // Total babysteps since G28
|
||||
static inline void reset_total(const AxisEnum axis) {
|
||||
#if ENABLED(BABYSTEP_XY)
|
||||
if (axis == Z_AXIS)
|
||||
#endif
|
||||
axis_total[BS_TOTAL_AXIS(axis)] = 0;
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
static void add_steps(const AxisEnum axis, const int32_t distance);
|
||||
static void add_mm(const AxisEnum axis, const float &mm);
|
||||
static void task();
|
||||
private:
|
||||
static void step_axis(const AxisEnum axis);
|
||||
};
|
||||
|
||||
extern Babystep babystep;
|
|
@ -42,10 +42,6 @@
|
|||
#define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE)
|
||||
#include "../../core/debug_out.h"
|
||||
|
||||
#if ENABLED(G26_MESH_VALIDATION)
|
||||
bool g26_debug_flag; // = false
|
||||
#endif
|
||||
|
||||
bool leveling_is_valid() {
|
||||
return
|
||||
#if ENABLED(MESH_BED_LEVELING)
|
||||
|
|
|
@ -28,12 +28,6 @@ typedef struct {
|
|||
float distance; // When populated, the distance from the search location
|
||||
} mesh_index_pair;
|
||||
|
||||
#if ENABLED(G26_MESH_VALIDATION)
|
||||
extern bool g26_debug_flag;
|
||||
#else
|
||||
constexpr bool g26_debug_flag = false;
|
||||
#endif
|
||||
|
||||
#if ENABLED(PROBE_MANUALLY)
|
||||
extern bool g29_in_progress;
|
||||
#else
|
||||
|
|
|
@ -58,54 +58,10 @@
|
|||
|
||||
void unified_bed_leveling::report_state() {
|
||||
echo_name();
|
||||
SERIAL_ECHOPGM(" System v" UBL_VERSION " ");
|
||||
if (!planner.leveling_active) SERIAL_ECHOPGM("in");
|
||||
SERIAL_ECHOLNPGM("active.");
|
||||
serial_ternary(planner.leveling_active, PSTR(" System v" UBL_VERSION " "), PSTR(""), PSTR("in"), PSTR("active\n"));
|
||||
serial_delay(50);
|
||||
}
|
||||
|
||||
#if ENABLED(UBL_DEVEL_DEBUGGING)
|
||||
|
||||
static void debug_echo_axis(const AxisEnum axis) {
|
||||
if (current_position[axis] == destination[axis])
|
||||
SERIAL_ECHOPGM("-------------");
|
||||
else
|
||||
SERIAL_ECHO_F(destination[X_AXIS], 6);
|
||||
}
|
||||
|
||||
void debug_current_and_destination(PGM_P title) {
|
||||
|
||||
// if the title message starts with a '!' it is so important, we are going to
|
||||
// ignore the status of the g26_debug_flag
|
||||
if (*title != '!' && !g26_debug_flag) return;
|
||||
|
||||
const float de = destination[E_AXIS] - current_position[E_AXIS];
|
||||
|
||||
if (de == 0.0) return; // Printing moves only
|
||||
|
||||
const float dx = destination[X_AXIS] - current_position[X_AXIS],
|
||||
dy = destination[Y_AXIS] - current_position[Y_AXIS],
|
||||
xy_dist = HYPOT(dx, dy);
|
||||
|
||||
if (xy_dist == 0.0) return;
|
||||
|
||||
const float fpmm = de / xy_dist;
|
||||
SERIAL_ECHOPAIR_F(" fpmm=", fpmm, 6);
|
||||
SERIAL_ECHOPAIR_F(" current=( ", current_position[X_AXIS], 6);
|
||||
SERIAL_ECHOPAIR_F(", ", current_position[Y_AXIS], 6);
|
||||
SERIAL_ECHOPAIR_F(", ", current_position[Z_AXIS], 6);
|
||||
SERIAL_ECHOPAIR_F(", ", current_position[E_AXIS], 6);
|
||||
SERIAL_ECHOPGM(" ) destination=( "); debug_echo_axis(X_AXIS);
|
||||
SERIAL_ECHOPGM(", "); debug_echo_axis(Y_AXIS);
|
||||
SERIAL_ECHOPGM(", "); debug_echo_axis(Z_AXIS);
|
||||
SERIAL_ECHOPGM(", "); debug_echo_axis(E_AXIS);
|
||||
SERIAL_ECHOPGM(" ) ");
|
||||
serialprintPGM(title);
|
||||
SERIAL_EOL();
|
||||
}
|
||||
|
||||
#endif // UBL_DEVEL_DEBUGGING
|
||||
|
||||
int8_t unified_bed_leveling::storage_slot;
|
||||
|
||||
float unified_bed_leveling::z_values[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y];
|
||||
|
|
|
@ -39,14 +39,6 @@
|
|||
#define USE_NOZZLE_AS_REFERENCE 0
|
||||
#define USE_PROBE_AS_REFERENCE 1
|
||||
|
||||
// ubl_motion.cpp
|
||||
|
||||
#if ENABLED(UBL_DEVEL_DEBUGGING)
|
||||
void debug_current_and_destination(PGM_P const title);
|
||||
#else
|
||||
FORCE_INLINE void debug_current_and_destination(PGM_P const title) { UNUSED(title); }
|
||||
#endif
|
||||
|
||||
// ubl_G29.cpp
|
||||
|
||||
enum MeshPointType : char { INVALID, REAL, SET_IN_BITMAP };
|
||||
|
|
|
@ -24,8 +24,6 @@
|
|||
|
||||
#if ENABLED(AUTO_BED_LEVELING_UBL)
|
||||
|
||||
//#define UBL_DEVEL_DEBUGGING
|
||||
|
||||
#include "ubl.h"
|
||||
|
||||
#include "../../../Marlin.h"
|
||||
|
@ -765,14 +763,12 @@
|
|||
|
||||
if (location.x_index >= 0) { // mesh point found and is reachable by probe
|
||||
const float rawx = mesh_index_to_xpos(location.x_index),
|
||||
rawy = mesh_index_to_ypos(location.y_index);
|
||||
|
||||
const float measured_z = probe_pt(rawx, rawy, stow_probe ? PROBE_PT_STOW : PROBE_PT_RAISE, g29_verbose_level); // TODO: Needs error handling
|
||||
rawy = mesh_index_to_ypos(location.y_index),
|
||||
measured_z = probe_pt(rawx, rawy, stow_probe ? PROBE_PT_STOW : PROBE_PT_RAISE, g29_verbose_level); // TODO: Needs error handling
|
||||
z_values[location.x_index][location.y_index] = measured_z;
|
||||
#if ENABLED(EXTENSIBLE_UI)
|
||||
ExtUI::onMeshUpdate(location.x_index, location.y_index, measured_z);
|
||||
#endif
|
||||
|
||||
}
|
||||
SERIAL_FLUSH(); // Prevent host M105 buffer overrun.
|
||||
} while (location.x_index >= 0 && --count);
|
||||
|
|
|
@ -64,17 +64,6 @@
|
|||
cell_dest_xi = get_cell_index_x(end[X_AXIS]),
|
||||
cell_dest_yi = get_cell_index_y(end[Y_AXIS]);
|
||||
|
||||
if (g26_debug_flag) {
|
||||
SERIAL_ECHOLNPAIR(
|
||||
" ubl.line_to_destination_cartesian(xe=", destination[X_AXIS],
|
||||
", ye=", destination[Y_AXIS],
|
||||
", ze=", destination[Z_AXIS],
|
||||
", ee=", destination[E_AXIS],
|
||||
")"
|
||||
);
|
||||
debug_current_and_destination(PSTR("Start of ubl.line_to_destination_cartesian()"));
|
||||
}
|
||||
|
||||
// A move within the same cell needs no splitting
|
||||
if (cell_start_xi == cell_dest_xi && cell_start_yi == cell_dest_yi) {
|
||||
|
||||
|
@ -93,9 +82,6 @@
|
|||
planner.buffer_segment(end[X_AXIS], end[Y_AXIS], end[Z_AXIS] + z_raise, end[E_AXIS], feed_rate, extruder);
|
||||
set_current_from_destination();
|
||||
|
||||
if (g26_debug_flag)
|
||||
debug_current_and_destination(PSTR("out of bounds in ubl.line_to_destination_cartesian()"));
|
||||
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -119,9 +105,6 @@
|
|||
// Replace NAN corrections with 0.0 to prevent NAN propagation.
|
||||
planner.buffer_segment(end[X_AXIS], end[Y_AXIS], end[Z_AXIS] + (isnan(z0) ? 0.0 : z0), end[E_AXIS], feed_rate, extruder);
|
||||
|
||||
if (g26_debug_flag)
|
||||
debug_current_and_destination(PSTR("FINAL_MOVE in ubl.line_to_destination_cartesian()"));
|
||||
|
||||
set_current_from_destination();
|
||||
return;
|
||||
}
|
||||
|
@ -215,9 +198,6 @@
|
|||
} //else printf("FIRST MOVE PRUNED ");
|
||||
}
|
||||
|
||||
if (g26_debug_flag)
|
||||
debug_current_and_destination(PSTR("vertical move done in ubl.line_to_destination_cartesian()"));
|
||||
|
||||
// At the final destination? Usually not, but when on a Y Mesh Line it's completed.
|
||||
if (current_position[X_AXIS] != end[X_AXIS] || current_position[Y_AXIS] != end[Y_AXIS])
|
||||
goto FINAL_MOVE;
|
||||
|
@ -267,9 +247,6 @@
|
|||
} //else printf("FIRST MOVE PRUNED ");
|
||||
}
|
||||
|
||||
if (g26_debug_flag)
|
||||
debug_current_and_destination(PSTR("horizontal move done in ubl.line_to_destination_cartesian()"));
|
||||
|
||||
if (current_position[X_AXIS] != end[X_AXIS] || current_position[Y_AXIS] != end[Y_AXIS])
|
||||
goto FINAL_MOVE;
|
||||
|
||||
|
@ -353,9 +330,6 @@
|
|||
if (xi_cnt < 0 || yi_cnt < 0) break; // Too far! Exit the loop and go to FINAL_MOVE
|
||||
}
|
||||
|
||||
if (g26_debug_flag)
|
||||
debug_current_and_destination(PSTR("generic move done in ubl.line_to_destination_cartesian()"));
|
||||
|
||||
if (current_position[X_AXIS] != end[X_AXIS] || current_position[Y_AXIS] != end[Y_AXIS])
|
||||
goto FINAL_MOVE;
|
||||
|
||||
|
|
|
@ -35,6 +35,9 @@
|
|||
#if MB(5DPRINT)
|
||||
#define DIGIPOT_I2C_FACTOR 117.96
|
||||
#define DIGIPOT_I2C_MAX_CURRENT 1.736
|
||||
#elif MB(AZTEEG_X5_MINI) || MB(AZTEEG_X5_MINI_WIFI)
|
||||
#define DIGIPOT_I2C_FACTOR 113.5
|
||||
#define DIGIPOT_I2C_MAX_CURRENT 2.0
|
||||
#else
|
||||
#define DIGIPOT_I2C_FACTOR 106.7
|
||||
#define DIGIPOT_I2C_MAX_CURRENT 2.5
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
|
|
|
@ -120,19 +120,28 @@ typedef struct LEDColor {
|
|||
#else
|
||||
#define MakeLEDColor(R,G,B,W,I) LEDColor(R, G, B, W)
|
||||
#endif
|
||||
#define LEDColorWhite() LEDColor(0, 0, 0, 255)
|
||||
#else
|
||||
#define MakeLEDColor(R,G,B,W,I) LEDColor(R, G, B)
|
||||
#define LEDColorWhite() LEDColor(255, 255, 255)
|
||||
#endif
|
||||
|
||||
#define LEDColorOff() LEDColor( 0, 0, 0)
|
||||
#define LEDColorRed() LEDColor(255, 0, 0)
|
||||
#if ENABLED(LED_COLORS_REDUCE_GREEN)
|
||||
#define LEDColorOrange() LEDColor(255, 25, 0)
|
||||
#define LEDColorYellow() LEDColor(255, 75, 0)
|
||||
#else
|
||||
#define LEDColorOrange() LEDColor(255, 80, 0)
|
||||
#define LEDColorYellow() LEDColor(255, 255, 0)
|
||||
#endif
|
||||
#define LEDColorGreen() LEDColor( 0, 255, 0)
|
||||
#define LEDColorBlue() LEDColor( 0, 0, 255)
|
||||
#define LEDColorIndigo() LEDColor( 0, 255, 255)
|
||||
#define LEDColorViolet() LEDColor(255, 0, 255)
|
||||
#if HAS_WHITE_LED
|
||||
#define LEDColorWhite() LEDColor( 0, 0, 0, 255)
|
||||
#else
|
||||
#define LEDColorWhite() LEDColor(255, 255, 255)
|
||||
#endif
|
||||
|
||||
class LEDLights {
|
||||
public:
|
||||
|
|
|
@ -50,6 +50,9 @@ job_recovery_info_t PrintJobRecovery::info;
|
|||
#include "fwretract.h"
|
||||
#endif
|
||||
|
||||
#define DEBUG_OUT ENABLED(DEBUG_POWER_LOSS_RECOVERY)
|
||||
#include "../core/debug_out.h"
|
||||
|
||||
PrintJobRecovery recovery;
|
||||
|
||||
/**
|
||||
|
@ -110,9 +113,7 @@ void PrintJobRecovery::load() {
|
|||
(void)file.read(&info, sizeof(info));
|
||||
close();
|
||||
}
|
||||
#if ENABLED(DEBUG_POWER_LOSS_RECOVERY)
|
||||
debug(PSTR("Load"));
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -125,6 +126,7 @@ void PrintJobRecovery::save(const bool force/*=false*/, const bool save_queue/*=
|
|||
millis_t ms = millis();
|
||||
#endif
|
||||
|
||||
// Did Z change since the last call?
|
||||
if (force
|
||||
#if DISABLED(SAVE_EACH_CMD_MODE) // Always save state when enabled
|
||||
#if PIN_EXISTS(POWER_LOSS) // Save if power loss pin is triggered
|
||||
|
@ -215,20 +217,14 @@ void PrintJobRecovery::save(const bool force/*=false*/, const bool save_queue/*=
|
|||
*/
|
||||
void PrintJobRecovery::write() {
|
||||
|
||||
#if ENABLED(DEBUG_POWER_LOSS_RECOVERY)
|
||||
debug(PSTR("Write"));
|
||||
#endif
|
||||
|
||||
open(false);
|
||||
file.seekSet(0);
|
||||
const int16_t ret = file.write(&info, sizeof(info));
|
||||
close();
|
||||
|
||||
#if ENABLED(DEBUG_POWER_LOSS_RECOVERY)
|
||||
if (ret == -1) SERIAL_ECHOLNPGM("Power-loss file write failed.");
|
||||
#else
|
||||
UNUSED(ret);
|
||||
#endif
|
||||
if (ret == -1) DEBUG_ECHOLNPGM("Power-loss file write failed.");
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -366,65 +362,65 @@ void PrintJobRecovery::resume() {
|
|||
#if ENABLED(DEBUG_POWER_LOSS_RECOVERY)
|
||||
|
||||
void PrintJobRecovery::debug(PGM_P const prefix) {
|
||||
serialprintPGM(prefix);
|
||||
SERIAL_ECHOLNPAIR(" Job Recovery Info...\nvalid_head:", int(info.valid_head), " valid_foot:", int(info.valid_foot));
|
||||
DEBUG_PRINT_P(prefix);
|
||||
DEBUG_ECHOLNPAIR(" Job Recovery Info...\nvalid_head:", int(info.valid_head), " valid_foot:", int(info.valid_foot));
|
||||
if (info.valid_head) {
|
||||
if (info.valid_head == info.valid_foot) {
|
||||
SERIAL_ECHOPGM("current_position: ");
|
||||
DEBUG_ECHOPGM("current_position: ");
|
||||
LOOP_XYZE(i) {
|
||||
SERIAL_ECHO(info.current_position[i]);
|
||||
if (i < E_AXIS) SERIAL_CHAR(',');
|
||||
if (i) DEBUG_CHAR(',');
|
||||
DEBUG_ECHO(info.current_position[i]);
|
||||
}
|
||||
SERIAL_EOL();
|
||||
SERIAL_ECHOLNPAIR("feedrate: ", info.feedrate);
|
||||
DEBUG_EOL();
|
||||
DEBUG_ECHOLNPAIR("feedrate: ", info.feedrate);
|
||||
|
||||
#if HOTENDS > 1
|
||||
SERIAL_ECHOLNPAIR("active_hotend: ", int(info.active_hotend));
|
||||
DEBUG_ECHOLNPAIR("active_hotend: ", int(info.active_hotend));
|
||||
#endif
|
||||
|
||||
SERIAL_ECHOPGM("target_temperature: ");
|
||||
DEBUG_ECHOPGM("target_temperature: ");
|
||||
HOTEND_LOOP() {
|
||||
SERIAL_ECHO(info.target_temperature[e]);
|
||||
if (e < HOTENDS - 1) SERIAL_CHAR(',');
|
||||
DEBUG_ECHO(info.target_temperature[e]);
|
||||
if (e < HOTENDS - 1) DEBUG_CHAR(',');
|
||||
}
|
||||
SERIAL_EOL();
|
||||
DEBUG_EOL();
|
||||
|
||||
#if HAS_HEATED_BED
|
||||
SERIAL_ECHOLNPAIR("target_temperature_bed: ", info.target_temperature_bed);
|
||||
DEBUG_ECHOLNPAIR("target_temperature_bed: ", info.target_temperature_bed);
|
||||
#endif
|
||||
|
||||
#if FAN_COUNT
|
||||
SERIAL_ECHOPGM("fan_speed: ");
|
||||
DEBUG_ECHOPGM("fan_speed: ");
|
||||
FANS_LOOP(i) {
|
||||
SERIAL_ECHO(int(info.fan_speed[i]));
|
||||
if (i < FAN_COUNT - 1) SERIAL_CHAR(',');
|
||||
DEBUG_ECHO(int(info.fan_speed[i]));
|
||||
if (i < FAN_COUNT - 1) DEBUG_CHAR(',');
|
||||
}
|
||||
SERIAL_EOL();
|
||||
DEBUG_EOL();
|
||||
#endif
|
||||
|
||||
#if HAS_LEVELING
|
||||
SERIAL_ECHOLNPAIR("leveling: ", int(info.leveling), "\n fade: ", int(info.fade));
|
||||
DEBUG_ECHOLNPAIR("leveling: ", int(info.leveling), "\n fade: ", int(info.fade));
|
||||
#endif
|
||||
#if ENABLED(FWRETRACT)
|
||||
SERIAL_ECHOPGM("retract: ");
|
||||
DEBUG_ECHOPGM("retract: ");
|
||||
for (int8_t e = 0; e < EXTRUDERS; e++) {
|
||||
SERIAL_ECHO(info.retract[e]);
|
||||
if (e < EXTRUDERS - 1) SERIAL_CHAR(',');
|
||||
DEBUG_ECHO(info.retract[e]);
|
||||
if (e < EXTRUDERS - 1) DEBUG_CHAR(',');
|
||||
}
|
||||
SERIAL_EOL();
|
||||
SERIAL_ECHOLNPAIR("retract_hop: ", info.retract_hop);
|
||||
DEBUG_EOL();
|
||||
DEBUG_ECHOLNPAIR("retract_hop: ", info.retract_hop);
|
||||
#endif
|
||||
SERIAL_ECHOLNPAIR("cmd_queue_index_r: ", int(info.cmd_queue_index_r));
|
||||
SERIAL_ECHOLNPAIR("commands_in_queue: ", int(info.commands_in_queue));
|
||||
for (uint8_t i = 0; i < info.commands_in_queue; i++) SERIAL_ECHOLNPAIR("> ", info.command_queue[i]);
|
||||
SERIAL_ECHOLNPAIR("sd_filename: ", info.sd_filename);
|
||||
SERIAL_ECHOLNPAIR("sdpos: ", info.sdpos);
|
||||
SERIAL_ECHOLNPAIR("print_job_elapsed: ", info.print_job_elapsed);
|
||||
DEBUG_ECHOLNPAIR("cmd_queue_index_r: ", int(info.cmd_queue_index_r));
|
||||
DEBUG_ECHOLNPAIR("commands_in_queue: ", int(info.commands_in_queue));
|
||||
for (uint8_t i = 0; i < info.commands_in_queue; i++) DEBUG_ECHOLNPAIR("> ", info.command_queue[i]);
|
||||
DEBUG_ECHOLNPAIR("sd_filename: ", info.sd_filename);
|
||||
DEBUG_ECHOLNPAIR("sdpos: ", info.sdpos);
|
||||
DEBUG_ECHOLNPAIR("print_job_elapsed: ", info.print_job_elapsed);
|
||||
}
|
||||
else
|
||||
SERIAL_ECHOLNPGM("INVALID DATA");
|
||||
DEBUG_ECHOLNPGM("INVALID DATA");
|
||||
}
|
||||
SERIAL_ECHOLNPGM("---");
|
||||
DEBUG_ECHOLNPGM("---");
|
||||
}
|
||||
|
||||
#endif // DEBUG_POWER_LOSS_RECOVERY
|
||||
|
|
|
@ -127,6 +127,8 @@ class PrintJobRecovery {
|
|||
|
||||
#if ENABLED(DEBUG_POWER_LOSS_RECOVERY)
|
||||
static void debug(PGM_P const prefix);
|
||||
#else
|
||||
static inline void debug(PGM_P const prefix) { UNUSED(prefix); }
|
||||
#endif
|
||||
|
||||
private:
|
||||
|
|
|
@ -90,7 +90,7 @@ bool MMU2::enabled, MMU2::ready, MMU2::mmu_print_saved;
|
|||
uint8_t MMU2::cmd, MMU2::cmd_arg, MMU2::last_cmd, MMU2::extruder;
|
||||
int8_t MMU2::state = 0;
|
||||
volatile int8_t MMU2::finda = 1;
|
||||
volatile bool MMU2::findaRunoutValid;
|
||||
volatile bool MMU2::finda_runout_valid;
|
||||
int16_t MMU2::version = -1, MMU2::buildnr = -1;
|
||||
millis_t MMU2::last_request, MMU2::next_P0_request;
|
||||
char MMU2::rx_buffer[16], MMU2::tx_buffer[16];
|
||||
|
@ -103,7 +103,7 @@ char MMU2::rx_buffer[16], MMU2::tx_buffer[16];
|
|||
};
|
||||
|
||||
static constexpr E_Step ramming_sequence[] PROGMEM = { MMU2_RAMMING_SEQUENCE };
|
||||
static constexpr E_Step loadToNozzle_sequence[] PROGMEM = { MMU2_LOAD_TO_NOZZLE_SEQUENCE };
|
||||
static constexpr E_Step load_to_nozzle_sequence[] PROGMEM = { MMU2_LOAD_TO_NOZZLE_SEQUENCE };
|
||||
|
||||
#endif // MMU2_MENUS
|
||||
|
||||
|
@ -142,11 +142,11 @@ void MMU2::reset() {
|
|||
#endif
|
||||
}
|
||||
|
||||
uint8_t MMU2::getCurrentTool() {
|
||||
uint8_t MMU2::get_current_tool() {
|
||||
return extruder == MMU2_NO_TOOL ? -1 : extruder;
|
||||
}
|
||||
|
||||
void MMU2::mmuLoop() {
|
||||
void MMU2::mmu_loop() {
|
||||
|
||||
switch (state) {
|
||||
|
||||
|
@ -185,7 +185,7 @@ void MMU2::mmuLoop() {
|
|||
|
||||
DEBUG_ECHOLNPAIR("MMU => ", buildnr);
|
||||
|
||||
checkVersion();
|
||||
check_version();
|
||||
|
||||
#if ENABLED(MMU2_MODE_12V)
|
||||
DEBUG_ECHOLNPGM("MMU <= 'M1'");
|
||||
|
@ -207,7 +207,7 @@ void MMU2::mmuLoop() {
|
|||
if (rx_ok()) {
|
||||
DEBUG_ECHOLNPGM("MMU => ok");
|
||||
|
||||
checkVersion();
|
||||
check_version();
|
||||
|
||||
DEBUG_ECHOLNPGM("MMU <= 'P0'");
|
||||
|
||||
|
@ -294,13 +294,13 @@ void MMU2::mmuLoop() {
|
|||
sscanf(rx_buffer, "%hhuok\n", &finda);
|
||||
|
||||
// This is super annoying. Only activate if necessary
|
||||
// if (findaRunoutValid) DEBUG_ECHOLNPAIR_F("MMU <= 'P0'\nMMU => ", finda, 6);
|
||||
// if (finda_runout_valid) DEBUG_ECHOLNPAIR_F("MMU <= 'P0'\nMMU => ", finda, 6);
|
||||
|
||||
state = 1;
|
||||
|
||||
if (cmd == 0) ready = true;
|
||||
|
||||
if (!finda && findaRunoutValid) filamentRunout();
|
||||
if (!finda && finda_runout_valid) filament_runout();
|
||||
}
|
||||
else if (ELAPSED(millis(), last_request + MMU_P0_TIMEOUT)) // Resend request after timeout (30s)
|
||||
state = 1;
|
||||
|
@ -434,7 +434,7 @@ bool MMU2::rx_ok() {
|
|||
/**
|
||||
* Check if MMU has compatible firmware
|
||||
*/
|
||||
void MMU2::checkVersion() {
|
||||
void MMU2::check_version() {
|
||||
if (buildnr < MMU_REQUIRED_FW_BUILDNR) {
|
||||
SERIAL_ERROR_START();
|
||||
SERIAL_ECHOPGM("MMU2 firmware version invalid. Required version >= ");
|
||||
|
@ -447,7 +447,7 @@ void MMU2::checkVersion() {
|
|||
/**
|
||||
* Handle tool change
|
||||
*/
|
||||
void MMU2::toolChange(uint8_t index) {
|
||||
void MMU2::tool_change(uint8_t index) {
|
||||
|
||||
if (!enabled) return;
|
||||
|
||||
|
@ -461,7 +461,7 @@ void MMU2::toolChange(uint8_t index) {
|
|||
|
||||
command(MMU_CMD_T0 + index);
|
||||
|
||||
manageResponse(true, true);
|
||||
manage_response(true, true);
|
||||
KEEPALIVE_STATE(IN_HANDLER);
|
||||
|
||||
command(MMU_CMD_C0);
|
||||
|
@ -490,7 +490,7 @@ void MMU2::toolChange(uint8_t index) {
|
|||
* Tc Load to nozzle after filament was prepared by Tx and extruder nozzle is already heated.
|
||||
*
|
||||
*/
|
||||
void MMU2::toolChange(const char* special) {
|
||||
void MMU2::tool_change(const char* special) {
|
||||
|
||||
if (!enabled) return;
|
||||
|
||||
|
@ -501,19 +501,19 @@ void MMU2::toolChange(const char* special) {
|
|||
|
||||
switch (*special) {
|
||||
case '?': {
|
||||
uint8_t index = mmu2_chooseFilament();
|
||||
uint8_t index = mmu2_choose_filament();
|
||||
while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(100);
|
||||
loadFilamentToNozzle(index);
|
||||
load_filament_to_nozzle(index);
|
||||
} break;
|
||||
|
||||
case 'x': {
|
||||
planner.synchronize();
|
||||
uint8_t index = mmu2_chooseFilament();
|
||||
uint8_t index = mmu2_choose_filament();
|
||||
disable_E0();
|
||||
command(MMU_CMD_T0 + index);
|
||||
manageResponse(true, true);
|
||||
manage_response(true, true);
|
||||
command(MMU_CMD_C0);
|
||||
mmuLoop();
|
||||
mmu_loop();
|
||||
|
||||
enable_E0();
|
||||
extruder = index;
|
||||
|
@ -522,7 +522,7 @@ void MMU2::toolChange(const char* special) {
|
|||
|
||||
case 'c': {
|
||||
while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(100);
|
||||
executeExtruderSequence((const E_Step *)loadToNozzle_sequence, COUNT(loadToNozzle_sequence));
|
||||
execute_extruder_sequence((const E_Step *)load_to_nozzle_sequence, COUNT(load_to_nozzle_sequence));
|
||||
} break;
|
||||
}
|
||||
|
||||
|
@ -547,7 +547,7 @@ void MMU2::command(const uint8_t mmu_cmd) {
|
|||
/**
|
||||
* Wait for response from MMU
|
||||
*/
|
||||
bool MMU2::getResponse(void) {
|
||||
bool MMU2::get_response(void) {
|
||||
while (cmd != MMU_CMD_NONE) idle();
|
||||
|
||||
while (!ready) {
|
||||
|
@ -565,7 +565,7 @@ bool MMU2::getResponse(void) {
|
|||
/**
|
||||
* Wait for response and deal with timeout if nexcessary
|
||||
*/
|
||||
void MMU2::manageResponse(bool move_axes, bool turn_off_nozzle) {
|
||||
void MMU2::manage_response(bool move_axes, bool turn_off_nozzle) {
|
||||
|
||||
bool response = false;
|
||||
mmu_print_saved = false;
|
||||
|
@ -575,7 +575,7 @@ void MMU2::manageResponse(bool move_axes, bool turn_off_nozzle) {
|
|||
|
||||
while (!response) {
|
||||
|
||||
response = getResponse(); //wait for "ok" from mmu
|
||||
response = get_response(); //wait for "ok" from mmu
|
||||
|
||||
if (!response) { //no "ok" was received in reserved time frame, user will fix the issue on mmu unit
|
||||
if (!mmu_print_saved) { //first occurence, we are saving current position, park print head in certain position and disable nozzle heater
|
||||
|
@ -636,7 +636,7 @@ void MMU2::manageResponse(bool move_axes, bool turn_off_nozzle) {
|
|||
}
|
||||
}
|
||||
|
||||
void MMU2::setFilamentType(uint8_t index, uint8_t filamentType) {
|
||||
void MMU2::set_filament_type(uint8_t index, uint8_t filamentType) {
|
||||
if (!enabled) return;
|
||||
|
||||
KEEPALIVE_STATE(IN_HANDLER);
|
||||
|
@ -644,12 +644,12 @@ void MMU2::setFilamentType(uint8_t index, uint8_t filamentType) {
|
|||
cmd_arg = filamentType;
|
||||
command(MMU_CMD_F0 + index);
|
||||
|
||||
manageResponse(true, true);
|
||||
manage_response(true, true);
|
||||
|
||||
KEEPALIVE_STATE(NOT_BUSY);
|
||||
}
|
||||
|
||||
void MMU2::filamentRunout() {
|
||||
void MMU2::filament_runout() {
|
||||
enqueue_and_echo_commands_P(PSTR(MMU2_FILAMENT_RUNOUT_SCRIPT));
|
||||
planner.synchronize();
|
||||
}
|
||||
|
@ -657,10 +657,10 @@ void MMU2::filamentRunout() {
|
|||
#if HAS_LCD_MENU && ENABLED(MMU2_MENUS)
|
||||
|
||||
// Load filament into MMU2
|
||||
void MMU2::loadFilament(uint8_t index) {
|
||||
void MMU2::load_filament(uint8_t index) {
|
||||
if (!enabled) return;
|
||||
command(MMU_CMD_L0 + index);
|
||||
manageResponse(false, false);
|
||||
manage_response(false, false);
|
||||
BUZZ(200, 404);
|
||||
}
|
||||
|
||||
|
@ -669,7 +669,7 @@ void MMU2::filamentRunout() {
|
|||
* Switch material and load to nozzle
|
||||
*
|
||||
*/
|
||||
bool MMU2::loadFilamentToNozzle(uint8_t index) {
|
||||
bool MMU2::load_filament_to_nozzle(uint8_t index) {
|
||||
|
||||
if (!enabled) return false;
|
||||
|
||||
|
@ -682,14 +682,14 @@ void MMU2::filamentRunout() {
|
|||
KEEPALIVE_STATE(IN_HANDLER);
|
||||
|
||||
command(MMU_CMD_T0 + index);
|
||||
manageResponse(true, true);
|
||||
manage_response(true, true);
|
||||
command(MMU_CMD_C0);
|
||||
mmuLoop();
|
||||
mmu_loop();
|
||||
|
||||
extruder = index;
|
||||
active_extruder = 0;
|
||||
|
||||
loadToNozzle();
|
||||
load_to_nozzle();
|
||||
|
||||
BUZZ(200, 404);
|
||||
|
||||
|
@ -706,12 +706,12 @@ void MMU2::filamentRunout() {
|
|||
* It is not used after T0 .. T4 command (select filament), in such case, gcode is responsible for loading
|
||||
* filament to nozzle.
|
||||
*/
|
||||
void MMU2::loadToNozzle() {
|
||||
void MMU2::load_to_nozzle() {
|
||||
if (!enabled) return;
|
||||
executeExtruderSequence((const E_Step *)loadToNozzle_sequence, COUNT(loadToNozzle_sequence));
|
||||
execute_extruder_sequence((const E_Step *)load_to_nozzle_sequence, COUNT(load_to_nozzle_sequence));
|
||||
}
|
||||
|
||||
bool MMU2::ejectFilament(uint8_t index, bool recover) {
|
||||
bool MMU2::eject_filament(uint8_t index, bool recover) {
|
||||
|
||||
if (!enabled) return false;
|
||||
|
||||
|
@ -731,7 +731,7 @@ void MMU2::filamentRunout() {
|
|||
planner.buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 2500 / 60, active_extruder);
|
||||
planner.synchronize();
|
||||
command(MMU_CMD_E0 + index);
|
||||
manageResponse(false, false);
|
||||
manage_response(false, false);
|
||||
|
||||
if (recover) {
|
||||
LCD_MESSAGEPGM(MSG_MMU2_EJECT_RECOVER);
|
||||
|
@ -745,7 +745,7 @@ void MMU2::filamentRunout() {
|
|||
BUZZ(200, 404);
|
||||
|
||||
command(MMU_CMD_R0);
|
||||
manageResponse(false, false);
|
||||
manage_response(false, false);
|
||||
}
|
||||
|
||||
ui.reset_status();
|
||||
|
@ -783,10 +783,10 @@ void MMU2::filamentRunout() {
|
|||
|
||||
KEEPALIVE_STATE(IN_HANDLER);
|
||||
|
||||
filamentRamming();
|
||||
filament_ramming();
|
||||
|
||||
command(MMU_CMD_U0);
|
||||
manageResponse(false, true);
|
||||
manage_response(false, true);
|
||||
|
||||
BUZZ(200, 404);
|
||||
|
||||
|
@ -803,11 +803,11 @@ void MMU2::filamentRunout() {
|
|||
/**
|
||||
* Unload sequence to optimize shape of the tip of the unloaded filament
|
||||
*/
|
||||
void MMU2::filamentRamming() {
|
||||
executeExtruderSequence((const E_Step *)ramming_sequence, sizeof(ramming_sequence) / sizeof(E_Step));
|
||||
void MMU2::filament_ramming() {
|
||||
execute_extruder_sequence((const E_Step *)ramming_sequence, sizeof(ramming_sequence) / sizeof(E_Step));
|
||||
}
|
||||
|
||||
void MMU2::executeExtruderSequence(const E_Step * sequence, int steps) {
|
||||
void MMU2::execute_extruder_sequence(const E_Step * sequence, int steps) {
|
||||
|
||||
planner.synchronize();
|
||||
enable_E0();
|
||||
|
|
|
@ -36,18 +36,18 @@ public:
|
|||
|
||||
static void init();
|
||||
static void reset();
|
||||
static void mmuLoop();
|
||||
static void toolChange(uint8_t index);
|
||||
static void toolChange(const char* special);
|
||||
static uint8_t getCurrentTool();
|
||||
static void setFilamentType(uint8_t index, uint8_t type);
|
||||
static void mmu_loop();
|
||||
static void tool_change(uint8_t index);
|
||||
static void tool_change(const char* special);
|
||||
static uint8_t get_current_tool();
|
||||
static void set_filament_type(uint8_t index, uint8_t type);
|
||||
|
||||
#if HAS_LCD_MENU && ENABLED(MMU2_MENUS)
|
||||
static bool unload();
|
||||
static void loadFilament(uint8_t);
|
||||
static void loadAll();
|
||||
static bool loadFilamentToNozzle(uint8_t index);
|
||||
static bool ejectFilament(uint8_t index, bool recover);
|
||||
static void load_filament(uint8_t);
|
||||
static void load_all();
|
||||
static bool load_filament_to_nozzle(uint8_t index);
|
||||
static bool eject_filament(uint8_t index, bool recover);
|
||||
#endif
|
||||
|
||||
private:
|
||||
|
@ -59,31 +59,31 @@ private:
|
|||
|
||||
static bool rx_ok();
|
||||
static bool rx_start();
|
||||
static void checkVersion();
|
||||
static void check_version();
|
||||
|
||||
static void command(const uint8_t cmd);
|
||||
static bool getResponse(void);
|
||||
static void manageResponse(bool move_axes, bool turn_off_nozzle);
|
||||
static bool get_response(void);
|
||||
static void manage_response(bool move_axes, bool turn_off_nozzle);
|
||||
|
||||
#if HAS_LCD_MENU && ENABLED(MMU2_MENUS)
|
||||
static void loadToNozzle();
|
||||
static void filamentRamming();
|
||||
static void executeExtruderSequence(const E_Step * sequence, int steps);
|
||||
static void load_to_nozzle();
|
||||
static void filament_ramming();
|
||||
static void execute_extruder_sequence(const E_Step * sequence, int steps);
|
||||
#endif
|
||||
|
||||
static void filamentRunout();
|
||||
static void filament_runout();
|
||||
|
||||
static bool enabled, ready, mmu_print_saved;
|
||||
static uint8_t cmd, cmd_arg, last_cmd, extruder;
|
||||
static int8_t state;
|
||||
static volatile int8_t finda;
|
||||
static volatile bool findaRunoutValid;
|
||||
static volatile bool finda_runout_valid;
|
||||
static int16_t version, buildnr;
|
||||
static millis_t last_request, next_P0_request;
|
||||
static char rx_buffer[16], tx_buffer[16];
|
||||
|
||||
static inline void set_runout_valid(const bool valid) {
|
||||
findaRunoutValid = valid;
|
||||
finda_runout_valid = valid;
|
||||
#if HAS_FILAMENT_SENSOR
|
||||
if (valid) runout.reset();
|
||||
#endif
|
||||
|
|
|
@ -49,7 +49,7 @@ class FilamentMonitorBase {
|
|||
#if ENABLED(HOST_ACTION_COMMANDS)
|
||||
static bool host_handling;
|
||||
#else
|
||||
constexpr static bool host_handling = false;
|
||||
static constexpr bool host_handling = false;
|
||||
#endif
|
||||
};
|
||||
|
||||
|
|
|
@ -474,7 +474,7 @@
|
|||
switch (i) {
|
||||
case TMC_PWM_SCALE: SERIAL_PRINT(st.PWM_SCALE(), DEC); break;
|
||||
case TMC_SGT: SERIAL_PRINT(st.sgt(), DEC); break;
|
||||
case TMC_STEALTHCHOP: serialprintPGM(st.en_pwm_mode() ? PSTR("true") : PSTR("false")); break;
|
||||
case TMC_STEALTHCHOP: serialprint_truefalse(st.en_pwm_mode()); break;
|
||||
default: break;
|
||||
}
|
||||
}
|
||||
|
@ -497,7 +497,7 @@
|
|||
switch (i) {
|
||||
case TMC_PWM_SCALE: SERIAL_PRINT(st.PWM_SCALE(), DEC); break;
|
||||
case TMC_SGT: SERIAL_PRINT(st.sgt(), DEC); break;
|
||||
case TMC_STEALTHCHOP: serialprintPGM(st.en_pwm_mode() ? PSTR("true") : PSTR("false")); break;
|
||||
case TMC_STEALTHCHOP: serialprint_truefalse(st.en_pwm_mode()); break;
|
||||
case TMC_GLOBAL_SCALER:
|
||||
{
|
||||
uint16_t value = st.GLOBAL_SCALER();
|
||||
|
@ -514,7 +514,7 @@
|
|||
static void tmc_status(TMC2208Stepper &st, const TMC_debug_enum i) {
|
||||
switch (i) {
|
||||
case TMC_PWM_SCALE: SERIAL_PRINT(st.pwm_scale_sum(), DEC); break;
|
||||
case TMC_STEALTHCHOP: serialprintPGM(st.stealth() ? PSTR("true") : PSTR("false")); break;
|
||||
case TMC_STEALTHCHOP: serialprint_truefalse(st.stealth()); break;
|
||||
case TMC_S2VSA: if (st.s2vsa()) SERIAL_CHAR('X'); break;
|
||||
case TMC_S2VSB: if (st.s2vsb()) SERIAL_CHAR('X'); break;
|
||||
default: break;
|
||||
|
@ -541,7 +541,7 @@
|
|||
SERIAL_CHAR('\t');
|
||||
switch (i) {
|
||||
case TMC_CODES: st.printLabel(); break;
|
||||
case TMC_ENABLED: serialprintPGM(st.isEnabled() ? PSTR("true") : PSTR("false")); break;
|
||||
case TMC_ENABLED: serialprint_truefalse(st.isEnabled()); break;
|
||||
case TMC_CURRENT: SERIAL_ECHO(st.getMilliamps()); break;
|
||||
case TMC_RMS_CURRENT: SERIAL_ECHO(st.rms_current()); break;
|
||||
case TMC_MAX_CURRENT: SERIAL_PRINT((float)st.rms_current() * 1.41, 0); break;
|
||||
|
@ -578,9 +578,9 @@
|
|||
SERIAL_CHAR('-');
|
||||
}
|
||||
break;
|
||||
case TMC_OTPW: serialprintPGM(st.otpw() ? PSTR("true") : PSTR("false")); break;
|
||||
case TMC_OTPW: serialprint_truefalse(st.otpw()); break;
|
||||
#if ENABLED(MONITOR_DRIVER_STATUS)
|
||||
case TMC_OTPW_TRIGGERED: serialprintPGM(st.getOTPW() ? PSTR("true") : PSTR("false")); break;
|
||||
case TMC_OTPW_TRIGGERED: serialprint_truefalse(st.getOTPW()); break;
|
||||
#endif
|
||||
case TMC_TOFF: SERIAL_PRINT(st.toff(), DEC); break;
|
||||
case TMC_TBL: SERIAL_PRINT(st.blank_time(), DEC); break;
|
||||
|
@ -596,7 +596,7 @@
|
|||
SERIAL_CHAR('\t');
|
||||
switch (i) {
|
||||
case TMC_CODES: st.printLabel(); break;
|
||||
case TMC_ENABLED: serialprintPGM(st.isEnabled() ? PSTR("true") : PSTR("false")); break;
|
||||
case TMC_ENABLED: serialprint_truefalse(st.isEnabled()); break;
|
||||
case TMC_CURRENT: SERIAL_ECHO(st.getMilliamps()); break;
|
||||
case TMC_RMS_CURRENT: SERIAL_ECHO(st.rms_current()); break;
|
||||
case TMC_MAX_CURRENT: SERIAL_PRINT((float)st.rms_current() * 1.41, 0); break;
|
||||
|
@ -606,8 +606,8 @@
|
|||
break;
|
||||
case TMC_VSENSE: serialprintPGM(st.vsense() ? PSTR("1=.165") : PSTR("0=.310")); break;
|
||||
case TMC_MICROSTEPS: SERIAL_ECHO(st.microsteps()); break;
|
||||
//case TMC_OTPW: serialprintPGM(st.otpw() ? PSTR("true") : PSTR("false")); break;
|
||||
//case TMC_OTPW_TRIGGERED: serialprintPGM(st.getOTPW() ? PSTR("true") : PSTR("false")); break;
|
||||
//case TMC_OTPW: serialprint_truefalse(st.otpw()); break;
|
||||
//case TMC_OTPW_TRIGGERED: serialprint_truefalse(st.getOTPW()); break;
|
||||
case TMC_SGT: SERIAL_PRINT(st.sgt(), DEC); break;
|
||||
case TMC_TOFF: SERIAL_PRINT(st.toff(), DEC); break;
|
||||
case TMC_TBL: SERIAL_PRINT(st.blank_time(), DEC); break;
|
||||
|
|
|
@ -227,7 +227,7 @@ void tmc_set_current(TMC &st, const int mA) {
|
|||
void tmc_report_otpw(TMC &st) {
|
||||
st.printLabel();
|
||||
SERIAL_ECHOPGM(" temperature prewarn triggered: ");
|
||||
serialprintPGM(st.getOTPW() ? PSTR("true") : PSTR("false"));
|
||||
serialprint_truefalse(st.getOTPW());
|
||||
SERIAL_EOL();
|
||||
}
|
||||
template<typename TMC>
|
||||
|
|
|
@ -246,8 +246,6 @@ void move_to(const float &rx, const float &ry, const float &z, const float &e_de
|
|||
// Yes: a 'normal' movement. No: a retract() or recover()
|
||||
feed_value = has_xy_component ? G26_XY_FEEDRATE : planner.settings.max_feedrate_mm_s[E_AXIS] / 1.5;
|
||||
|
||||
if (g26_debug_flag) SERIAL_ECHOLNPAIR("in move_to() feed_value for XY:", feed_value);
|
||||
|
||||
destination[X_AXIS] = rx;
|
||||
destination[Y_AXIS] = ry;
|
||||
destination[E_AXIS] += e_delta;
|
||||
|
@ -327,19 +325,15 @@ inline bool look_for_lines_to_connect() {
|
|||
for (uint8_t j = 0; j < GRID_MAX_POINTS_Y; j++) {
|
||||
|
||||
#if HAS_LCD_MENU
|
||||
if (user_canceled()) return true; // Check if the user wants to stop the Mesh Validation
|
||||
if (user_canceled()) return true;
|
||||
#endif
|
||||
|
||||
if (i < GRID_MAX_POINTS_X) { // We can't connect to anything to the right than GRID_MAX_POINTS_X.
|
||||
// This is already a half circle because we are at the edge of the bed.
|
||||
if (i < GRID_MAX_POINTS_X) { // Can't connect to anything to the right than GRID_MAX_POINTS_X.
|
||||
// Already a half circle at the edge of the bed.
|
||||
|
||||
if (is_bitmap_set(circle_flags, i, j) && is_bitmap_set(circle_flags, i + 1, j)) { // check if we can do a line to the left
|
||||
if (!is_bitmap_set(horizontal_mesh_line_flags, i, j)) {
|
||||
|
||||
//
|
||||
// We found two circles that need a horizontal line to connect them
|
||||
// Print it!
|
||||
//
|
||||
// Two circles need a horizontal line to connect them
|
||||
sx = _GET_MESH_X( i ) + (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)); // right edge
|
||||
ex = _GET_MESH_X(i + 1) - (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)); // left edge
|
||||
|
||||
|
@ -347,27 +341,19 @@ inline bool look_for_lines_to_connect() {
|
|||
sy = ey = constrain(_GET_MESH_Y(j), Y_MIN_POS + 1, Y_MAX_POS - 1);
|
||||
ex = constrain(ex, X_MIN_POS + 1, X_MAX_POS - 1);
|
||||
|
||||
if (position_is_reachable(sx, sy) && position_is_reachable(ex, ey)) {
|
||||
|
||||
if (g26_debug_flag) {
|
||||
SERIAL_ECHOLNPAIR(" Connecting with horizontal line (sx=", sx, ", sy=", sy, ") -> (ex=", ex, ", ey=", ey, ")");
|
||||
//debug_current_and_destination(PSTR("Connecting horizontal line."));
|
||||
}
|
||||
if (position_is_reachable(sx, sy) && position_is_reachable(ex, ey))
|
||||
print_line_from_here_to_there(sx, sy, g26_layer_height, ex, ey, g26_layer_height);
|
||||
}
|
||||
bitmap_set(horizontal_mesh_line_flags, i, j); // Mark it as done so we don't do it again, even if we skipped it
|
||||
|
||||
bitmap_set(horizontal_mesh_line_flags, i, j); // Mark done, even if skipped
|
||||
}
|
||||
}
|
||||
|
||||
if (j < GRID_MAX_POINTS_Y) { // We can't connect to anything further back than GRID_MAX_POINTS_Y.
|
||||
// This is already a half circle because we are at the edge of the bed.
|
||||
if (j < GRID_MAX_POINTS_Y) { // Can't connect to anything further back than GRID_MAX_POINTS_Y.
|
||||
// Already a half circle at the edge of the bed.
|
||||
|
||||
if (is_bitmap_set(circle_flags, i, j) && is_bitmap_set(circle_flags, i, j + 1)) { // check if we can do a line straight down
|
||||
if (!is_bitmap_set( vertical_mesh_line_flags, i, j)) {
|
||||
//
|
||||
// We found two circles that need a vertical line to connect them
|
||||
// Print it!
|
||||
//
|
||||
// Two circles that need a vertical line to connect them
|
||||
sy = _GET_MESH_Y( j ) + (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)); // top edge
|
||||
ey = _GET_MESH_Y(j + 1) - (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)); // bottom edge
|
||||
|
||||
|
@ -375,23 +361,10 @@ inline bool look_for_lines_to_connect() {
|
|||
sy = constrain(sy, Y_MIN_POS + 1, Y_MAX_POS - 1);
|
||||
ey = constrain(ey, Y_MIN_POS + 1, Y_MAX_POS - 1);
|
||||
|
||||
if (position_is_reachable(sx, sy) && position_is_reachable(ex, ey)) {
|
||||
|
||||
if (g26_debug_flag) {
|
||||
SERIAL_ECHOPAIR(" Connecting with vertical line (sx=", sx);
|
||||
SERIAL_ECHOPAIR(", sy=", sy);
|
||||
SERIAL_ECHOPAIR(") -> (ex=", ex);
|
||||
SERIAL_ECHOPAIR(", ey=", ey);
|
||||
SERIAL_CHAR(')');
|
||||
SERIAL_EOL();
|
||||
|
||||
#if ENABLED(AUTO_BED_LEVELING_UBL)
|
||||
debug_current_and_destination(PSTR("Connecting vertical line."));
|
||||
#endif
|
||||
}
|
||||
if (position_is_reachable(sx, sy) && position_is_reachable(ex, ey))
|
||||
print_line_from_here_to_there(sx, sy, g26_layer_height, ex, ey, g26_layer_height);
|
||||
}
|
||||
bitmap_set(vertical_mesh_line_flags, i, j); // Mark it as done so we don't do it again, even if skipped
|
||||
|
||||
bitmap_set(vertical_mesh_line_flags, i, j); // Mark done, even if skipped
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -725,8 +698,6 @@ void GcodeSuite::G26() {
|
|||
ui.capture();
|
||||
#endif
|
||||
|
||||
//debug_current_and_destination(PSTR("Starting G26 Mesh Validation Pattern."));
|
||||
|
||||
#if DISABLED(ARC_SUPPORT)
|
||||
|
||||
/**
|
||||
|
@ -768,6 +739,7 @@ void GcodeSuite::G26() {
|
|||
#if ENABLED(ARC_SUPPORT)
|
||||
|
||||
#define ARC_LENGTH(quarters) (INTERSECTION_CIRCLE_RADIUS * M_PI * (quarters) / 2)
|
||||
#define INTERSECTION_CIRCLE_DIAM ((INTERSECTION_CIRCLE_RADIUS) * 2)
|
||||
float sx = circle_x + INTERSECTION_CIRCLE_RADIUS, // default to full circle
|
||||
ex = circle_x + INTERSECTION_CIRCLE_RADIUS,
|
||||
sy = circle_y, ey = circle_y,
|
||||
|
@ -775,14 +747,8 @@ void GcodeSuite::G26() {
|
|||
|
||||
// Figure out where to start and end the arc - we always print counterclockwise
|
||||
if (xi == 0) { // left edge
|
||||
if (!f) {
|
||||
sx = circle_x;
|
||||
sy -= (INTERSECTION_CIRCLE_RADIUS);
|
||||
}
|
||||
if (!b) {
|
||||
ex = circle_x;
|
||||
ey += INTERSECTION_CIRCLE_RADIUS;
|
||||
}
|
||||
if (!f) { sx = circle_x; sy -= INTERSECTION_CIRCLE_RADIUS; }
|
||||
if (!b) { ex = circle_x; ey += INTERSECTION_CIRCLE_RADIUS; }
|
||||
arc_length = (f || b) ? ARC_LENGTH(1) : ARC_LENGTH(2);
|
||||
}
|
||||
else if (r) { // right edge
|
||||
|
@ -793,22 +759,19 @@ void GcodeSuite::G26() {
|
|||
arc_length = (f || b) ? ARC_LENGTH(1) : ARC_LENGTH(2);
|
||||
}
|
||||
else if (f) {
|
||||
ex = circle_x - (INTERSECTION_CIRCLE_RADIUS);
|
||||
ex -= INTERSECTION_CIRCLE_DIAM;
|
||||
arc_length = ARC_LENGTH(2);
|
||||
}
|
||||
else if (b) {
|
||||
sx = circle_x - (INTERSECTION_CIRCLE_RADIUS);
|
||||
sx -= INTERSECTION_CIRCLE_DIAM;
|
||||
arc_length = ARC_LENGTH(2);
|
||||
}
|
||||
const float arc_offset[2] = {
|
||||
circle_x - sx,
|
||||
circle_y - sy
|
||||
};
|
||||
|
||||
const float dx_s = current_position[X_AXIS] - sx, // find our distance from the start of the actual circle
|
||||
const float arc_offset[2] = { circle_x - sx, circle_y - sy },
|
||||
dx_s = current_position[X_AXIS] - sx, // find our distance from the start of the actual circle
|
||||
dy_s = current_position[Y_AXIS] - sy,
|
||||
dist_start = HYPOT2(dx_s, dy_s);
|
||||
const float endpoint[XYZE] = {
|
||||
dist_start = HYPOT2(dx_s, dy_s),
|
||||
endpoint[XYZE] = {
|
||||
ex, ey,
|
||||
g26_layer_height,
|
||||
current_position[E_AXIS] + (arc_length * g26_e_axis_feedrate * g26_extrusion_multiplier)
|
||||
|
@ -827,18 +790,6 @@ void GcodeSuite::G26() {
|
|||
const float save_feedrate = feedrate_mm_s;
|
||||
feedrate_mm_s = PLANNER_XY_FEEDRATE() / 10.0;
|
||||
|
||||
if (g26_debug_flag) {
|
||||
SERIAL_ECHOPAIR(" plan_arc(ex=", endpoint[X_AXIS]);
|
||||
SERIAL_ECHOPAIR(", ey=", endpoint[Y_AXIS]);
|
||||
SERIAL_ECHOPAIR(", ez=", endpoint[Z_AXIS]);
|
||||
SERIAL_ECHOPAIR(", len=", arc_length);
|
||||
SERIAL_ECHOPAIR(") -> (ex=", current_position[X_AXIS]);
|
||||
SERIAL_ECHOPAIR(", ey=", current_position[Y_AXIS]);
|
||||
SERIAL_ECHOPAIR(", ez=", current_position[Z_AXIS]);
|
||||
SERIAL_CHAR(')');
|
||||
SERIAL_EOL();
|
||||
}
|
||||
|
||||
plan_arc(endpoint, arc_offset, false); // Draw a counter-clockwise arc
|
||||
feedrate_mm_s = save_feedrate;
|
||||
set_destination_from_current();
|
||||
|
@ -906,16 +857,13 @@ void GcodeSuite::G26() {
|
|||
retract_filament(destination);
|
||||
destination[Z_AXIS] = Z_CLEARANCE_BETWEEN_PROBES;
|
||||
|
||||
//debug_current_and_destination(PSTR("ready to do Z-Raise."));
|
||||
move_to(destination, 0); // Raise the nozzle
|
||||
//debug_current_and_destination(PSTR("done doing Z-Raise."));
|
||||
|
||||
destination[X_AXIS] = g26_x_pos; // Move back to the starting position
|
||||
destination[Y_AXIS] = g26_y_pos;
|
||||
//destination[Z_AXIS] = Z_CLEARANCE_BETWEEN_PROBES; // Keep the nozzle where it is
|
||||
|
||||
move_to(destination, 0); // Move back to the starting position
|
||||
//debug_current_and_destination(PSTR("done doing X/Y move."));
|
||||
|
||||
#if DISABLED(NO_VOLUMETRICS)
|
||||
parser.volumetric_enabled = volumetric_was_enabled;
|
||||
|
|
|
@ -182,7 +182,6 @@
|
|||
*
|
||||
*/
|
||||
void GcodeSuite::G28(const bool always_home_all) {
|
||||
|
||||
if (DEBUGGING(LEVELING)) {
|
||||
DEBUG_ECHOLNPGM(">>> G28");
|
||||
log_machine_info();
|
||||
|
@ -268,13 +267,16 @@ void GcodeSuite::G28(const bool always_home_all) {
|
|||
const bool homeX = always_home_all || parser.seen('X'),
|
||||
homeY = always_home_all || parser.seen('Y'),
|
||||
homeZ = always_home_all || parser.seen('Z'),
|
||||
home_all = (!homeX && !homeY && !homeZ) || (homeX && homeY && homeZ);
|
||||
home_all = (!homeX && !homeY && !homeZ) || (homeX && homeY && homeZ),
|
||||
doX = home_all || homeX,
|
||||
doY = home_all || homeY,
|
||||
doZ = home_all || homeZ;
|
||||
|
||||
set_destination_from_current();
|
||||
|
||||
#if Z_HOME_DIR > 0 // If homing away from BED do Z first
|
||||
|
||||
if (home_all || homeZ) homeaxis(Z_AXIS);
|
||||
if (doZ) homeaxis(Z_AXIS);
|
||||
|
||||
#endif
|
||||
|
||||
|
@ -285,7 +287,7 @@ void GcodeSuite::G28(const bool always_home_all) {
|
|||
(parser.seenval('R') ? parser.value_linear_units() : Z_HOMING_HEIGHT)
|
||||
);
|
||||
|
||||
if (z_homing_height && (home_all || homeX || homeY)) {
|
||||
if (z_homing_height && (doX || doY)) {
|
||||
// Raise Z before homing any other axes and z is not already high enough (never lower z)
|
||||
destination[Z_AXIS] = z_homing_height;
|
||||
if (destination[Z_AXIS] > current_position[Z_AXIS]) {
|
||||
|
@ -296,25 +298,25 @@ void GcodeSuite::G28(const bool always_home_all) {
|
|||
|
||||
#if ENABLED(QUICK_HOME)
|
||||
|
||||
if (home_all || (homeX && homeY)) quick_home_xy();
|
||||
if (doX && doY) quick_home_xy();
|
||||
|
||||
#endif
|
||||
|
||||
// Home Y (before X)
|
||||
#if ENABLED(HOME_Y_BEFORE_X)
|
||||
|
||||
if (home_all || homeY
|
||||
if (doY
|
||||
#if ENABLED(CODEPENDENT_XY_HOMING)
|
||||
|| homeX
|
||||
|| doX
|
||||
#endif
|
||||
) homeaxis(Y_AXIS);
|
||||
|
||||
#endif
|
||||
|
||||
// Home X
|
||||
if (home_all || homeX
|
||||
if (doX
|
||||
#if ENABLED(CODEPENDENT_XY_HOMING) && DISABLED(HOME_Y_BEFORE_X)
|
||||
|| homeY
|
||||
|| doY
|
||||
#endif
|
||||
) {
|
||||
|
||||
|
@ -345,12 +347,12 @@ void GcodeSuite::G28(const bool always_home_all) {
|
|||
|
||||
// Home Y (after X)
|
||||
#if DISABLED(HOME_Y_BEFORE_X)
|
||||
if (home_all || homeY) homeaxis(Y_AXIS);
|
||||
if (doY) homeaxis(Y_AXIS);
|
||||
#endif
|
||||
|
||||
// Home Z last if homing towards the bed
|
||||
#if Z_HOME_DIR < 0
|
||||
if (home_all || homeZ) {
|
||||
if (doZ) {
|
||||
#if ENABLED(Z_SAFE_HOMING)
|
||||
home_z_safely();
|
||||
#else
|
||||
|
@ -361,7 +363,7 @@ void GcodeSuite::G28(const bool always_home_all) {
|
|||
move_z_after_probing();
|
||||
#endif
|
||||
|
||||
} // home_all || homeZ
|
||||
} // doZ
|
||||
#endif // Z_HOME_DIR < 0
|
||||
|
||||
sync_plan_position();
|
||||
|
@ -402,6 +404,15 @@ void GcodeSuite::G28(const bool always_home_all) {
|
|||
|
||||
#endif // DUAL_X_CARRIAGE
|
||||
|
||||
#ifdef HOMING_BACKOFF_MM
|
||||
endstops.enable(false);
|
||||
constexpr float endstop_backoff[XYZ] = HOMING_BACKOFF_MM;
|
||||
const float backoff_x = doX ? ABS(endstop_backoff[X_AXIS]) * (X_HOME_DIR) : 0,
|
||||
backoff_y = doY ? ABS(endstop_backoff[Y_AXIS]) * (Y_HOME_DIR) : 0,
|
||||
backoff_z = doZ ? ABS(endstop_backoff[Z_AXIS]) * (Z_HOME_DIR) : 0;
|
||||
if (backoff_z) do_blocking_move_to_z(current_position[Z_AXIS] - backoff_z);
|
||||
if (backoff_x || backoff_y) do_blocking_move_to_xy(current_position[X_AXIS] - backoff_x, current_position[Y_AXIS] - backoff_y);
|
||||
#endif
|
||||
endstops.not_homing();
|
||||
|
||||
#if BOTH(DELTA, DELTA_HOME_TO_SAFE_ZONE)
|
||||
|
@ -417,7 +428,7 @@ void GcodeSuite::G28(const bool always_home_all) {
|
|||
|
||||
// Restore the active tool after homing
|
||||
#if HOTENDS > 1 && (DISABLED(DELTA) || ENABLED(DELTA_HOME_TO_SAFE_ZONE))
|
||||
#if ENABLED(PARKING_EXTRUDER) || ENABLED(DUAL_X_CARRIAGE)
|
||||
#if EITHER(PARKING_EXTRUDER, DUAL_X_CARRIAGE)
|
||||
#define NO_FETCH false // fetch the previous toolhead
|
||||
#else
|
||||
#define NO_FETCH true
|
||||
|
@ -432,7 +443,7 @@ void GcodeSuite::G28(const bool always_home_all) {
|
|||
#if ENABLED(NANODLP_ALL_AXIS)
|
||||
#define _HOME_SYNC true // For any axis, output sync text.
|
||||
#else
|
||||
#define _HOME_SYNC (home_all || homeZ) // Only for Z-axis
|
||||
#define _HOME_SYNC doZ // Only for Z-axis
|
||||
#endif
|
||||
if (_HOME_SYNC)
|
||||
SERIAL_ECHOLNPGM(MSG_Z_MOVE_COMP);
|
||||
|
|
|
@ -30,7 +30,7 @@
|
|||
void M217_report(const bool eeprom=false) {
|
||||
|
||||
#if ENABLED(TOOLCHANGE_FILAMENT_SWAP)
|
||||
serialprintPGM(eeprom ? PSTR(" M217") : PSTR("Singlenozzle:"));
|
||||
serialprintPGM(eeprom ? PSTR(" M217") : PSTR("Toolchange:"));
|
||||
SERIAL_ECHOPAIR(" S", LINEAR_UNIT(toolchange_settings.swap_length));
|
||||
SERIAL_ECHOPAIR(" P", LINEAR_UNIT(toolchange_settings.prime_speed));
|
||||
SERIAL_ECHOPAIR(" R", LINEAR_UNIT(toolchange_settings.retract_speed));
|
||||
|
|
|
@ -47,13 +47,13 @@ inline void toggle_pins() {
|
|||
|
||||
for (uint8_t i = start; i <= end; i++) {
|
||||
pin_t pin = GET_PIN_MAP_PIN(i);
|
||||
//report_pin_state_extended(pin, ignore_protection, false);
|
||||
if (!VALID_PIN(pin)) continue;
|
||||
if (!ignore_protection && pin_is_protected(pin)) {
|
||||
if (M43_NEVER_TOUCH(i) || (!ignore_protection && pin_is_protected(pin))) {
|
||||
report_pin_state_extended(pin, ignore_protection, true, "Untouched ");
|
||||
SERIAL_EOL();
|
||||
}
|
||||
else {
|
||||
watchdog_reset();
|
||||
report_pin_state_extended(pin, ignore_protection, true, "Pulsing ");
|
||||
#if AVR_AT90USB1286_FAMILY // Teensy IDEs don't know about these pins so must use FASTIO
|
||||
if (pin == TEENSY_E2) {
|
||||
|
@ -77,12 +77,12 @@ inline void toggle_pins() {
|
|||
{
|
||||
pinMode(pin, OUTPUT);
|
||||
for (int16_t j = 0; j < repeat; j++) {
|
||||
extDigitalWrite(pin, 0); safe_delay(wait);
|
||||
extDigitalWrite(pin, 1); safe_delay(wait);
|
||||
extDigitalWrite(pin, 0); safe_delay(wait);
|
||||
watchdog_reset(); extDigitalWrite(pin, 0); safe_delay(wait);
|
||||
watchdog_reset(); extDigitalWrite(pin, 1); safe_delay(wait);
|
||||
watchdog_reset(); extDigitalWrite(pin, 0); safe_delay(wait);
|
||||
watchdog_reset();
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
SERIAL_EOL();
|
||||
}
|
||||
|
@ -277,7 +277,7 @@ void GcodeSuite::M43() {
|
|||
for (uint8_t i = first_pin; i <= last_pin; i++) {
|
||||
pin_t pin = GET_PIN_MAP_PIN(i);
|
||||
if (!VALID_PIN(pin)) continue;
|
||||
if (!ignore_protection && pin_is_protected(pin)) continue;
|
||||
if (M43_NEVER_TOUCH(i) || (!ignore_protection && pin_is_protected(pin))) continue;
|
||||
pinMode(pin, INPUT_PULLUP);
|
||||
delay(1);
|
||||
/*
|
||||
|
@ -300,7 +300,7 @@ void GcodeSuite::M43() {
|
|||
for (uint8_t i = first_pin; i <= last_pin; i++) {
|
||||
pin_t pin = GET_PIN_MAP_PIN(i);
|
||||
if (!VALID_PIN(pin)) continue;
|
||||
if (!ignore_protection && pin_is_protected(pin)) continue;
|
||||
if (M43_NEVER_TOUCH(i) || (!ignore_protection && pin_is_protected(pin))) continue;
|
||||
const byte val =
|
||||
/*
|
||||
IS_ANALOG(pin)
|
||||
|
|
|
@ -53,7 +53,7 @@ uint8_t spindle_laser_power; // = 0
|
|||
* NOTE: A minimum PWM frequency of 50 Hz is needed. All prescaler
|
||||
* factors for timers 2, 3, 4, and 5 are acceptable.
|
||||
*
|
||||
* SPINDLE_LASER_ENABLE_PIN needs an external pullup or it may power on
|
||||
* SPINDLE_LASER_ENA_PIN needs an external pullup or it may power on
|
||||
* the spindle/laser during power-up or when connecting to the host
|
||||
* (usually goes through a reset which sets all I/O pins to tri-state)
|
||||
*
|
||||
|
@ -73,7 +73,7 @@ inline void delay_for_power_down() { safe_delay(SPINDLE_LASER_POWERDOWN_DELAY);
|
|||
*/
|
||||
|
||||
inline void set_spindle_laser_ocr(const uint8_t ocr) {
|
||||
WRITE(SPINDLE_LASER_ENABLE_PIN, SPINDLE_LASER_ENABLE_INVERT); // turn spindle on (active low)
|
||||
WRITE(SPINDLE_LASER_ENA_PIN, SPINDLE_LASER_ENABLE_INVERT); // turn spindle on (active low)
|
||||
analogWrite(SPINDLE_LASER_PWM_PIN, (SPINDLE_LASER_PWM_INVERT) ? 255 - ocr : ocr);
|
||||
}
|
||||
|
||||
|
@ -81,7 +81,7 @@ inline void set_spindle_laser_ocr(const uint8_t ocr) {
|
|||
|
||||
void update_spindle_laser_power() {
|
||||
if (spindle_laser_power == 0) {
|
||||
WRITE(SPINDLE_LASER_ENABLE_PIN, !SPINDLE_LASER_ENABLE_INVERT); // turn spindle off (active low)
|
||||
WRITE(SPINDLE_LASER_ENA_PIN, !SPINDLE_LASER_ENABLE_INVERT); // turn spindle off (active low)
|
||||
analogWrite(SPINDLE_LASER_PWM_PIN, SPINDLE_LASER_PWM_INVERT ? 255 : 0); // only write low byte
|
||||
delay_for_power_down();
|
||||
}
|
||||
|
@ -101,7 +101,7 @@ inline void set_spindle_laser_ocr(const uint8_t ocr) {
|
|||
#endif // SPINDLE_LASER_PWM
|
||||
|
||||
bool spindle_laser_enabled() {
|
||||
return !!spindle_laser_power; // READ(SPINDLE_LASER_ENABLE_PIN) == SPINDLE_LASER_ENABLE_INVERT;
|
||||
return !!spindle_laser_power; // READ(SPINDLE_LASER_ENA_PIN) == SPINDLE_LASER_ENABLE_INVERT;
|
||||
}
|
||||
|
||||
void set_spindle_laser_enabled(const bool enable) {
|
||||
|
@ -111,11 +111,11 @@ void set_spindle_laser_enabled(const bool enable) {
|
|||
update_spindle_laser_power();
|
||||
#else
|
||||
if (enable) {
|
||||
WRITE(SPINDLE_LASER_ENABLE_PIN, SPINDLE_LASER_ENABLE_INVERT);
|
||||
WRITE(SPINDLE_LASER_ENA_PIN, SPINDLE_LASER_ENABLE_INVERT);
|
||||
delay_for_power_up();
|
||||
}
|
||||
else {
|
||||
WRITE(SPINDLE_LASER_ENABLE_PIN, !SPINDLE_LASER_ENABLE_INVERT);
|
||||
WRITE(SPINDLE_LASER_ENA_PIN, !SPINDLE_LASER_ENABLE_INVERT);
|
||||
delay_for_power_down();
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -55,7 +55,7 @@ void GcodeSuite::T(const uint8_t tool_index) {
|
|||
|
||||
#if ENABLED(PRUSA_MMU2)
|
||||
if (parser.string_arg) {
|
||||
mmu2.toolChange(parser.string_arg); // Special commands T?/Tx/Tc
|
||||
mmu2.tool_change(parser.string_arg); // Special commands T?/Tx/Tc
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -84,7 +84,7 @@ void GcodeSuite::M701() {
|
|||
|
||||
// Load filament
|
||||
#if ENABLED(PRUSA_MMU2)
|
||||
mmu2.loadFilamentToNozzle(target_extruder);
|
||||
mmu2.load_filament_to_nozzle(target_extruder);
|
||||
#else
|
||||
constexpr float slow_load_length = FILAMENT_CHANGE_SLOW_LOAD_LENGTH;
|
||||
const float fast_load_length = ABS(parser.seen('L') ? parser.value_axis_units(E_AXIS)
|
||||
|
|
|
@ -29,17 +29,20 @@
|
|||
#include "../../../module/motion.h"
|
||||
#include "../../../lcd/ultralcd.h"
|
||||
|
||||
#define DEBUG_OUT ENABLED(DEBUG_POWER_LOSS_RECOVERY)
|
||||
#include "../../../core/debug_out.h"
|
||||
|
||||
void menu_job_recovery();
|
||||
|
||||
#if ENABLED(DEBUG_POWER_LOSS_RECOVERY)
|
||||
|
||||
inline void plr_error(PGM_P const prefix) {
|
||||
SERIAL_ECHO_START();
|
||||
#if ENABLED(DEBUG_POWER_LOSS_RECOVERY)
|
||||
DEBUG_ECHO_START();
|
||||
serialprintPGM(prefix);
|
||||
SERIAL_ECHOLNPGM(" Power-Loss Recovery Data");
|
||||
}
|
||||
|
||||
DEBUG_ECHOLNPGM(" Power-Loss Recovery Data");
|
||||
#else
|
||||
UNUSED(prefix);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* M1000: Resume from power-loss (undocumented)
|
||||
|
@ -54,11 +57,8 @@ void GcodeSuite::M1000() {
|
|||
else
|
||||
recovery.resume();
|
||||
}
|
||||
else {
|
||||
#if ENABLED(DEBUG_POWER_LOSS_RECOVERY)
|
||||
else
|
||||
plr_error(recovery.info.valid_head ? PSTR("No") : PSTR("Invalid"));
|
||||
#endif
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
|
|
@ -41,7 +41,7 @@ void GcodeSuite::M403() {
|
|||
type = parser.intval('F', -1);
|
||||
|
||||
if (WITHIN(index, 0, 4) && WITHIN(type, 0, 2))
|
||||
mmu2.setFilamentType(index, type);
|
||||
mmu2.set_filament_type(index, type);
|
||||
else
|
||||
SERIAL_ECHO_MSG("M403 - bad arguments.");
|
||||
}
|
||||
|
|
|
@ -105,7 +105,7 @@ void GcodeSuite::get_destination_from_command() {
|
|||
|
||||
#if ENABLED(POWER_LOSS_RECOVERY)
|
||||
// Only update power loss recovery on moves with E
|
||||
if ((seen[E_AXIS] || seen[Z_AXIS]) && IS_SD_PRINTING()) recovery.save();
|
||||
if (seen[E_AXIS] && (seen[X_AXIS] || seen[Y_AXIS]) && IS_SD_PRINTING()) recovery.save();
|
||||
#endif
|
||||
|
||||
if (parser.linearval('F') > 0)
|
||||
|
@ -269,6 +269,16 @@ void GcodeSuite::process_parsed_command(
|
|||
break;
|
||||
#endif
|
||||
|
||||
#if ENABLED(CNC_COORDINATE_SYSTEMS)
|
||||
case 53: G53(); break;
|
||||
case 54: G54(); break;
|
||||
case 55: G55(); break;
|
||||
case 56: G56(); break;
|
||||
case 57: G57(); break;
|
||||
case 58: G58(); break;
|
||||
case 59: G59(); break;
|
||||
#endif
|
||||
|
||||
#if ENABLED(GCODE_MOTION_MODES)
|
||||
case 80: G80(); break; // G80: Reset the current motion mode
|
||||
#endif
|
||||
|
@ -348,10 +358,6 @@ void GcodeSuite::process_parsed_command(
|
|||
case 48: M48(); break; // M48: Z probe repeatability test
|
||||
#endif
|
||||
|
||||
#if ENABLED(G26_MESH_VALIDATION)
|
||||
case 49: M49(); break; // M49: Turn on or off G26 debug flag for verbose output
|
||||
#endif
|
||||
|
||||
#if ENABLED(LCD_SET_PROGRESS_MANUALLY)
|
||||
case 73: M73(); break; // M73: Set progress percentage (for display on LCD)
|
||||
#endif
|
||||
|
|
|
@ -495,10 +495,6 @@ private:
|
|||
static void M48();
|
||||
#endif
|
||||
|
||||
#if ENABLED(G26_MESH_VALIDATION)
|
||||
static void M49();
|
||||
#endif
|
||||
|
||||
#if ENABLED(LCD_SET_PROGRESS_MANUALLY)
|
||||
static void M73();
|
||||
#endif
|
||||
|
|
|
@ -59,7 +59,7 @@ bool GcodeSuite::select_coordinate_system(const int8_t _new) {
|
|||
*
|
||||
* Marlin also uses G53 on a line by itself to go back to native space.
|
||||
*/
|
||||
inline void GcodeSuite::G53() {
|
||||
void GcodeSuite::G53() {
|
||||
const int8_t _system = active_coordinate_system;
|
||||
active_coordinate_system = -1;
|
||||
if (parser.chain()) { // If this command has more following...
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
|
|
|
@ -25,6 +25,7 @@
|
|||
#if ENABLED(BABYSTEPPING)
|
||||
|
||||
#include "../gcode.h"
|
||||
#include "../../feature/babystep.h"
|
||||
#include "../../module/probe.h"
|
||||
#include "../../module/temperature.h"
|
||||
#include "../../module/planner.h"
|
||||
|
@ -49,7 +50,7 @@
|
|||
else {
|
||||
hotend_offset[Z_AXIS][active_extruder] -= offs;
|
||||
SERIAL_ECHO_START();
|
||||
SERIAL_ECHOLNPAIR(MSG_IDEX_Z_OFFSET ": ", hotend_offset[Z_AXIS][active_extruder]);
|
||||
SERIAL_ECHOLNPAIR(MSG_Z_OFFSET ": ", hotend_offset[Z_AXIS][active_extruder]);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
@ -64,7 +65,7 @@ void GcodeSuite::M290() {
|
|||
for (uint8_t a = X_AXIS; a <= Z_AXIS; a++)
|
||||
if (parser.seenval(axis_codes[a]) || (a == Z_AXIS && parser.seenval('S'))) {
|
||||
const float offs = constrain(parser.value_axis_units((AxisEnum)a), -2, 2);
|
||||
thermalManager.babystep_axis((AxisEnum)a, offs * planner.settings.axis_steps_per_mm[a]);
|
||||
babystep.add_mm((AxisEnum)a, offs);
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
if (a == Z_AXIS && (!parser.seen('P') || parser.value_bool())) mod_zprobe_zoffset(offs);
|
||||
#endif
|
||||
|
@ -72,7 +73,7 @@ void GcodeSuite::M290() {
|
|||
#else
|
||||
if (parser.seenval('Z') || parser.seenval('S')) {
|
||||
const float offs = constrain(parser.value_axis_units(Z_AXIS), -2, 2);
|
||||
thermalManager.babystep_axis(Z_AXIS, offs * planner.settings.axis_steps_per_mm[Z_AXIS]);
|
||||
babystep.add_mm(Z_AXIS, offs);
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
if (!parser.seen('P') || parser.value_bool()) mod_zprobe_zoffset(offs);
|
||||
#endif
|
||||
|
|
|
@ -37,10 +37,6 @@
|
|||
#include "../feature/leds/printer_event_leds.h"
|
||||
#endif
|
||||
|
||||
#if ENABLED(POWER_LOSS_RECOVERY)
|
||||
#include "../feature/power_loss_recovery.h"
|
||||
#endif
|
||||
|
||||
/**
|
||||
* GCode line number handling. Hosts may opt to include line numbers when
|
||||
* sending commands to Marlin, and lines will be checked for sequentiality.
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
|
|
|
@ -139,6 +139,13 @@
|
|||
|
||||
#define MINIPANEL
|
||||
|
||||
#elif ENABLED(FYSETC_MINI_12864)
|
||||
|
||||
#define DOGLCD
|
||||
#define ULTIPANEL
|
||||
#define DEFAULT_LCD_CONTRAST 255
|
||||
#define LED_COLORS_REDUCE_GREEN
|
||||
|
||||
#endif
|
||||
|
||||
#if EITHER(MAKRPANEL, MINIPANEL)
|
||||
|
@ -313,18 +320,10 @@
|
|||
|
||||
#define HAS_ADC_BUTTONS ENABLED(ADC_KEYPAD)
|
||||
|
||||
#if HAS_GRAPHICAL_LCD
|
||||
/**
|
||||
* Default LCD contrast for Graphical LCD displays
|
||||
*/
|
||||
#define HAS_LCD_CONTRAST ( \
|
||||
ENABLED(MAKRPANEL) \
|
||||
|| ENABLED(CARTESIO_UI) \
|
||||
|| ENABLED(VIKI2) \
|
||||
|| ENABLED(AZSMZ_12864) \
|
||||
|| ENABLED(miniVIKI) \
|
||||
|| ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) \
|
||||
)
|
||||
#define HAS_LCD_CONTRAST HAS_GRAPHICAL_LCD && defined(DEFAULT_LCD_CONTRAST)
|
||||
#if HAS_LCD_CONTRAST
|
||||
#ifndef LCD_CONTRAST_MIN
|
||||
#define LCD_CONTRAST_MIN 0
|
||||
|
@ -336,14 +335,6 @@
|
|||
#define DEFAULT_LCD_CONTRAST 32
|
||||
#endif
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// Boot screens
|
||||
#if !HAS_SPI_LCD
|
||||
#undef SHOW_BOOTSCREEN
|
||||
#elif !defined(BOOTSCREEN_TIMEOUT)
|
||||
#define BOOTSCREEN_TIMEOUT 2500
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Extruders have some combination of stepper motors and hotends
|
||||
|
@ -434,7 +425,7 @@
|
|||
*/
|
||||
#if ENABLED(DISTINCT_E_FACTORS) && E_STEPPERS > 1
|
||||
#define XYZE_N (XYZ + E_STEPPERS)
|
||||
#define E_AXIS_N(E) (E_AXIS + E)
|
||||
#define E_AXIS_N(E) AxisEnum(E_AXIS + E)
|
||||
#else
|
||||
#undef DISTINCT_E_FACTORS
|
||||
#define XYZE_N XYZE
|
||||
|
@ -519,7 +510,9 @@
|
|||
#define Z_MULTI_STEPPER_DRIVERS EITHER(Z_DUAL_STEPPER_DRIVERS, Z_TRIPLE_STEPPER_DRIVERS)
|
||||
#define Z_MULTI_ENDSTOPS EITHER(Z_DUAL_ENDSTOPS, Z_TRIPLE_ENDSTOPS)
|
||||
#define HAS_EXTRA_ENDSTOPS (EITHER(X_DUAL_ENDSTOPS, Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS)
|
||||
#define HAS_GAME_MENU (1 < ENABLED(MARLIN_BRICKOUT) + ENABLED(MARLIN_INVADERS) + ENABLED(MARLIN_SNAKE))
|
||||
|
||||
#define HAS_GAMES ANY(MARLIN_BRICKOUT, MARLIN_INVADERS, MARLIN_SNAKE, MARLIN_MAZE)
|
||||
#define HAS_GAME_MENU (1 < ENABLED(MARLIN_BRICKOUT) + ENABLED(MARLIN_INVADERS) + ENABLED(MARLIN_SNAKE) + ENABLED(MARLIN_MAZE))
|
||||
|
||||
#define IS_SCARA EITHER(MORGAN_SCARA, MAKERARM_SCARA)
|
||||
#define IS_KINEMATIC (ENABLED(DELTA) || IS_SCARA)
|
||||
|
@ -563,3 +556,7 @@
|
|||
#endif
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if ENABLED(SLIM_LCD_MENUS)
|
||||
#define BOOT_MARLIN_LOGO_SMALL
|
||||
#endif
|
||||
|
|
|
@ -873,9 +873,6 @@
|
|||
#define TMC_HAS_SPI (HAS_TMCX1X0 || HAS_DRIVER(TMC2660))
|
||||
#define HAS_STALLGUARD (HAS_TMCX1X0 || HAS_DRIVER(TMC2660))
|
||||
#define HAS_STEALTHCHOP (HAS_TMCX1X0 || HAS_DRIVER(TMC2208))
|
||||
#define AXIS_HAS_SPI(ST) (AXIS_DRIVER_TYPE(ST, TMC2130) || AXIS_DRIVER_TYPE(ST, TMC2160) || AXIS_DRIVER_TYPE(ST, TMC2660))
|
||||
#define AXIS_HAS_STALLGUARD(ST) (AXIS_DRIVER_TYPE(ST, TMC2130) || AXIS_DRIVER_TYPE(ST, TMC2160) || AXIS_DRIVER_TYPE(ST, TMC2660) || AXIS_DRIVER_TYPE(ST, TMC5130) || AXIS_DRIVER_TYPE(ST, TMC5160))
|
||||
#define AXIS_HAS_STEALTHCHOP(ST) (AXIS_DRIVER_TYPE(ST, TMC2130) || AXIS_DRIVER_TYPE(ST, TMC2160) || AXIS_DRIVER_TYPE(ST, TMC2208) || AXIS_DRIVER_TYPE(ST, TMC5130) || AXIS_DRIVER_TYPE(ST, TMC5160))
|
||||
|
||||
#define STEALTHCHOP_ENABLED ANY(STEALTHCHOP_XY, STEALTHCHOP_Z, STEALTHCHOP_E)
|
||||
#define USE_SENSORLESS EITHER(SENSORLESS_HOMING, SENSORLESS_PROBING)
|
||||
|
@ -921,7 +918,7 @@
|
|||
#define HAS_TEMP_HOTEND (HAS_TEMP_ADC_0 || ENABLED(HEATER_0_USES_MAX6675))
|
||||
#define HAS_TEMP_BED HAS_TEMP_ADC_BED
|
||||
#define HAS_TEMP_CHAMBER HAS_TEMP_ADC_CHAMBER
|
||||
#define HAS_HEATED_CHAMBER (HAS_TEMP_CHAMBER && PIN_EXISTS(CHAMBER_HEATER))
|
||||
#define HAS_HEATED_CHAMBER (HAS_TEMP_CHAMBER && PIN_EXISTS(HEATER_CHAMBER))
|
||||
|
||||
// Heaters
|
||||
#define HAS_HEATER_0 (PIN_EXISTS(HEATER_0))
|
||||
|
@ -1679,7 +1676,7 @@
|
|||
// Get LCD character width/height, which may be overridden by pins, configs, etc.
|
||||
#ifndef LCD_WIDTH
|
||||
#if HAS_GRAPHICAL_LCD
|
||||
#define LCD_WIDTH 22
|
||||
#define LCD_WIDTH 21
|
||||
#elif ENABLED(ULTIPANEL)
|
||||
#define LCD_WIDTH 20
|
||||
#elif HAS_SPI_LCD
|
||||
|
|
|
@ -341,6 +341,10 @@
|
|||
#error "MAX6675_SS is now MAX6675_SS_PIN. Please update your configuration and/or pins."
|
||||
#elif defined(MAX6675_SS2)
|
||||
#error "MAX6675_SS2 is now MAX6675_SS2_PIN. Please update your configuration and/or pins."
|
||||
#elif defined(SPINDLE_LASER_ENABLE_PIN)
|
||||
#error "SPINDLE_LASER_ENABLE_PIN is now SPINDLE_LASER_ENA_PIN. Please update your configuration and/or pins."
|
||||
#elif defined(CHAMBER_HEATER_PIN)
|
||||
#error "CHAMBER_HEATER_PIN is now HEATER_CHAMBER_PIN. Please update your configuration and/or pins."
|
||||
#elif defined(TMC_Z_CALIBRATION)
|
||||
#error "TMC_Z_CALIBRATION has been deprecated in favor of Z_STEPPER_AUTO_ALIGN. Please update your configuration."
|
||||
#elif defined(Z_MIN_PROBE_ENDSTOP)
|
||||
|
@ -551,6 +555,10 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
|
|||
#endif
|
||||
#endif
|
||||
|
||||
#if defined(EVENT_GCODE_SD_STOP) && DISABLED(NOZZLE_PARK_FEATURE)
|
||||
static_assert(NULL == strstr(EVENT_GCODE_SD_STOP, "G27"), "NOZZLE_PARK_FEATURE is required to use G27 in EVENT_GCODE_SD_STOP.");
|
||||
#endif
|
||||
|
||||
/**
|
||||
* I2C Position Encoders
|
||||
*/
|
||||
|
@ -1758,6 +1766,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
|
|||
+ ENABLED(G3D_PANEL) \
|
||||
+ (ENABLED(MINIPANEL) && DISABLED(MKS_MINI_12864)) \
|
||||
+ ENABLED(MKS_MINI_12864) \
|
||||
+ ENABLED(FYSETC_MINI_12864) \
|
||||
+ (ENABLED(REPRAPWORLD_KEYPAD) && DISABLED(CARTESIO_UI, ZONESTAR_LCD)) \
|
||||
+ ENABLED(RIGIDBOT_PANEL) \
|
||||
+ ENABLED(RA_CONTROL_PANEL) \
|
||||
|
|
|
@ -1025,7 +1025,7 @@ void MarlinUI::draw_status_screen() {
|
|||
}
|
||||
|
||||
void draw_edit_screen(PGM_P const pstr, const char* const value/*=NULL*/) {
|
||||
lcd_moveto(1, 1);
|
||||
lcd_moveto(0, 1);
|
||||
lcd_put_u8str_P(pstr);
|
||||
if (value != NULL) {
|
||||
lcd_put_wchar(':');
|
||||
|
@ -1037,6 +1037,16 @@ void MarlinUI::draw_status_screen() {
|
|||
}
|
||||
}
|
||||
|
||||
void draw_select_screen(PGM_P const yes, PGM_P const no, const bool yesno, PGM_P const pref, const char * const string, PGM_P const suff) {
|
||||
SETCURSOR(0, 0); lcd_put_u8str_P(pref);
|
||||
if (string) wrap_string(1, string);
|
||||
if (suff) lcd_put_u8str_P(suff);
|
||||
SETCURSOR(0, LCD_HEIGHT - 1);
|
||||
lcd_put_wchar(yesno ? ' ' : '['); lcd_put_u8str_P(no); lcd_put_wchar(yesno ? ' ' : ']');
|
||||
SETCURSOR_RJ(utf8_strlen_P(yes) + 2, LCD_HEIGHT - 1);
|
||||
lcd_put_wchar(yesno ? '[' : ' '); lcd_put_u8str_P(yes); lcd_put_wchar(yesno ? ']' : ' ');
|
||||
}
|
||||
|
||||
#if ENABLED(SDSUPPORT)
|
||||
|
||||
void draw_sd_menu_item(const bool sel, const uint8_t row, PGM_P const pstr, CardReader &theCard, const bool isDir) {
|
||||
|
|
|
@ -47,7 +47,7 @@
|
|||
uint8_t u8g_com_HAL_LPC1768_ssd_hw_i2c_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr);
|
||||
#define U8G_COM_SSD_I2C_HAL u8g_com_arduino_ssd_i2c_fn
|
||||
|
||||
#if defined(ARDUINO_ARCH_STM32F1)
|
||||
#ifdef ARDUINO_ARCH_STM32F1
|
||||
uint8_t u8g_com_stm32duino_fsmc_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr);
|
||||
#define U8G_COM_HAL_FSMC_FN u8g_com_stm32duino_fsmc_fn
|
||||
#else
|
||||
|
|
|
@ -29,21 +29,46 @@
|
|||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#if ENABLED(SHOW_BOOTSCREEN)
|
||||
|
||||
//#define START_BMPHIGH // Costs 399 bytes more flash
|
||||
|
||||
#if ENABLED(SHOW_CUSTOM_BOOTSCREEN)
|
||||
|
||||
#include "../../../_Bootscreen.h"
|
||||
|
||||
#ifndef CUSTOM_BOOTSCREEN_TIMEOUT
|
||||
#define CUSTOM_BOOTSCREEN_TIMEOUT 2500
|
||||
#ifndef CUSTOM_BOOTSCREEN_BMP_BYTEWIDTH
|
||||
#define CUSTOM_BOOTSCREEN_BMP_BYTEWIDTH ((CUSTOM_BOOTSCREEN_BMPWIDTH + 7) / 8)
|
||||
#endif
|
||||
#ifndef CUSTOM_BOOTSCREEN_BMPHEIGHT
|
||||
#define CUSTOM_BOOTSCREEN_BMPHEIGHT (sizeof(custom_start_bmp) / (CUSTOM_BOOTSCREEN_BMP_BYTEWIDTH))
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
#if ENABLED(START_BMPHIGH)
|
||||
#if ENABLED(BOOT_MARLIN_LOGO_SMALL)
|
||||
|
||||
#define START_BMPWIDTH 56
|
||||
|
||||
const unsigned char start_bmp[] PROGMEM = {
|
||||
B00011111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,
|
||||
B01100000,B00000000,B00000000,B00000000,B00000000,B00000001,B11111111,
|
||||
B01000000,B00000000,B00000000,B00000000,B00000000,B00000000,B11111111,
|
||||
B10000000,B00000000,B00000000,B00000000,B00000000,B00000000,B01111111,
|
||||
B10000011,B11001111,B00000000,B00000000,B00001100,B00110000,B00111111,
|
||||
B10000111,B11111111,B10000000,B00000000,B00001100,B00110000,B00011111,
|
||||
B10000110,B01111001,B10000000,B00000000,B00001100,B00000000,B00001111,
|
||||
B10001100,B00110000,B11000111,B10000011,B10001100,B00110000,B11100111,
|
||||
B10001100,B00110000,B11001111,B11000111,B11001100,B00110001,B11110011,
|
||||
B10001100,B00110000,B11011100,B11101100,B11101100,B00110011,B10111001,
|
||||
B10001100,B00110000,B11011000,B01101100,B01101100,B00110011,B00011001,
|
||||
B10001100,B00110000,B11010000,B01101100,B00001100,B00110011,B00011001,
|
||||
B10001100,B00110000,B11011000,B01101100,B00001100,B00110011,B00011001,
|
||||
B10001100,B00110000,B11011100,B01101100,B00001110,B00111011,B00011001,
|
||||
B10001100,B00110000,B11001111,B01111100,B00000111,B10011111,B00011001,
|
||||
B10001100,B00110000,B11000111,B01111100,B00000011,B10001111,B00011001,
|
||||
B01000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000010,
|
||||
B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000110,
|
||||
B00011111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111000
|
||||
};
|
||||
|
||||
#else
|
||||
|
||||
#define START_BMPWIDTH 112
|
||||
|
||||
|
@ -88,32 +113,6 @@
|
|||
B00000001,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B10000000
|
||||
};
|
||||
|
||||
#else
|
||||
|
||||
#define START_BMPWIDTH 56
|
||||
|
||||
const unsigned char start_bmp[] PROGMEM = {
|
||||
B00011111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,
|
||||
B01100000,B00000000,B00000000,B00000000,B00000000,B00000001,B11111111,
|
||||
B01000000,B00000000,B00000000,B00000000,B00000000,B00000000,B11111111,
|
||||
B10000000,B00000000,B00000000,B00000000,B00000000,B00000000,B01111111,
|
||||
B10000011,B11001111,B00000000,B00000000,B00001100,B00110000,B00111111,
|
||||
B10000111,B11111111,B10000000,B00000000,B00001100,B00110000,B00011111,
|
||||
B10000110,B01111001,B10000000,B00000000,B00001100,B00000000,B00001111,
|
||||
B10001100,B00110000,B11000111,B10000011,B10001100,B00110000,B11100111,
|
||||
B10001100,B00110000,B11001111,B11000111,B11001100,B00110001,B11110011,
|
||||
B10001100,B00110000,B11011100,B11101100,B11101100,B00110011,B10111001,
|
||||
B10001100,B00110000,B11011000,B01101100,B01101100,B00110011,B00011001,
|
||||
B10001100,B00110000,B11010000,B01101100,B00001100,B00110011,B00011001,
|
||||
B10001100,B00110000,B11011000,B01101100,B00001100,B00110011,B00011001,
|
||||
B10001100,B00110000,B11011100,B01101100,B00001110,B00111011,B00011001,
|
||||
B10001100,B00110000,B11001111,B01111100,B00000111,B10011111,B00011001,
|
||||
B10001100,B00110000,B11000111,B01111100,B00000011,B10001111,B00011001,
|
||||
B01000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000010,
|
||||
B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000110,
|
||||
B00011111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111000
|
||||
};
|
||||
|
||||
#endif
|
||||
|
||||
#ifndef START_BMP_BYTEWIDTH
|
||||
|
@ -124,12 +123,3 @@
|
|||
#endif
|
||||
|
||||
static_assert(sizeof(start_bmp) == (START_BMP_BYTEWIDTH) * (START_BMPHEIGHT), "Bootscreen (start_bmp) dimensions don't match data.");
|
||||
|
||||
#endif
|
||||
|
||||
#ifndef CUSTOM_BOOTSCREEN_BMP_BYTEWIDTH
|
||||
#define CUSTOM_BOOTSCREEN_BMP_BYTEWIDTH ((CUSTOM_BOOTSCREEN_BMPWIDTH + 7) / 8)
|
||||
#endif
|
||||
#ifndef CUSTOM_BOOTSCREEN_BMPHEIGHT
|
||||
#define CUSTOM_BOOTSCREEN_BMPHEIGHT (sizeof(custom_start_bmp) / (CUSTOM_BOOTSCREEN_BMP_BYTEWIDTH))
|
||||
#endif
|
||||
|
|
|
@ -97,7 +97,7 @@ static void fontgroup_drawwchar(font_group_t *group, const font_t *fnt_default,
|
|||
* @param utf8_msg : the UTF-8 string
|
||||
* @param cb_read_byte : how to read the utf8_msg, from RAM or ROM (call read_byte_ram or pgm_read_byte)
|
||||
* @param userdata : User's data
|
||||
* @param cb_draw_ram : the callback function of userdata to draw a !RAM! string (actural it is to draw a one byte string in RAM)
|
||||
* @param cb_draw_ram : the callback function of userdata to draw a !RAM! string (actually it is to draw a one byte string in RAM)
|
||||
*
|
||||
* @return N/A
|
||||
*
|
||||
|
|
|
@ -41,7 +41,10 @@
|
|||
|
||||
#include "ultralcd_DOGM.h"
|
||||
#include "u8g_fontutf8.h"
|
||||
|
||||
#if ENABLED(SHOW_BOOTSCREEN)
|
||||
#include "dogm_Bootscreen.h"
|
||||
#endif
|
||||
|
||||
#include "../lcdprint.h"
|
||||
#include "../fontutils.h"
|
||||
|
@ -138,6 +141,9 @@ void MarlinUI::set_font(const MarlinFont font_nr) {
|
|||
#else
|
||||
draw_custom_bootscreen(custom_start_bmp);
|
||||
#endif
|
||||
#ifndef CUSTOM_BOOTSCREEN_TIMEOUT
|
||||
#define CUSTOM_BOOTSCREEN_TIMEOUT 2500
|
||||
#endif
|
||||
safe_delay(CUSTOM_BOOTSCREEN_TIMEOUT);
|
||||
}
|
||||
|
||||
|
@ -148,31 +154,58 @@ void MarlinUI::set_font(const MarlinFont font_nr) {
|
|||
lcd_custom_bootscreen();
|
||||
#endif
|
||||
|
||||
constexpr uint8_t offy =
|
||||
#if ENABLED(START_BMPHIGH)
|
||||
(LCD_PIXEL_HEIGHT - (START_BMPHEIGHT)) / 2
|
||||
#else
|
||||
MENU_FONT_HEIGHT
|
||||
#endif
|
||||
;
|
||||
// Screen dimensions.
|
||||
//const uint8_t width = u8g.getWidth(), height = u8g.getHeight();
|
||||
constexpr uint8_t width = LCD_PIXEL_WIDTH, height = LCD_PIXEL_HEIGHT;
|
||||
|
||||
const uint8_t width = u8g.getWidth(), height = u8g.getHeight(),
|
||||
offx = (width - (START_BMPWIDTH)) / 2;
|
||||
// Determine text space needed
|
||||
#ifndef STRING_SPLASH_LINE2
|
||||
constexpr uint8_t text_total_height = MENU_FONT_HEIGHT,
|
||||
text_width_1 = (sizeof(STRING_SPLASH_LINE1) - 1) * (MENU_FONT_WIDTH),
|
||||
text_width_2 = 0;
|
||||
#else
|
||||
constexpr uint8_t text_total_height = (MENU_FONT_HEIGHT) * 2,
|
||||
text_width_1 = (sizeof(STRING_SPLASH_LINE1) - 1) * (MENU_FONT_WIDTH),
|
||||
text_width_2 = (sizeof(STRING_SPLASH_LINE2) - 1) * (MENU_FONT_WIDTH);
|
||||
#endif
|
||||
constexpr uint8_t text_max_width = MAX(text_width_1, text_width_2),
|
||||
rspace = width - (START_BMPWIDTH);
|
||||
|
||||
int8_t offx, offy, txt_base, txt_offx_1, txt_offx_2;
|
||||
|
||||
// Can the text fit to the right of the bitmap?
|
||||
if (text_max_width < rspace) {
|
||||
constexpr uint8_t inter = (width - text_max_width - (START_BMPWIDTH)) / 3; // Evenly distribute horizontal space
|
||||
offx = inter; // First the boot logo...
|
||||
offy = (height - (START_BMPHEIGHT)) / 2; // ...V-aligned in the full height
|
||||
txt_offx_1 = txt_offx_2 = inter + (START_BMPWIDTH) + inter; // Text right of the bitmap
|
||||
txt_base = (height + MENU_FONT_ASCENT + text_total_height - (MENU_FONT_HEIGHT)) / 2; // Text vertical center
|
||||
}
|
||||
else {
|
||||
constexpr uint8_t inter = (height - text_total_height - (START_BMPHEIGHT)) / 3; // Evenly distribute vertical space
|
||||
offy = inter; // V-align boot logo proportionally
|
||||
offx = rspace / 2; // Center the boot logo in the whole space
|
||||
txt_offx_1 = (width - text_width_1) / 2; // Text 1 centered
|
||||
txt_offx_2 = (width - text_width_2) / 2; // Text 2 centered
|
||||
txt_base = offy + START_BMPHEIGHT + offy + text_total_height - (MENU_FONT_DESCENT); // Even spacing looks best
|
||||
}
|
||||
NOLESS(offx, 0);
|
||||
NOLESS(offy, 0);
|
||||
|
||||
u8g.firstPage();
|
||||
do {
|
||||
u8g.drawBitmapP(offx, offy, (START_BMPWIDTH + 7) / 8, START_BMPHEIGHT, start_bmp);
|
||||
set_font(FONT_MENU);
|
||||
#ifndef STRING_SPLASH_LINE2
|
||||
const uint8_t txt1X = width - (sizeof(STRING_SPLASH_LINE1) - 1) * (MENU_FONT_WIDTH);
|
||||
u8g.drawStr(txt1X, (height + MENU_FONT_HEIGHT) / 2, STRING_SPLASH_LINE1);
|
||||
u8g.drawStr(txt_offx_1, txt_base, STRING_SPLASH_LINE1);
|
||||
#else
|
||||
const uint8_t txt1X = (width - (sizeof(STRING_SPLASH_LINE1) - 1) * (MENU_FONT_WIDTH)) / 2,
|
||||
txt2X = (width - (sizeof(STRING_SPLASH_LINE2) - 1) * (MENU_FONT_WIDTH)) / 2;
|
||||
u8g.drawStr(txt1X, height - (MENU_FONT_HEIGHT) * 3 / 2, STRING_SPLASH_LINE1);
|
||||
u8g.drawStr(txt2X, height - (MENU_FONT_HEIGHT) * 1 / 2, STRING_SPLASH_LINE2);
|
||||
u8g.drawStr(txt_offx_1, txt_base - (MENU_FONT_HEIGHT), STRING_SPLASH_LINE1);
|
||||
u8g.drawStr(txt_offx_2, txt_base, STRING_SPLASH_LINE2);
|
||||
#endif
|
||||
} while (u8g.nextPage());
|
||||
#ifndef BOOTSCREEN_TIMEOUT
|
||||
#define BOOTSCREEN_TIMEOUT 2500
|
||||
#endif
|
||||
safe_delay(BOOTSCREEN_TIMEOUT);
|
||||
}
|
||||
|
||||
|
@ -380,7 +413,7 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop
|
|||
if (value != NULL) {
|
||||
lcd_put_wchar(':');
|
||||
if (extra_row) {
|
||||
// Assume the value is numeric (with no descender)
|
||||
// Assume that value is numeric (with no descender)
|
||||
baseline += EDIT_FONT_ASCENT + 2;
|
||||
onpage = PAGE_CONTAINS(baseline - (EDIT_FONT_ASCENT - 1), baseline);
|
||||
}
|
||||
|
@ -392,6 +425,27 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop
|
|||
}
|
||||
}
|
||||
|
||||
inline void draw_boxed_string(const uint8_t x, const uint8_t y, PGM_P const pstr, const bool inv) {
|
||||
const uint8_t len = utf8_strlen_P(pstr), bw = len * (MENU_FONT_WIDTH),
|
||||
bx = x * (MENU_FONT_WIDTH), by = (y + 1) * (MENU_FONT_HEIGHT);
|
||||
if (inv) {
|
||||
u8g.setColorIndex(1);
|
||||
u8g.drawBox(bx - 1, by - (MENU_FONT_ASCENT) + 1, bw + 2, MENU_FONT_HEIGHT - 1);
|
||||
u8g.setColorIndex(0);
|
||||
}
|
||||
lcd_moveto(bx, by);
|
||||
lcd_put_u8str_P(pstr);
|
||||
if (inv) u8g.setColorIndex(1);
|
||||
}
|
||||
|
||||
void draw_select_screen(PGM_P const yes, PGM_P const no, const bool yesno, PGM_P const pref, const char * const string, PGM_P const suff) {
|
||||
SETCURSOR(0, 0); lcd_put_u8str_P(pref);
|
||||
if (string) wrap_string(1, string);
|
||||
if (suff) lcd_put_u8str_P(suff);
|
||||
draw_boxed_string(1, LCD_HEIGHT - 1, no, !yesno);
|
||||
draw_boxed_string(LCD_WIDTH - (utf8_strlen_P(yes) + 1), LCD_HEIGHT - 1, yes, yesno);
|
||||
}
|
||||
|
||||
#if ENABLED(SDSUPPORT)
|
||||
|
||||
void draw_sd_menu_item(const bool sel, const uint8_t row, PGM_P const pstr, CardReader &theCard, const bool isDir) {
|
||||
|
@ -500,22 +554,22 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop
|
|||
#if EITHER(BABYSTEP_ZPROBE_GFX_OVERLAY, MESH_EDIT_GFX_OVERLAY)
|
||||
|
||||
const unsigned char cw_bmp[] PROGMEM = {
|
||||
B00000011,B11111000,B00000000,
|
||||
B00001111,B11111110,B00000000,
|
||||
B00011110,B00001111,B00000000,
|
||||
B00111000,B00000111,B00000000,
|
||||
B00111000,B00000011,B10000000,
|
||||
B01110000,B00000011,B10000000,
|
||||
B01110000,B00001111,B11100000,
|
||||
B01110000,B00000111,B11000000,
|
||||
B01110000,B00000011,B10000000,
|
||||
B01110000,B00000001,B00000000,
|
||||
B01110000,B00000000,B00000000,
|
||||
B00111000,B00000000,B00000000,
|
||||
B00111000,B00000111,B00000000,
|
||||
B00011110,B00001111,B00000000,
|
||||
B00001111,B11111110,B00000000,
|
||||
B00000011,B11111000,B00000000
|
||||
B00000001,B11111100,B00000000,
|
||||
B00000111,B11111111,B00000000,
|
||||
B00001111,B00000111,B10000000,
|
||||
B00001110,B00000001,B11000000,
|
||||
B00000000,B00000001,B11000000,
|
||||
B00000000,B00000000,B11100000,
|
||||
B00001000,B00000000,B11100000,
|
||||
B00011100,B00000000,B11100000,
|
||||
B00111110,B00000000,B11100000,
|
||||
B01111111,B00000000,B11100000,
|
||||
B00011100,B00000000,B11100000,
|
||||
B00001110,B00000000,B11100000,
|
||||
B00001110,B00000001,B11000000,
|
||||
B00000111,B10000011,B11000000,
|
||||
B00000011,B11111111,B10000000,
|
||||
B00000000,B11111110,B00000000
|
||||
};
|
||||
|
||||
const unsigned char ccw_bmp[] PROGMEM = {
|
||||
|
@ -615,10 +669,10 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop
|
|||
|
||||
// Draw cw/ccw indicator and up/down arrows.
|
||||
if (PAGE_CONTAINS(47, 62)) {
|
||||
u8g.drawBitmapP(left + 0, 47, 3, 16, rot_down);
|
||||
u8g.drawBitmapP(right + 0, 47, 3, 16, rot_up);
|
||||
u8g.drawBitmapP(right + 20, 48 - dir, 2, 13, up_arrow_bmp);
|
||||
u8g.drawBitmapP(left + 20, 49 - dir, 2, 13, down_arrow_bmp);
|
||||
u8g.drawBitmapP(right + 0, 48 - dir, 2, 13, up_arrow_bmp);
|
||||
u8g.drawBitmapP(left + 0, 49 - dir, 2, 13, down_arrow_bmp);
|
||||
u8g.drawBitmapP(left + 13, 47, 3, 16, rot_down);
|
||||
u8g.drawBitmapP(right + 13, 47, 3, 16, rot_up);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -107,7 +107,7 @@
|
|||
// Generic support for SSD1309 OLED I2C LCDs
|
||||
#define U8G_CLASS U8GLIB_SSD1309_128X64
|
||||
#define U8G_PARAM (U8G_I2C_OPT_NONE | U8G_I2C_OPT_FAST)
|
||||
#elif ENABLED(MINIPANEL)
|
||||
#elif EITHER(MINIPANEL, FYSETC_MINI_12864)
|
||||
// The MINIPanel display
|
||||
//#define U8G_CLASS U8GLIB_MINI12864
|
||||
//#define U8G_PARAM DOGLCD_CS, DOGLCD_A0 // 8 stripes
|
||||
|
|
|
@ -97,6 +97,10 @@
|
|||
#include "../../feature/runout.h"
|
||||
#endif
|
||||
|
||||
#if ENABLED(BABYSTEPPING)
|
||||
#include "../../feature/babystep.h"
|
||||
#endif
|
||||
|
||||
inline float clamp(const float value, const float minimum, const float maximum) {
|
||||
return MAX(MIN(value, maximum), minimum);
|
||||
}
|
||||
|
@ -584,10 +588,10 @@ namespace ExtUI {
|
|||
bool babystepAxis_steps(const int16_t steps, const axis_t axis) {
|
||||
switch (axis) {
|
||||
#if ENABLED(BABYSTEP_XY)
|
||||
case X: thermalManager.babystep_axis(X_AXIS, steps); break;
|
||||
case Y: thermalManager.babystep_axis(Y_AXIS, steps); break;
|
||||
case X: babystep.add_steps(X_AXIS, steps); break;
|
||||
case Y: babystep.add_steps(Y_AXIS, steps); break;
|
||||
#endif
|
||||
case Z: thermalManager.babystep_axis(Z_AXIS, steps); break;
|
||||
case Z: babystep.add_steps(Z_AXIS, steps); break;
|
||||
default: return false;
|
||||
};
|
||||
return true;
|
||||
|
|
|
@ -34,6 +34,8 @@
|
|||
#define THIS_LANGUAGES_SPECIAL_SYMBOLS _UxGT("ÄäÖöÜüß²³")
|
||||
|
||||
#define WELCOME_MSG MACHINE_NAME _UxGT(" bereit")
|
||||
#define MSG_YES _UxGT("JA")
|
||||
#define MSG_NO _UxGT("NEIN")
|
||||
#define MSG_BACK _UxGT("Zurück")
|
||||
#define MSG_SD_INSERTED _UxGT("SD-Karte erkannt")
|
||||
#define MSG_SD_REMOVED _UxGT("SD-Karte entfernt")
|
||||
|
@ -97,14 +99,14 @@
|
|||
#define MSG_UBL_TOOLS _UxGT("UBL-Werkzeuge")
|
||||
#define MSG_UBL_LEVEL_BED _UxGT("Unified Bed Leveling")
|
||||
#define MSG_IDEX_MENU _UxGT("IDEX-Modus")
|
||||
#define MSG_OFFSETS_MENU _UxGT("Werkzeugversätze")
|
||||
#define MSG_IDEX_MODE_AUTOPARK _UxGT("Autom. Parken")
|
||||
#define MSG_IDEX_MODE_DUPLICATE _UxGT("Duplizieren")
|
||||
#define MSG_IDEX_MODE_MIRRORED_COPY _UxGT("Spiegelkopie")
|
||||
#define MSG_IDEX_MODE_FULL_CTRL _UxGT("vollstä. Kontrolle")
|
||||
#define MSG_IDEX_X_OFFSET _UxGT("2. Düse X")
|
||||
#define MSG_IDEX_Y_OFFSET _UxGT("2. Düse Y")
|
||||
#define MSG_IDEX_Z_OFFSET _UxGT("2. Düse Z")
|
||||
#define MSG_IDEX_SAVE_OFFSETS _UxGT("Versätze speichern")
|
||||
#define MSG_X_OFFSET _UxGT("2. Düse X")
|
||||
#define MSG_Y_OFFSET _UxGT("2. Düse Y")
|
||||
#define MSG_Z_OFFSET _UxGT("2. Düse Z")
|
||||
#define MSG_UBL_MANUAL_MESH _UxGT("Netz manuell erst.")
|
||||
#define MSG_UBL_BC_INSERT _UxGT("Unterlegen & messen")
|
||||
#define MSG_UBL_BC_INSERT2 _UxGT("Messen")
|
||||
|
@ -197,6 +199,7 @@
|
|||
#define MSG_BED_Z _UxGT("Bett Z")
|
||||
#define MSG_NOZZLE _UxGT("Düse")
|
||||
#define MSG_BED _UxGT("Bett")
|
||||
#define MSG_CHAMBER _UxGT("Gehäuse")
|
||||
#define MSG_FAN_SPEED _UxGT("Lüfter")
|
||||
#define MSG_EXTRA_FAN_SPEED _UxGT("Geschw. Extralüfter")
|
||||
#define MSG_FLOW _UxGT("Flussrate")
|
||||
|
@ -269,6 +272,9 @@
|
|||
#define MSG_WATCH _UxGT("Info")
|
||||
#define MSG_PREPARE _UxGT("Vorbereitung")
|
||||
#define MSG_TUNE _UxGT("Justierung")
|
||||
#define MSG_START_PRINT _UxGT("Starte Druck")
|
||||
#define MSG_BUTTON_PRINT _UxGT("Drucke")
|
||||
#define MSG_BUTTON_CANCEL _UxGT("Abbrechen")
|
||||
#define MSG_PAUSE_PRINT _UxGT("SD-Druck pausieren")
|
||||
#define MSG_RESUME_PRINT _UxGT("SD-Druck fortsetzen")
|
||||
#define MSG_STOP_PRINT _UxGT("SD-Druck abbrechen")
|
||||
|
@ -310,6 +316,9 @@
|
|||
#define MSG_BLTOUCH_SELFTEST _UxGT("BLTouch Selbsttest")
|
||||
#define MSG_BLTOUCH_RESET _UxGT("BLTouch zurücks.")
|
||||
#define MSG_BLTOUCH_DEPLOY _UxGT("BLTouch ausfahren")
|
||||
#define MSG_BLTOUCH_SW_MODE _UxGT("BLTouch SW-Modus")
|
||||
#define MSG_BLTOUCH_5V_MODE _UxGT("BLTouch 5V-Modus")
|
||||
#define MSG_BLTOUCH_STOW _UxGT("BLTouch einfahren")
|
||||
#define MSG_BLTOUCH_STOW _UxGT("BLTouch einfahren")
|
||||
#define MSG_MANUAL_DEPLOY _UxGT("Z-Sonde ausfahren")
|
||||
#define MSG_MANUAL_STOW _UxGT("Z-Sonde einfahren")
|
||||
|
@ -319,6 +328,7 @@
|
|||
#define MSG_BABYSTEP_X _UxGT("Babystep X")
|
||||
#define MSG_BABYSTEP_Y _UxGT("Babystep Y")
|
||||
#define MSG_BABYSTEP_Z _UxGT("Babystep Z")
|
||||
#define MSG_BABYSTEP_TOTAL _UxGT("Total")
|
||||
#define MSG_ENDSTOP_ABORT _UxGT("Endstopp Abbr.")
|
||||
#define MSG_HEATING_FAILED_LCD _UxGT("HEIZEN ERFOLGLOS")
|
||||
#define MSG_HEATING_FAILED_LCD_BED _UxGT("Bett heizen fehlge.")
|
||||
|
@ -329,6 +339,8 @@
|
|||
#define MSG_ERR_MINTEMP LCD_STR_THERMOMETER _UxGT(" UNTERSCHRITTEN")
|
||||
#define MSG_ERR_MAXTEMP_BED _UxGT("BETT ") LCD_STR_THERMOMETER _UxGT(" ÜBERSCHRITTEN")
|
||||
#define MSG_ERR_MINTEMP_BED _UxGT("BETT ") LCD_STR_THERMOMETER _UxGT(" UNTERSCHRITTEN")
|
||||
#define MSG_ERR_MAXTEMP_CHAMBER _UxGT("Err: GEHÄUSE MAX TEM")
|
||||
#define MSG_ERR_MINTEMP_CHAMBER _UxGT("Err: GEHÄUSE MIN TEM")
|
||||
#define MSG_ERR_Z_HOMING MSG_HOME _UxGT(" ") MSG_X MSG_Y _UxGT(" ") MSG_FIRST
|
||||
#define MSG_HALTED _UxGT("DRUCKER STOPP")
|
||||
#define MSG_PLEASE_RESET _UxGT("Bitte neustarten")
|
||||
|
@ -447,6 +459,10 @@
|
|||
#define MSG_VTOOLS_RESET _UxGT("V-Tools ist resetet")
|
||||
#define MSG_START_Z _UxGT("Z Start")
|
||||
#define MSG_END_Z _UxGT("Z End")
|
||||
#define MSG_BRICKOUT _UxGT("Brickout")
|
||||
#define MSG_INVADERS _UxGT("Invaders")
|
||||
#define MSG_SNAKE _UxGT("Sn4k3")
|
||||
#define MSG_MAZE _UxGT("Maze")
|
||||
|
||||
//
|
||||
// Die Filament-Change-Bildschirme können bis zu 3 Zeilen auf einem 4-Zeilen-Display anzeigen
|
||||
|
@ -454,6 +470,7 @@
|
|||
#if LCD_HEIGHT >= 4
|
||||
#define MSG_ADVANCED_PAUSE_WAITING_1 _UxGT("Knopf drücken um")
|
||||
#define MSG_ADVANCED_PAUSE_WAITING_2 _UxGT("Druck fortzusetzen")
|
||||
#define MSG_PAUSE_PRINT_INIT_1 _UxGT("Parken...")
|
||||
#define MSG_FILAMENT_CHANGE_INIT_1 _UxGT("Warte auf den")
|
||||
#define MSG_FILAMENT_CHANGE_INIT_2 _UxGT("Start des")
|
||||
#define MSG_FILAMENT_CHANGE_INIT_3 _UxGT("Filamentwechsels...")
|
||||
|
@ -499,3 +516,8 @@
|
|||
#define MSG_TMC_HOMING_THRS _UxGT("Sensorloses Homing")
|
||||
#define MSG_TMC_STEPPING_MODE _UxGT("Schrittmodus")
|
||||
#define MSG_TMC_STEALTH_ENABLED _UxGT("StealthChop einsch.")
|
||||
#define MSG_SERVICE_RESET _UxGT("Reset")
|
||||
#define MSG_SERVICE_IN _UxGT(" im:")
|
||||
#define MSG_BACKLASH _UxGT("Spiel")
|
||||
#define MSG_BACKLASH_CORRECTION _UxGT("Korrektur")
|
||||
#define MSG_BACKLASH_SMOOTHING _UxGT("Glätten")
|
||||
|
|
|
@ -52,6 +52,12 @@
|
|||
#ifndef WELCOME_MSG
|
||||
#define WELCOME_MSG MACHINE_NAME _UxGT(" Ready.")
|
||||
#endif
|
||||
#ifndef MSG_YES
|
||||
#define MSG_YES _UxGT("YES")
|
||||
#endif
|
||||
#ifndef MSG_NO
|
||||
#define MSG_NO _UxGT("NO")
|
||||
#endif
|
||||
#ifndef MSG_BACK
|
||||
#define MSG_BACK _UxGT("Back")
|
||||
#endif
|
||||
|
@ -241,6 +247,9 @@
|
|||
#ifndef MSG_IDEX_MENU
|
||||
#define MSG_IDEX_MENU _UxGT("IDEX Mode")
|
||||
#endif
|
||||
#ifndef MSG_OFFSETS_MENU
|
||||
#define MSG_OFFSETS_MENU _UxGT("Tool Offsets")
|
||||
#endif
|
||||
#ifndef MSG_IDEX_MODE_AUTOPARK
|
||||
#define MSG_IDEX_MODE_AUTOPARK _UxGT("Auto-Park")
|
||||
#endif
|
||||
|
@ -253,17 +262,14 @@
|
|||
#ifndef MSG_IDEX_MODE_FULL_CTRL
|
||||
#define MSG_IDEX_MODE_FULL_CTRL _UxGT("Full control")
|
||||
#endif
|
||||
#ifndef MSG_IDEX_X_OFFSET
|
||||
#define MSG_IDEX_X_OFFSET _UxGT("2nd nozzle X")
|
||||
#ifndef MSG_X_OFFSET
|
||||
#define MSG_X_OFFSET _UxGT("2nd nozzle X")
|
||||
#endif
|
||||
#ifndef MSG_IDEX_Y_OFFSET
|
||||
#define MSG_IDEX_Y_OFFSET _UxGT("2nd nozzle Y")
|
||||
#ifndef MSG_Y_OFFSET
|
||||
#define MSG_Y_OFFSET _UxGT("2nd nozzle Y")
|
||||
#endif
|
||||
#ifndef MSG_IDEX_Z_OFFSET
|
||||
#define MSG_IDEX_Z_OFFSET _UxGT("2nd nozzle Z")
|
||||
#endif
|
||||
#ifndef MSG_IDEX_SAVE_OFFSETS
|
||||
#define MSG_IDEX_SAVE_OFFSETS _UxGT("Save Offsets")
|
||||
#ifndef MSG_Z_OFFSET
|
||||
#define MSG_Z_OFFSET _UxGT("2nd nozzle Z")
|
||||
#endif
|
||||
#ifndef MSG_UBL_MANUAL_MESH
|
||||
#define MSG_UBL_MANUAL_MESH _UxGT("Manually Build Mesh")
|
||||
|
@ -744,6 +750,15 @@
|
|||
#ifndef MSG_TUNE
|
||||
#define MSG_TUNE _UxGT("Tune")
|
||||
#endif
|
||||
#ifndef MSG_START_PRINT
|
||||
#define MSG_START_PRINT _UxGT("Start print")
|
||||
#endif
|
||||
#ifndef MSG_BUTTON_PRINT
|
||||
#define MSG_BUTTON_PRINT _UxGT("Print")
|
||||
#endif
|
||||
#ifndef MSG_BUTTON_CANCEL
|
||||
#define MSG_BUTTON_CANCEL _UxGT("Cancel")
|
||||
#endif
|
||||
#ifndef MSG_PAUSE_PRINT
|
||||
#define MSG_PAUSE_PRINT _UxGT("Pause print")
|
||||
#endif
|
||||
|
@ -903,6 +918,9 @@
|
|||
#ifndef MSG_BABYSTEP_Z
|
||||
#define MSG_BABYSTEP_Z _UxGT("Babystep Z")
|
||||
#endif
|
||||
#ifndef MSG_BABYSTEP_TOTAL
|
||||
#define MSG_BABYSTEP_TOTAL _UxGT("Total")
|
||||
#endif
|
||||
#ifndef MSG_ENDSTOP_ABORT
|
||||
#define MSG_ENDSTOP_ABORT _UxGT("Endstop abort")
|
||||
#endif
|
||||
|
|
|
@ -32,6 +32,8 @@
|
|||
#define DISPLAY_CHARSET_ISO10646_1
|
||||
|
||||
#define WELCOME_MSG MACHINE_NAME _UxGT(" pronto.")
|
||||
#define MSG_YES _UxGT("SI")
|
||||
#define MSG_NO _UxGT("NO")
|
||||
#define MSG_BACK _UxGT("Indietro")
|
||||
#define MSG_SD_INSERTED _UxGT("SD Card inserita")
|
||||
#define MSG_SD_REMOVED _UxGT("SD Card rimossa")
|
||||
|
@ -95,14 +97,14 @@
|
|||
#define MSG_UBL_TOOLS _UxGT("Strumenti UBL")
|
||||
#define MSG_UBL_LEVEL_BED _UxGT("Unified Bed Leveling")
|
||||
#define MSG_IDEX_MENU _UxGT("Modo IDEX")
|
||||
#define MSG_OFFSETS_MENU _UxGT("Strumenti Offsets")
|
||||
#define MSG_IDEX_MODE_AUTOPARK _UxGT("Auto-Park")
|
||||
#define MSG_IDEX_MODE_DUPLICATE _UxGT("Duplicazione")
|
||||
#define MSG_IDEX_MODE_MIRRORED_COPY _UxGT("Copia speculare")
|
||||
#define MSG_IDEX_MODE_FULL_CTRL _UxGT("Pieno controllo")
|
||||
#define MSG_IDEX_X_OFFSET _UxGT("2° ugello X")
|
||||
#define MSG_IDEX_Y_OFFSET _UxGT("2° ugello Y")
|
||||
#define MSG_IDEX_Z_OFFSET _UxGT("2° ugello Z")
|
||||
#define MSG_IDEX_SAVE_OFFSETS _UxGT("Memorizza Offsets")
|
||||
#define MSG_X_OFFSET _UxGT("2° ugello X")
|
||||
#define MSG_Y_OFFSET _UxGT("2° ugello Y")
|
||||
#define MSG_Z_OFFSET _UxGT("2° ugello Z")
|
||||
#define MSG_UBL_MANUAL_MESH _UxGT("Mesh Manuale")
|
||||
#define MSG_UBL_BC_INSERT _UxGT("Metti spes. e misura")
|
||||
#define MSG_UBL_BC_INSERT2 _UxGT("Misura")
|
||||
|
@ -268,6 +270,9 @@
|
|||
#define MSG_WATCH _UxGT("Schermata info")
|
||||
#define MSG_PREPARE _UxGT("Prepara")
|
||||
#define MSG_TUNE _UxGT("Regola")
|
||||
#define MSG_START_PRINT _UxGT("Avvia stampa")
|
||||
#define MSG_BUTTON_PRINT _UxGT("Stampa")
|
||||
#define MSG_BUTTON_CANCEL _UxGT("Annulla")
|
||||
#define MSG_PAUSE_PRINT _UxGT("Pausa stampa")
|
||||
#define MSG_RESUME_PRINT _UxGT("Riprendi stampa")
|
||||
#define MSG_STOP_PRINT _UxGT("Arresta stampa")
|
||||
|
@ -321,6 +326,7 @@
|
|||
#define MSG_BABYSTEP_X _UxGT("Babystep X")
|
||||
#define MSG_BABYSTEP_Y _UxGT("Babystep Y")
|
||||
#define MSG_BABYSTEP_Z _UxGT("Babystep Z")
|
||||
#define MSG_BABYSTEP_TOTAL _UxGT("Totali")
|
||||
#define MSG_ENDSTOP_ABORT _UxGT("Finecorsa annullati")
|
||||
#define MSG_HEATING_FAILED_LCD _UxGT("Riscald. Fallito")
|
||||
#define MSG_HEATING_FAILED_LCD_BED _UxGT("Risc. piatto fallito")
|
||||
|
@ -449,6 +455,10 @@
|
|||
#define MSG_VTOOLS_RESET _UxGT("V-tools ripristin.")
|
||||
#define MSG_START_Z _UxGT("Z inizio")
|
||||
#define MSG_END_Z _UxGT("Z fine")
|
||||
#define MSG_BRICKOUT _UxGT("Brickout")
|
||||
#define MSG_INVADERS _UxGT("Invaders")
|
||||
#define MSG_SNAKE _UxGT("Sn4k3")
|
||||
#define MSG_MAZE _UxGT("Maze")
|
||||
|
||||
//
|
||||
// Le schermate di Cambio Filamento possono visualizzare fino a 3 linee su un display a 4 righe
|
||||
|
@ -505,3 +515,7 @@
|
|||
|
||||
#define MSG_SERVICE_RESET _UxGT("Resetta")
|
||||
#define MSG_SERVICE_IN _UxGT(" tra:")
|
||||
|
||||
#define MSG_BACKLASH _UxGT("Gioco")
|
||||
#define MSG_BACKLASH_CORRECTION _UxGT("Correzione")
|
||||
#define MSG_BACKLASH_SMOOTHING _UxGT("Smoothing")
|
||||
|
|
|
@ -90,10 +90,9 @@
|
|||
#define MSG_IDEX_MODE_DUPLICATE _UxGT("Duplication")
|
||||
#define MSG_IDEX_MODE_MIRRORED_COPY _UxGT("미러 사본")
|
||||
#define MSG_IDEX_MODE_FULL_CTRL _UxGT("Full control")
|
||||
#define MSG_IDEX_X_OFFSET _UxGT("2nd nozzle X")
|
||||
#define MSG_IDEX_Y_OFFSET _UxGT("2nd nozzle Y")
|
||||
#define MSG_IDEX_Z_OFFSET _UxGT("2nd nozzle Z")
|
||||
#define MSG_IDEX_SAVE_OFFSETS _UxGT("Save Offsets")
|
||||
#define MSG_X_OFFSET _UxGT("2nd nozzle X")
|
||||
#define MSG_Y_OFFSET _UxGT("2nd nozzle Y")
|
||||
#define MSG_Z_OFFSET _UxGT("2nd nozzle Z")
|
||||
#define MSG_UBL_MANUAL_MESH _UxGT("Manually Build Mesh")
|
||||
#define MSG_UBL_BC_INSERT _UxGT("Place shim & measure")
|
||||
#define MSG_UBL_BC_INSERT2 _UxGT("Measure")
|
||||
|
|
|
@ -101,10 +101,9 @@
|
|||
#define MSG_IDEX_MODE_DUPLICATE _UxGT("Duplicação")
|
||||
#define MSG_IDEX_MODE_MIRRORED_COPY _UxGT("Cópia espelhada")
|
||||
#define MSG_IDEX_MODE_FULL_CTRL _UxGT("Controle Total")
|
||||
#define MSG_IDEX_X_OFFSET _UxGT("2o bico X")
|
||||
#define MSG_IDEX_Y_OFFSET _UxGT("2o bico Y")
|
||||
#define MSG_IDEX_Z_OFFSET _UxGT("2o bico Z")
|
||||
#define MSG_IDEX_SAVE_OFFSETS _UxGT("Salvar Compensação")
|
||||
#define MSG_X_OFFSET _UxGT("2o bico X")
|
||||
#define MSG_Y_OFFSET _UxGT("2o bico Y")
|
||||
#define MSG_Z_OFFSET _UxGT("2o bico Z")
|
||||
|
||||
#define MSG_UBL_MANUAL_MESH _UxGT("Fazer malha manual")
|
||||
#define MSG_UBL_BC_INSERT _UxGT("Calçar e calibrar")
|
||||
|
|
|
@ -108,10 +108,9 @@
|
|||
#define MSG_IDEX_MODE_DUPLICATE _UxGT("Duplikácia")
|
||||
#define MSG_IDEX_MODE_MIRRORED_COPY _UxGT("Zrkadlená kópia")
|
||||
#define MSG_IDEX_MODE_FULL_CTRL _UxGT("Plná kontrola")
|
||||
#define MSG_IDEX_X_OFFSET _UxGT("2. tryska X")
|
||||
#define MSG_IDEX_Y_OFFSET _UxGT("2. tryska Y")
|
||||
#define MSG_IDEX_Z_OFFSET _UxGT("2. tryska Z")
|
||||
#define MSG_IDEX_SAVE_OFFSETS _UxGT("Uložiť offsety")
|
||||
#define MSG_X_OFFSET _UxGT("2. tryska X")
|
||||
#define MSG_Y_OFFSET _UxGT("2. tryska Y")
|
||||
#define MSG_Z_OFFSET _UxGT("2. tryska Z")
|
||||
#define MSG_UBL_MANUAL_MESH _UxGT("Manuálna sieť bodov")
|
||||
#define MSG_UBL_BC_INSERT _UxGT("Položte a zmerajte")
|
||||
#define MSG_UBL_BC_INSERT2 _UxGT("Zmerajte")
|
||||
|
|
|
@ -100,10 +100,9 @@
|
|||
#define MSG_IDEX_MODE_DUPLICATE _UxGT("Kopyala")
|
||||
#define MSG_IDEX_MODE_MIRRORED_COPY _UxGT("Yansıtılmış kopya")
|
||||
#define MSG_IDEX_MODE_FULL_CTRL _UxGT("Tam Kontrol")
|
||||
#define MSG_IDEX_X_OFFSET _UxGT("2. nozul X")
|
||||
#define MSG_IDEX_Y_OFFSET _UxGT("2. nozul Y")
|
||||
#define MSG_IDEX_Z_OFFSET _UxGT("2. nozul Z")
|
||||
#define MSG_IDEX_SAVE_OFFSETS _UxGT("Ofsetleri Kaydet")
|
||||
#define MSG_X_OFFSET _UxGT("2. nozul X")
|
||||
#define MSG_Y_OFFSET _UxGT("2. nozul Y")
|
||||
#define MSG_Z_OFFSET _UxGT("2. nozul Z")
|
||||
#define MSG_UBL_MANUAL_MESH _UxGT("Elle Mesh Oluştur")
|
||||
#define MSG_UBL_BC_INSERT _UxGT("Altlık & Ölçü Ver")
|
||||
#define MSG_UBL_BC_INSERT2 _UxGT("Ölçü")
|
||||
|
|
213
Marlin/src/lcd/menu/game/brickout.cpp
Normal file
213
Marlin/src/lcd/menu/game/brickout.cpp
Normal file
|
@ -0,0 +1,213 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2019 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 "../../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if ENABLED(MARLIN_BRICKOUT)
|
||||
|
||||
#include "game.h"
|
||||
|
||||
#define BRICK_H 5
|
||||
#define BRICK_TOP MENU_FONT_ASCENT
|
||||
#define BRICK_ROWS 4
|
||||
#define BRICK_COLS 16
|
||||
|
||||
#define PADDLE_H 2
|
||||
#define PADDLE_VEL 3
|
||||
#define PADDLE_W ((LCD_PIXEL_WIDTH) / 8)
|
||||
#define PADDLE_Y (LCD_PIXEL_HEIGHT - 1 - PADDLE_H)
|
||||
|
||||
#define BRICK_W ((LCD_PIXEL_WIDTH) / (BRICK_COLS))
|
||||
#define BRICK_BOT (BRICK_TOP + BRICK_H * BRICK_ROWS - 1)
|
||||
|
||||
#define BRICK_COL(X) ((X) / (BRICK_W))
|
||||
#define BRICK_ROW(Y) ((Y - (BRICK_TOP)) / (BRICK_H))
|
||||
|
||||
uint8_t balls_left, brick_count;
|
||||
uint16_t bricks[BRICK_ROWS];
|
||||
|
||||
inline void reset_bricks(const uint16_t v) {
|
||||
brick_count = (BRICK_COLS) * (BRICK_ROWS);
|
||||
LOOP_L_N(i, BRICK_ROWS) bricks[i] = v;
|
||||
}
|
||||
|
||||
int8_t paddle_x, hit_dir;
|
||||
fixed_t ballx, bally, ballh, ballv;
|
||||
|
||||
void reset_ball() {
|
||||
constexpr uint8_t ball_dist = 24;
|
||||
bally = BTOF(PADDLE_Y - ball_dist);
|
||||
ballv = FTOP(1.3f);
|
||||
ballh = -FTOP(1.25f);
|
||||
uint8_t bx = paddle_x + (PADDLE_W) / 2 + ball_dist;
|
||||
if (bx >= LCD_PIXEL_WIDTH - 10) { bx -= ball_dist * 2; ballh = -ballh; }
|
||||
ballx = BTOF(bx);
|
||||
hit_dir = -1;
|
||||
}
|
||||
|
||||
void BrickoutGame::game_screen() {
|
||||
if (game_frame()) { // Run logic twice for finer resolution
|
||||
// Update Paddle Position
|
||||
paddle_x = (int8_t)ui.encoderPosition;
|
||||
paddle_x = constrain(paddle_x, 0, (LCD_PIXEL_WIDTH - (PADDLE_W)) / (PADDLE_VEL));
|
||||
ui.encoderPosition = paddle_x;
|
||||
paddle_x *= (PADDLE_VEL);
|
||||
|
||||
// Run the ball logic
|
||||
if (game_state) do {
|
||||
|
||||
// Provisionally update the ball position
|
||||
const fixed_t newx = ballx + ballh, newy = bally + ballv; // current next position
|
||||
if (!WITHIN(newx, 0, BTOF(LCD_PIXEL_WIDTH - 1))) { // out in x?
|
||||
ballh = -ballh; _BUZZ(5, 220); // bounce x
|
||||
}
|
||||
if (newy < 0) { // out in y?
|
||||
ballv = -ballv; _BUZZ(5, 280); // bounce v
|
||||
hit_dir = 1;
|
||||
}
|
||||
// Did the ball go below the bottom?
|
||||
else if (newy > BTOF(LCD_PIXEL_HEIGHT)) {
|
||||
BUZZ(500, 75);
|
||||
if (--balls_left) reset_ball(); else game_state = 0;
|
||||
break; // done
|
||||
}
|
||||
|
||||
// Is the ball colliding with a brick?
|
||||
if (WITHIN(newy, BTOF(BRICK_TOP), BTOF(BRICK_BOT))) {
|
||||
const int8_t bit = BRICK_COL(FTOB(newx)), row = BRICK_ROW(FTOB(newy));
|
||||
const uint16_t mask = _BV(bit);
|
||||
if (bricks[row] & mask) {
|
||||
// Yes. Remove it!
|
||||
bricks[row] &= ~mask;
|
||||
// Score!
|
||||
score += BRICK_ROWS - row;
|
||||
// If bricks are gone, go to reset state
|
||||
if (!--brick_count) game_state = 2;
|
||||
// Bounce the ball cleverly
|
||||
if ((ballv < 0) == (hit_dir < 0)) { ballv = -ballv; ballh += fixed_t(random(-16, 16)); _BUZZ(5, 880); }
|
||||
else { ballh = -ballh; ballv += fixed_t(random(-16, 16)); _BUZZ(5, 640); }
|
||||
}
|
||||
}
|
||||
// Is the ball moving down and in paddle range?
|
||||
else if (ballv > 0 && WITHIN(newy, BTOF(PADDLE_Y), BTOF(PADDLE_Y + PADDLE_H))) {
|
||||
// Ball actually hitting paddle
|
||||
const int8_t diff = FTOB(newx) - paddle_x;
|
||||
if (WITHIN(diff, 0, PADDLE_W - 1)) {
|
||||
|
||||
// Reverse Y direction
|
||||
ballv = -ballv; _BUZZ(3, 880);
|
||||
hit_dir = -1;
|
||||
|
||||
// Near edges affects X velocity
|
||||
const bool is_left_edge = (diff <= 1);
|
||||
if (is_left_edge || diff >= PADDLE_W-1 - 1) {
|
||||
if ((ballh > 0) == is_left_edge) ballh = -ballh;
|
||||
}
|
||||
else if (diff <= 3) {
|
||||
ballh += fixed_t(random(-64, 0));
|
||||
NOLESS(ballh, BTOF(-2));
|
||||
NOMORE(ballh, BTOF(2));
|
||||
}
|
||||
else if (diff >= PADDLE_W-1 - 3) {
|
||||
ballh += fixed_t(random( 0, 64));
|
||||
NOLESS(ballh, BTOF(-2));
|
||||
NOMORE(ballh, BTOF(2));
|
||||
}
|
||||
|
||||
// Paddle hit after clearing the board? Reset the board.
|
||||
if (game_state == 2) { reset_bricks(0xFFFF); game_state = 1; }
|
||||
}
|
||||
}
|
||||
|
||||
ballx += ballh; bally += ballv; // update with new velocity
|
||||
|
||||
} while (false);
|
||||
}
|
||||
|
||||
u8g.setColorIndex(1);
|
||||
|
||||
// Draw bricks
|
||||
if (PAGE_CONTAINS(BRICK_TOP, BRICK_BOT)) {
|
||||
for (uint8_t y = 0; y < BRICK_ROWS; ++y) {
|
||||
const uint8_t yy = y * BRICK_H + BRICK_TOP;
|
||||
if (PAGE_CONTAINS(yy, yy + BRICK_H - 1)) {
|
||||
for (uint8_t x = 0; x < BRICK_COLS; ++x) {
|
||||
if (TEST(bricks[y], x)) {
|
||||
const uint8_t xx = x * BRICK_W;
|
||||
for (uint8_t v = 0; v < BRICK_H - 1; ++v)
|
||||
if (PAGE_CONTAINS(yy + v, yy + v))
|
||||
u8g.drawHLine(xx, yy + v, BRICK_W - 1);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Draw paddle
|
||||
if (PAGE_CONTAINS(PADDLE_Y-1, PADDLE_Y)) {
|
||||
u8g.drawHLine(paddle_x, PADDLE_Y, PADDLE_W);
|
||||
#if PADDLE_H > 1
|
||||
u8g.drawHLine(paddle_x, PADDLE_Y-1, PADDLE_W);
|
||||
#if PADDLE_H > 2
|
||||
u8g.drawHLine(paddle_x, PADDLE_Y-2, PADDLE_W);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
// Draw ball while game is running
|
||||
if (game_state) {
|
||||
const uint8_t by = FTOB(bally);
|
||||
if (PAGE_CONTAINS(by, by+1))
|
||||
u8g.drawFrame(FTOB(ballx), by, 2, 2);
|
||||
}
|
||||
// Or draw GAME OVER
|
||||
else
|
||||
draw_game_over();
|
||||
|
||||
if (PAGE_UNDER(MENU_FONT_ASCENT)) {
|
||||
// Score Digits
|
||||
//const uint8_t sx = (LCD_PIXEL_WIDTH - (score >= 10 ? score >= 100 ? score >= 1000 ? 4 : 3 : 2 : 1) * MENU_FONT_WIDTH) / 2;
|
||||
constexpr uint8_t sx = 0;
|
||||
lcd_moveto(sx, MENU_FONT_ASCENT - 1);
|
||||
lcd_put_int(score);
|
||||
|
||||
// Balls Left
|
||||
lcd_moveto(LCD_PIXEL_WIDTH - MENU_FONT_WIDTH * 3, MENU_FONT_ASCENT - 1);
|
||||
PGM_P const ohs = PSTR("ooo\0\0");
|
||||
lcd_put_u8str_P(ohs + 3 - balls_left);
|
||||
}
|
||||
|
||||
// A click always exits this game
|
||||
if (ui.use_click()) exit_game();
|
||||
}
|
||||
|
||||
void BrickoutGame::enter_game() {
|
||||
init_game(2, game_screen); // 2 = reset bricks on paddle hit
|
||||
constexpr uint8_t paddle_start = SCREEN_M - (PADDLE_W) / 2;
|
||||
paddle_x = paddle_start;
|
||||
balls_left = 3;
|
||||
reset_bricks(0x0000);
|
||||
reset_ball();
|
||||
ui.encoderPosition = paddle_start / (PADDLE_VEL);
|
||||
}
|
||||
|
||||
#endif // MARLIN_BRICKOUT
|
68
Marlin/src/lcd/menu/game/game.cpp
Normal file
68
Marlin/src/lcd/menu/game/game.cpp
Normal file
|
@ -0,0 +1,68 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2019 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 "../../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if HAS_GAMES
|
||||
|
||||
#include "game.h"
|
||||
|
||||
int MarlinGame::score;
|
||||
uint8_t MarlinGame::game_state;
|
||||
millis_t MarlinGame::next_frame;
|
||||
|
||||
bool MarlinGame::game_frame() {
|
||||
static int8_t slew;
|
||||
if (ui.first_page) slew = 2;
|
||||
ui.refresh(LCDVIEW_CALL_NO_REDRAW); // Refresh as often as possible
|
||||
return (game_state && slew-- > 0);
|
||||
}
|
||||
|
||||
void MarlinGame::draw_game_over() {
|
||||
constexpr int8_t gowide = (MENU_FONT_WIDTH) * 9,
|
||||
gohigh = MENU_FONT_ASCENT - 3,
|
||||
lx = (LCD_PIXEL_WIDTH - gowide) / 2,
|
||||
ly = (LCD_PIXEL_HEIGHT + gohigh) / 2;
|
||||
if (PAGE_CONTAINS(ly - gohigh - 1, ly + 1)) {
|
||||
u8g.setColorIndex(0);
|
||||
u8g.drawBox(lx - 1, ly - gohigh - 1, gowide + 2, gohigh + 2);
|
||||
u8g.setColorIndex(1);
|
||||
if (ui.get_blink()) {
|
||||
lcd_moveto(lx, ly);
|
||||
lcd_put_u8str_P(PSTR("GAME OVER"));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void MarlinGame::init_game(const uint8_t init_state, const screenFunc_t screen) {
|
||||
score = 0;
|
||||
game_state = init_state;
|
||||
ui.encoder_direction_normal();
|
||||
ui.goto_screen(screen);
|
||||
ui.defer_status_screen();
|
||||
}
|
||||
|
||||
void MarlinGame::exit_game() {
|
||||
ui.goto_previous_screen_no_defer();
|
||||
}
|
||||
|
||||
#endif // HAS_GAMES
|
78
Marlin/src/lcd/menu/game/game.h
Normal file
78
Marlin/src/lcd/menu/game/game.h
Normal file
|
@ -0,0 +1,78 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2019 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/MarlinConfigPre.h"
|
||||
#include "../../dogm/ultralcd_DOGM.h"
|
||||
#include "../../lcdprint.h"
|
||||
#include "../../ultralcd.h"
|
||||
|
||||
//#define MUTE_GAMES
|
||||
|
||||
#ifdef MUTE_GAMES
|
||||
#define _BUZZ(D,F) NOOP
|
||||
#else
|
||||
#define _BUZZ(D,F) BUZZ(D,F)
|
||||
#endif
|
||||
|
||||
// Simple 8:8 fixed-point
|
||||
typedef int16_t fixed_t;
|
||||
#define FTOP(F) fixed_t((F)*256.0f)
|
||||
#define PTOF(P) (float(P)*(1.0f/256.0f))
|
||||
#define BTOF(X) (fixed_t(X)<<8)
|
||||
#define FTOB(X) int8_t(fixed_t(X)>>8)
|
||||
|
||||
#define SCREEN_M ((LCD_PIXEL_WIDTH) / 2)
|
||||
|
||||
#if HAS_GAME_MENU
|
||||
void menu_game();
|
||||
#endif
|
||||
|
||||
class MarlinGame {
|
||||
protected:
|
||||
static int score;
|
||||
static uint8_t game_state;
|
||||
static millis_t next_frame;
|
||||
|
||||
static bool game_frame();
|
||||
static void draw_game_over();
|
||||
static void exit_game();
|
||||
public:
|
||||
static void init_game(const uint8_t init_state, const screenFunc_t screen);
|
||||
};
|
||||
|
||||
#if ENABLED(MARLIN_BRICKOUT)
|
||||
class BrickoutGame : MarlinGame { public: static void enter_game(); static void game_screen(); };
|
||||
extern BrickoutGame brickout;
|
||||
#endif
|
||||
#if ENABLED(MARLIN_INVADERS)
|
||||
class InvadersGame : MarlinGame { public: static void enter_game(); static void game_screen(); };
|
||||
extern InvadersGame invaders;
|
||||
#endif
|
||||
#if ENABLED(MARLIN_SNAKE)
|
||||
class SnakeGame : MarlinGame { public: static void enter_game(); static void game_screen(); };
|
||||
extern SnakeGame snake;
|
||||
#endif
|
||||
#if ENABLED(MARLIN_MAZE)
|
||||
class MazeGame : MarlinGame { public: static void enter_game(); static void game_screen(); };
|
||||
extern MazeGame maze;
|
||||
#endif
|
468
Marlin/src/lcd/menu/game/invaders.cpp
Normal file
468
Marlin/src/lcd/menu/game/invaders.cpp
Normal file
|
@ -0,0 +1,468 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2019 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 "../../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if ENABLED(MARLIN_INVADERS)
|
||||
|
||||
#include "game.h"
|
||||
|
||||
// 11x8
|
||||
const unsigned char invader[3][2][16] PROGMEM = {
|
||||
{ { B00000110,B00000000,
|
||||
B00001111,B00000000,
|
||||
B00011111,B10000000,
|
||||
B00110110,B11000000,
|
||||
B00111111,B11000000,
|
||||
B00001001,B00000000,
|
||||
B00010110,B10000000,
|
||||
B00101001,B01000000
|
||||
}, {
|
||||
B00000110,B00000000,
|
||||
B00001111,B00000000,
|
||||
B00011111,B10000000,
|
||||
B00110110,B11000000,
|
||||
B00111111,B11000000,
|
||||
B00010110,B10000000,
|
||||
B00100000,B01000000,
|
||||
B00010000,B10000000
|
||||
}
|
||||
}, {
|
||||
{ B00010000,B01000000,
|
||||
B00001000,B10000000,
|
||||
B00011111,B11000000,
|
||||
B00110111,B01100000,
|
||||
B01111111,B11110000,
|
||||
B01011111,B11010000,
|
||||
B01010000,B01010000,
|
||||
B00001101,B10000000
|
||||
}, {
|
||||
B00010000,B01000000,
|
||||
B01001000,B10010000,
|
||||
B01011111,B11010000,
|
||||
B01110111,B01110000,
|
||||
B01111111,B11110000,
|
||||
B00011111,B11000000,
|
||||
B00010000,B01000000,
|
||||
B00100000,B00100000
|
||||
}
|
||||
}, {
|
||||
{ B00001111,B00000000,
|
||||
B01111111,B11100000,
|
||||
B11111111,B11110000,
|
||||
B11100110,B01110000,
|
||||
B11111111,B11110000,
|
||||
B00011001,B10000000,
|
||||
B00110110,B11000000,
|
||||
B11000000,B00110000
|
||||
}, {
|
||||
B00001111,B00000000,
|
||||
B01111111,B11100000,
|
||||
B11111111,B11110000,
|
||||
B11100110,B01110000,
|
||||
B11111111,B11110000,
|
||||
B00011001,B10000000,
|
||||
B00110110,B11000000,
|
||||
B00011001,B10000000
|
||||
}
|
||||
}
|
||||
};
|
||||
const unsigned char cannon[] PROGMEM = {
|
||||
B00000100,B00000000,
|
||||
B00001110,B00000000,
|
||||
B00001110,B00000000,
|
||||
B01111111,B11000000,
|
||||
B11111111,B11100000,
|
||||
B11111111,B11100000,
|
||||
B11111111,B11100000,
|
||||
B11111111,B11100000
|
||||
};
|
||||
const unsigned char life[] PROGMEM = {
|
||||
B00010000,
|
||||
B01111100,
|
||||
B11111110,
|
||||
B11111110,
|
||||
B11111110
|
||||
};
|
||||
const unsigned char explosion[] PROGMEM = {
|
||||
B01000100,B01000000,
|
||||
B00100100,B10000000,
|
||||
B00000000,B00000000,
|
||||
B00110001,B10000000,
|
||||
B00000000,B00000000,
|
||||
B00100100,B10000000,
|
||||
B01000100,B01000000
|
||||
};
|
||||
const unsigned char ufo[] PROGMEM = {
|
||||
B00011111,B11000000,
|
||||
B01111111,B11110000,
|
||||
B11011101,B11011000,
|
||||
B11111111,B11111000,
|
||||
B01111111,B11110000
|
||||
};
|
||||
|
||||
#define INVASION_SIZE 3
|
||||
|
||||
#if INVASION_SIZE == 3
|
||||
#define INVADER_COLS 5
|
||||
#elif INVASION_SIZE == 4
|
||||
#define INVADER_COLS 6
|
||||
#else
|
||||
#define INVADER_COLS 8
|
||||
#undef INVASION_SIZE
|
||||
#define INVASION_SIZE 5
|
||||
#endif
|
||||
|
||||
#define INVADER_ROWS INVASION_SIZE
|
||||
|
||||
constexpr uint8_t inv_type[] = {
|
||||
#if INVADER_ROWS == 5
|
||||
0, 1, 1, 2, 2
|
||||
#elif INVADER_ROWS == 4
|
||||
0, 1, 1, 2
|
||||
#elif INVADER_ROWS == 3
|
||||
0, 1, 2
|
||||
#else
|
||||
#error "INVASION_SIZE must be 3, 4, or 5."
|
||||
#endif
|
||||
};
|
||||
|
||||
#define INVADER_RIGHT ((INVADER_COLS) * (COL_W))
|
||||
|
||||
#define CANNON_W 11
|
||||
#define CANNON_H 8
|
||||
#define CANNON_VEL 4
|
||||
#define CANNON_Y (LCD_PIXEL_HEIGHT - 1 - CANNON_H)
|
||||
|
||||
#define COL_W 14
|
||||
#define INVADER_H 8
|
||||
#define ROW_H (INVADER_H + 2)
|
||||
#define INVADER_VEL 3
|
||||
|
||||
#define INVADER_TOP MENU_FONT_ASCENT
|
||||
#define INVADERS_WIDE ((COL_W) * (INVADER_COLS))
|
||||
#define INVADERS_HIGH ((ROW_H) * (INVADER_ROWS))
|
||||
|
||||
#define UFO_H 5
|
||||
#define UFO_W 13
|
||||
|
||||
#define LASER_H 4
|
||||
#define SHOT_H 3
|
||||
#define EXPL_W 11
|
||||
#define LIFE_W 8
|
||||
#define LIFE_H 5
|
||||
|
||||
#define INVADER_COL(X) ((X - invaders_x) / (COL_W))
|
||||
#define INVADER_ROW(Y) ((Y - invaders_y + 2) / (ROW_H))
|
||||
|
||||
#define INV_X_LEFT(C,T) (invaders_x + (C) * (COL_W) + inv_off[T])
|
||||
#define INV_X_CTR(C,T) (INV_X_LEFT(C,T) + inv_wide[T] / 2)
|
||||
#define INV_Y_BOT(R) (invaders_y + (R + 1) * (ROW_H) - 2)
|
||||
|
||||
typedef struct { int8_t x, y, v; } laser_t;
|
||||
|
||||
uint8_t cannons_left;
|
||||
int8_t cannon_x;
|
||||
laser_t explod, laser, bullet[10];
|
||||
constexpr uint8_t inv_off[] = { 2, 1, 0 }, inv_wide[] = { 8, 11, 12 };
|
||||
int8_t invaders_x, invaders_y, invaders_dir, leftmost, rightmost, botmost;
|
||||
uint8_t invader_count, quit_count, bugs[INVADER_ROWS], shooters[(INVADER_ROWS) * (INVADER_COLS)];
|
||||
|
||||
inline void update_invader_data() {
|
||||
uint8_t inv_mask = 0;
|
||||
// Get a list of all active invaders
|
||||
uint8_t sc = 0;
|
||||
LOOP_L_N(y, INVADER_ROWS) {
|
||||
uint8_t m = bugs[y];
|
||||
if (m) botmost = y + 1;
|
||||
inv_mask |= m;
|
||||
for (uint8_t x = 0; x < INVADER_COLS; ++x)
|
||||
if (TEST(m, x)) shooters[sc++] = (y << 4) | x;
|
||||
}
|
||||
leftmost = 0;
|
||||
LOOP_L_N(i, INVADER_COLS) { if (TEST(inv_mask, i)) break; leftmost -= COL_W; }
|
||||
rightmost = LCD_PIXEL_WIDTH - (INVADERS_WIDE);
|
||||
for (uint8_t i = INVADER_COLS; i--;) { if (TEST(inv_mask, i)) break; rightmost += COL_W; }
|
||||
if (invader_count == 2) invaders_dir = invaders_dir > 0 ? INVADER_VEL + 1 : -(INVADER_VEL + 1);
|
||||
}
|
||||
|
||||
inline void reset_bullets() {
|
||||
LOOP_L_N(i, COUNT(bullet)) bullet[i].v = 0;
|
||||
}
|
||||
|
||||
inline void reset_invaders() {
|
||||
invaders_x = 0; invaders_y = INVADER_TOP;
|
||||
invaders_dir = INVADER_VEL;
|
||||
invader_count = (INVADER_COLS) * (INVADER_ROWS);
|
||||
LOOP_L_N(i, INVADER_ROWS) bugs[i] = _BV(INVADER_COLS) - 1;
|
||||
update_invader_data();
|
||||
reset_bullets();
|
||||
}
|
||||
|
||||
int8_t ufox, ufov;
|
||||
inline void spawn_ufo() {
|
||||
ufov = random(0, 2) ? 1 : -1;
|
||||
ufox = ufov > 0 ? -(UFO_W) : LCD_PIXEL_WIDTH - 1;
|
||||
}
|
||||
|
||||
inline void reset_player() {
|
||||
cannon_x = 0;
|
||||
ui.encoderPosition = 0;
|
||||
}
|
||||
|
||||
inline void fire_cannon() {
|
||||
laser.x = cannon_x + CANNON_W / 2;
|
||||
laser.y = LCD_PIXEL_HEIGHT - CANNON_H - (LASER_H);
|
||||
laser.v = -(LASER_H);
|
||||
}
|
||||
|
||||
inline void explode(const int8_t x, const int8_t y, const int8_t v=4) {
|
||||
explod.x = x - (EXPL_W) / 2;
|
||||
explod.y = y;
|
||||
explod.v = v;
|
||||
}
|
||||
|
||||
inline void kill_cannon(uint8_t &game_state, const uint8_t st) {
|
||||
reset_bullets();
|
||||
explode(cannon_x + (CANNON_W) / 2, CANNON_Y, 6);
|
||||
_BUZZ(1000, 10);
|
||||
if (--cannons_left) {
|
||||
laser.v = 0;
|
||||
game_state = st;
|
||||
reset_player();
|
||||
}
|
||||
else
|
||||
game_state = 0;
|
||||
}
|
||||
|
||||
void InvadersGame::game_screen() {
|
||||
static bool game_blink;
|
||||
|
||||
ui.refresh(LCDVIEW_CALL_NO_REDRAW); // Call as often as possible
|
||||
|
||||
// Run game logic once per full screen
|
||||
if (ui.first_page) {
|
||||
|
||||
// Update Cannon Position
|
||||
int16_t ep = int16_t(ui.encoderPosition);
|
||||
ep = constrain(ep, 0, (LCD_PIXEL_WIDTH - (CANNON_W)) / (CANNON_VEL));
|
||||
ui.encoderPosition = ep;
|
||||
|
||||
ep *= (CANNON_VEL);
|
||||
if (ep > cannon_x) { cannon_x += CANNON_VEL - 1; if (ep - cannon_x < 2) cannon_x = ep; }
|
||||
if (ep < cannon_x) { cannon_x -= CANNON_VEL - 1; if (cannon_x - ep < 2) cannon_x = ep; }
|
||||
|
||||
// Run the game logic
|
||||
if (game_state) do {
|
||||
|
||||
// Move the UFO, if any
|
||||
if (ufov) { ufox += ufov; if (!WITHIN(ufox, -(UFO_W), LCD_PIXEL_WIDTH - 1)) ufov = 0; }
|
||||
|
||||
if (game_state > 1) { if (--game_state == 2) { reset_invaders(); } else if (game_state == 100) { game_state = 1; } break; }
|
||||
|
||||
static uint8_t blink_count;
|
||||
const bool did_blink = (++blink_count > invader_count >> 1);
|
||||
if (did_blink) {
|
||||
game_blink = !game_blink;
|
||||
blink_count = 0;
|
||||
}
|
||||
|
||||
if (invader_count && did_blink) {
|
||||
const int8_t newx = invaders_x + invaders_dir;
|
||||
if (!WITHIN(newx, leftmost, rightmost)) { // Invaders reached the edge?
|
||||
invaders_dir *= -1; // Invaders change direction
|
||||
invaders_y += (ROW_H) / 2; // Invaders move down
|
||||
invaders_x -= invaders_dir; // ...and only move down this time.
|
||||
if (invaders_y + botmost * (ROW_H) - 2 >= CANNON_Y) // Invaders reached the bottom?
|
||||
kill_cannon(game_state, 20); // Kill the cannon. Reset invaders.
|
||||
}
|
||||
|
||||
invaders_x += invaders_dir; // Invaders take one step left/right
|
||||
|
||||
// Randomly shoot if invaders are listed
|
||||
if (invader_count && !random(0, 20)) {
|
||||
|
||||
// Find a free bullet
|
||||
laser_t *b = NULL;
|
||||
LOOP_L_N(i, COUNT(bullet)) if (!bullet[i].v) { b = &bullet[i]; break; }
|
||||
if (b) {
|
||||
// Pick a random shooter and update the bullet
|
||||
//SERIAL_ECHOLNPGM("free bullet found");
|
||||
const uint8_t inv = shooters[random(0, invader_count + 1)], col = inv & 0x0F, row = inv >> 4, type = inv_type[row];
|
||||
b->x = INV_X_CTR(col, type);
|
||||
b->y = INV_Y_BOT(row);
|
||||
b->v = 2 + random(0, 2);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Update the laser position
|
||||
if (laser.v) {
|
||||
laser.y += laser.v;
|
||||
if (laser.y < 0) laser.v = 0;
|
||||
}
|
||||
|
||||
// Did the laser collide with an invader?
|
||||
if (laser.v && WITHIN(laser.y, invaders_y, invaders_y + INVADERS_HIGH - 1)) {
|
||||
const int8_t col = INVADER_COL(laser.x);
|
||||
if (WITHIN(col, 0, INVADER_COLS - 1)) {
|
||||
const int8_t row = INVADER_ROW(laser.y);
|
||||
if (WITHIN(row, 0, INVADER_ROWS - 1)) {
|
||||
const uint8_t mask = _BV(col);
|
||||
if (bugs[row] & mask) {
|
||||
const uint8_t type = inv_type[row];
|
||||
const int8_t invx = INV_X_LEFT(col, type);
|
||||
if (WITHIN(laser.x, invx, invx + inv_wide[type] - 1)) {
|
||||
// Turn off laser
|
||||
laser.v = 0;
|
||||
// Remove the invader!
|
||||
bugs[row] &= ~mask;
|
||||
// Score!
|
||||
score += INVADER_ROWS - row;
|
||||
// Explode sound!
|
||||
_BUZZ(40, 10);
|
||||
// Explosion bitmap!
|
||||
explode(invx + inv_wide[type] / 2, invaders_y + row * (ROW_H));
|
||||
// If invaders are gone, go to reset invaders state
|
||||
if (--invader_count) update_invader_data(); else { game_state = 20; reset_bullets(); }
|
||||
} // laser x hit
|
||||
} // invader exists
|
||||
} // good row
|
||||
} // good col
|
||||
} // laser in invader zone
|
||||
|
||||
// Handle alien bullets
|
||||
LOOP_L_N(s, COUNT(bullet)) {
|
||||
laser_t *b = &bullet[s];
|
||||
if (b->v) {
|
||||
// Update alien bullet position
|
||||
b->y += b->v;
|
||||
if (b->y >= LCD_PIXEL_HEIGHT)
|
||||
b->v = 0; // Offscreen
|
||||
else if (b->y >= CANNON_Y && WITHIN(b->x, cannon_x, cannon_x + CANNON_W - 1))
|
||||
kill_cannon(game_state, 120); // Hit the cannon
|
||||
}
|
||||
}
|
||||
|
||||
// Randomly spawn a UFO
|
||||
if (!ufov && !random(0,500)) spawn_ufo();
|
||||
|
||||
// Did the laser hit a ufo?
|
||||
if (laser.v && ufov && laser.y < UFO_H + 2 && WITHIN(laser.x, ufox, ufox + UFO_W - 1)) {
|
||||
// Turn off laser and UFO
|
||||
laser.v = ufov = 0;
|
||||
// Score!
|
||||
score += 10;
|
||||
// Explode!
|
||||
_BUZZ(40, 10);
|
||||
// Explosion bitmap
|
||||
explode(ufox + (UFO_W) / 2, 1);
|
||||
}
|
||||
|
||||
} while (false);
|
||||
|
||||
}
|
||||
|
||||
// Click-and-hold to abort
|
||||
if (ui.button_pressed()) --quit_count; else quit_count = 10;
|
||||
|
||||
// Click to fire or exit
|
||||
if (ui.use_click()) {
|
||||
if (!game_state)
|
||||
quit_count = 0;
|
||||
else if (game_state == 1 && !laser.v)
|
||||
fire_cannon();
|
||||
}
|
||||
|
||||
if (!quit_count) exit_game();
|
||||
|
||||
u8g.setColorIndex(1);
|
||||
|
||||
// Draw invaders
|
||||
if (PAGE_CONTAINS(invaders_y, invaders_y + botmost * (ROW_H) - 2 - 1)) {
|
||||
int8_t yy = invaders_y;
|
||||
for (uint8_t y = 0; y < INVADER_ROWS; ++y) {
|
||||
const uint8_t type = inv_type[y];
|
||||
if (PAGE_CONTAINS(yy, yy + INVADER_H - 1)) {
|
||||
int8_t xx = invaders_x;
|
||||
for (uint8_t x = 0; x < INVADER_COLS; ++x) {
|
||||
if (TEST(bugs[y], x))
|
||||
u8g.drawBitmapP(xx, yy, 2, INVADER_H, invader[type][game_blink]);
|
||||
xx += COL_W;
|
||||
}
|
||||
}
|
||||
yy += ROW_H;
|
||||
}
|
||||
}
|
||||
|
||||
// Draw UFO
|
||||
if (ufov && PAGE_UNDER(UFO_H + 2))
|
||||
u8g.drawBitmapP(ufox, 2, 2, UFO_H, ufo);
|
||||
|
||||
// Draw cannon
|
||||
if (game_state && PAGE_CONTAINS(CANNON_Y, CANNON_Y + CANNON_H - 1) && (game_state < 2 || (game_state & 0x02)))
|
||||
u8g.drawBitmapP(cannon_x, CANNON_Y, 2, CANNON_H, cannon);
|
||||
|
||||
// Draw laser
|
||||
if (laser.v && PAGE_CONTAINS(laser.y, laser.y + LASER_H - 1))
|
||||
u8g.drawVLine(laser.x, laser.y, LASER_H);
|
||||
|
||||
// Draw invader bullets
|
||||
LOOP_L_N (i, COUNT(bullet)) {
|
||||
if (bullet[i].v && PAGE_CONTAINS(bullet[i].y - (SHOT_H - 1), bullet[i].y))
|
||||
u8g.drawVLine(bullet[i].x, bullet[i].y - (SHOT_H - 1), SHOT_H);
|
||||
}
|
||||
|
||||
// Draw explosion
|
||||
if (explod.v && PAGE_CONTAINS(explod.y, explod.y + 7 - 1)) {
|
||||
u8g.drawBitmapP(explod.x, explod.y, 2, 7, explosion);
|
||||
--explod.v;
|
||||
}
|
||||
|
||||
// Blink GAME OVER when game is over
|
||||
if (!game_state) draw_game_over();
|
||||
|
||||
if (PAGE_UNDER(MENU_FONT_ASCENT - 1)) {
|
||||
// Draw Score
|
||||
//const uint8_t sx = (LCD_PIXEL_WIDTH - (score >= 10 ? score >= 100 ? score >= 1000 ? 4 : 3 : 2 : 1) * MENU_FONT_WIDTH) / 2;
|
||||
constexpr uint8_t sx = 0;
|
||||
lcd_moveto(sx, MENU_FONT_ASCENT - 1);
|
||||
lcd_put_int(score);
|
||||
|
||||
// Draw lives
|
||||
if (cannons_left)
|
||||
for (uint8_t i = 1; i <= cannons_left; ++i)
|
||||
u8g.drawBitmapP(LCD_PIXEL_WIDTH - i * (LIFE_W), 6 - (LIFE_H), 1, LIFE_H, life);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void InvadersGame::enter_game() {
|
||||
init_game(20, game_screen); // countdown to reset invaders
|
||||
cannons_left = 3;
|
||||
quit_count = 10;
|
||||
laser.v = 0;
|
||||
reset_invaders();
|
||||
reset_player();
|
||||
}
|
||||
|
||||
#endif // MARLIN_INVADERS
|
137
Marlin/src/lcd/menu/game/maze.cpp
Normal file
137
Marlin/src/lcd/menu/game/maze.cpp
Normal file
|
@ -0,0 +1,137 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2019 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 "../../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if ENABLED(MARLIN_MAZE)
|
||||
|
||||
#include "game.h"
|
||||
|
||||
int8_t move_dir, last_move_dir, // NESW0
|
||||
prizex, prizey, prize_cnt, old_encoder;
|
||||
fixed_t playerx, playery;
|
||||
|
||||
// Up to 50 lines, then you win!
|
||||
typedef struct { int8_t x, y; } pos_t;
|
||||
uint8_t head_ind;
|
||||
pos_t maze_walls[50] = {
|
||||
{ 0, 0 }
|
||||
};
|
||||
|
||||
// Turn the player cw or ccw
|
||||
inline void turn_player(const bool cw) {
|
||||
if (move_dir == 4) move_dir = last_move_dir;
|
||||
move_dir += cw ? 1 : -1;
|
||||
move_dir &= 0x03;
|
||||
last_move_dir = move_dir;
|
||||
}
|
||||
|
||||
// Reset the player for a new game
|
||||
void player_reset() {
|
||||
// Init position
|
||||
playerx = BTOF(1);
|
||||
playery = BTOF(GAME_H / 2);
|
||||
|
||||
// Init motion with a ccw turn
|
||||
move_dir = 0;
|
||||
turn_player(false);
|
||||
|
||||
// Clear prize flag
|
||||
prize_cnt = 255;
|
||||
|
||||
// Clear the controls
|
||||
ui.encoderPosition = 0;
|
||||
old_encoder = 0;
|
||||
}
|
||||
|
||||
void MazeGame::game_screen() {
|
||||
// Run the sprite logic
|
||||
if (game_frame()) do { // Run logic twice for finer resolution
|
||||
|
||||
// Move the man one unit in the current direction
|
||||
// Direction index 4 is for the stopped man
|
||||
const int8_t oldx = FTOB(playerx), oldy = FTOB(playery);
|
||||
pos_t dir_add[] = { { 0, -1 }, { 1, 0 }, { 0, 1 }, { -1, 0 }, { 0, 0 } };
|
||||
playerx += dir_add[move_dir].x;
|
||||
playery += dir_add[move_dir].y;
|
||||
const int8_t x = FTOB(playerx), y = FTOB(playery);
|
||||
|
||||
} while(0);
|
||||
|
||||
u8g.setColorIndex(1);
|
||||
|
||||
// Draw Score
|
||||
if (PAGE_UNDER(HEADER_H)) {
|
||||
lcd_moveto(0, HEADER_H - 1);
|
||||
lcd_put_int(score);
|
||||
}
|
||||
|
||||
// Draw the maze
|
||||
// for (uint8_t n = 0; n < head_ind; ++n) {
|
||||
// const pos_t &p = maze_walls[n], &q = maze_walls[n + 1];
|
||||
// if (p.x == q.x) {
|
||||
// const int8_t y1 = GAMEY(MIN(p.y, q.y)), y2 = GAMEY(MAX(p.y, q.y));
|
||||
// if (PAGE_CONTAINS(y1, y2))
|
||||
// u8g.drawVLine(GAMEX(p.x), y1, y2 - y1 + 1);
|
||||
// }
|
||||
// else if (PAGE_CONTAINS(GAMEY(p.y), GAMEY(p.y))) {
|
||||
// const int8_t x1 = GAMEX(MIN(p.x, q.x)), x2 = GAMEX(MAX(p.x, q.x));
|
||||
// u8g.drawHLine(x1, GAMEY(p.y), x2 - x1 + 1);
|
||||
// }
|
||||
// }
|
||||
|
||||
// Draw Man
|
||||
// const int8_t fy = GAMEY(foody);
|
||||
// if (PAGE_CONTAINS(fy, fy + FOOD_WH - 1)) {
|
||||
// const int8_t fx = GAMEX(foodx);
|
||||
// u8g.drawFrame(fx, fy, FOOD_WH, FOOD_WH);
|
||||
// if (FOOD_WH == 5) u8g.drawPixel(fx + 2, fy + 2);
|
||||
// }
|
||||
|
||||
// Draw Ghosts
|
||||
// const int8_t fy = GAMEY(foody);
|
||||
// if (PAGE_CONTAINS(fy, fy + FOOD_WH - 1)) {
|
||||
// const int8_t fx = GAMEX(foodx);
|
||||
// u8g.drawFrame(fx, fy, FOOD_WH, FOOD_WH);
|
||||
// if (FOOD_WH == 5) u8g.drawPixel(fx + 2, fy + 2);
|
||||
// }
|
||||
|
||||
// Draw Prize
|
||||
// if (PAGE_CONTAINS(prizey, prizey + PRIZE_WH - 1)) {
|
||||
// u8g.drawFrame(prizex, prizey, PRIZE_WH, PRIZE_WH);
|
||||
// if (PRIZE_WH == 5) u8g.drawPixel(prizex + 2, prizey + 2);
|
||||
// }
|
||||
|
||||
// Draw GAME OVER
|
||||
if (!game_state) draw_game_over();
|
||||
|
||||
// A click always exits this game
|
||||
if (ui.use_click()) exit_game();
|
||||
}
|
||||
|
||||
void MazeGame::enter_game() {
|
||||
init_game(1, game_screen); // Game running
|
||||
reset_player();
|
||||
reset_enemies();
|
||||
}
|
||||
|
||||
#endif // MARLIN_MAZE
|
334
Marlin/src/lcd/menu/game/snake.cpp
Normal file
334
Marlin/src/lcd/menu/game/snake.cpp
Normal file
|
@ -0,0 +1,334 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2019 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 "../../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if ENABLED(MARLIN_SNAKE)
|
||||
|
||||
#include "game.h"
|
||||
|
||||
#define SNAKE_BOX 4
|
||||
|
||||
#define HEADER_H (MENU_FONT_ASCENT - 2)
|
||||
#define SNAKE_WH (SNAKE_BOX + 1)
|
||||
|
||||
#define IDEAL_L 2
|
||||
#define IDEAL_R (LCD_PIXEL_WIDTH - 1 - 2)
|
||||
#define IDEAL_T (HEADER_H + 2)
|
||||
#define IDEAL_B (LCD_PIXEL_HEIGHT - 1 - 2)
|
||||
#define IDEAL_W (IDEAL_R - (IDEAL_L) + 1)
|
||||
#define IDEAL_H (IDEAL_B - (IDEAL_T) + 1)
|
||||
|
||||
#define GAME_W int((IDEAL_W) / (SNAKE_WH))
|
||||
#define GAME_H int((IDEAL_H) / (SNAKE_WH))
|
||||
|
||||
#define BOARD_W ((SNAKE_WH) * (GAME_W) + 1)
|
||||
#define BOARD_H ((SNAKE_WH) * (GAME_H) + 1)
|
||||
#define BOARD_L ((LCD_PIXEL_WIDTH - (BOARD_W) + 1) / 2)
|
||||
#define BOARD_R (BOARD_L + BOARD_W - 1)
|
||||
#define BOARD_T (((LCD_PIXEL_HEIGHT + IDEAL_T) - (BOARD_H)) / 2)
|
||||
#define BOARD_B (BOARD_T + BOARD_H - 1)
|
||||
|
||||
#define GAMEX(X) (BOARD_L + ((X) * (SNAKE_WH)))
|
||||
#define GAMEY(Y) (BOARD_T + ((Y) * (SNAKE_WH)))
|
||||
|
||||
#if SNAKE_BOX > 2
|
||||
#define FOOD_WH SNAKE_BOX
|
||||
#else
|
||||
#define FOOD_WH 2
|
||||
#endif
|
||||
|
||||
#if SNAKE_BOX < 1
|
||||
#define SNAKE_SIZ 1
|
||||
#else
|
||||
#define SNAKE_SIZ SNAKE_BOX
|
||||
#endif
|
||||
|
||||
constexpr fixed_t snakev = FTOP(0.20);
|
||||
|
||||
int8_t snake_dir, // NESW
|
||||
foodx, foody, food_cnt,
|
||||
old_encoder;
|
||||
fixed_t snakex, snakey;
|
||||
|
||||
// Up to 50 lines, then you win!
|
||||
typedef struct { int8_t x, y; } pos_t;
|
||||
uint8_t head_ind;
|
||||
pos_t snake_tail[50];
|
||||
|
||||
// Remove the first pixel from the tail.
|
||||
// If needed, shift out the first segment.
|
||||
void shorten_tail() {
|
||||
pos_t &p = snake_tail[0], &q = snake_tail[1];
|
||||
bool shift = false;
|
||||
if (p.x == q.x) {
|
||||
// Vertical line
|
||||
p.y += (q.y > p.y) ? 1 : -1;
|
||||
shift = p.y == q.y;
|
||||
}
|
||||
else {
|
||||
// Horizontal line
|
||||
p.x += (q.x > p.x) ? 1 : -1;
|
||||
shift = p.x == q.x;
|
||||
}
|
||||
if (shift) {
|
||||
head_ind--;
|
||||
for (uint8_t i = 0; i <= head_ind; ++i)
|
||||
snake_tail[i] = snake_tail[i + 1];
|
||||
}
|
||||
}
|
||||
|
||||
// The food is on a line
|
||||
inline bool food_on_line() {
|
||||
for (uint8_t n = 0; n < head_ind; ++n) {
|
||||
pos_t &p = snake_tail[n], &q = snake_tail[n + 1];
|
||||
if (p.x == q.x) {
|
||||
if ((foodx == p.x - 1 || foodx == p.x) && WITHIN(foody, MIN(p.y, q.y), MAX(p.y, q.y)))
|
||||
return true;
|
||||
}
|
||||
else if ((foody == p.y - 1 || foody == p.y) && WITHIN(foodx, MIN(p.x, q.x), MAX(p.x, q.x)))
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
// Add a new food blob
|
||||
void food_reset() {
|
||||
do {
|
||||
foodx = random(0, GAME_W);
|
||||
foody = random(0, GAME_H);
|
||||
} while (food_on_line());
|
||||
}
|
||||
|
||||
// Turn the snake cw or ccw
|
||||
inline void turn_snake(const bool cw) {
|
||||
snake_dir += cw ? 1 : -1;
|
||||
snake_dir &= 0x03;
|
||||
head_ind++;
|
||||
snake_tail[head_ind].x = FTOB(snakex);
|
||||
snake_tail[head_ind].y = FTOB(snakey);
|
||||
}
|
||||
|
||||
// Reset the snake for a new game
|
||||
void snake_reset() {
|
||||
// Init the head and velocity
|
||||
snakex = BTOF(1);
|
||||
snakey = BTOF(GAME_H / 2);
|
||||
//snakev = FTOP(0.25);
|
||||
|
||||
// Init the tail with a cw turn
|
||||
snake_dir = 0;
|
||||
head_ind = 0;
|
||||
snake_tail[0].x = 0;
|
||||
snake_tail[0].y = GAME_H / 2;
|
||||
turn_snake(true);
|
||||
|
||||
// Clear food flag
|
||||
food_cnt = 5;
|
||||
|
||||
// Clear the controls
|
||||
ui.encoderPosition = 0;
|
||||
old_encoder = 0;
|
||||
}
|
||||
|
||||
// Check if head segment overlaps another
|
||||
bool snake_overlap() {
|
||||
// 4 lines must exist before a collision is possible
|
||||
if (head_ind < 4) return false;
|
||||
// Is the last segment crossing any others?
|
||||
const pos_t &h1 = snake_tail[head_ind - 1], &h2 = snake_tail[head_ind];
|
||||
// VERTICAL head segment?
|
||||
if (h1.x == h2.x) {
|
||||
// Loop from oldest to segment two away from head
|
||||
for (uint8_t n = 0; n < head_ind - 2; ++n) {
|
||||
// Segment p to q
|
||||
const pos_t &p = snake_tail[n], &q = snake_tail[n + 1];
|
||||
if (p.x != q.x) {
|
||||
// Crossing horizontal segment
|
||||
if (WITHIN(h1.x, MIN(p.x, q.x), MAX(p.x, q.x)) && (h1.y <= p.y) == (h2.y >= p.y)) return true;
|
||||
} // Overlapping vertical segment
|
||||
else if (h1.x == p.x && MIN(h1.y, h2.y) <= MAX(p.y, q.y) && MAX(h1.y, h2.y) >= MIN(p.y, q.y)) return true;
|
||||
}
|
||||
}
|
||||
else {
|
||||
// Loop from oldest to segment two away from head
|
||||
for (uint8_t n = 0; n < head_ind - 2; ++n) {
|
||||
// Segment p to q
|
||||
const pos_t &p = snake_tail[n], &q = snake_tail[n + 1];
|
||||
if (p.y != q.y) {
|
||||
// Crossing vertical segment
|
||||
if (WITHIN(h1.y, MIN(p.y, q.y), MAX(p.y, q.y)) && (h1.x <= p.x) == (h2.x >= p.x)) return true;
|
||||
} // Overlapping horizontal segment
|
||||
else if (h1.y == p.y && MIN(h1.x, h2.x) <= MAX(p.x, q.x) && MAX(h1.x, h2.x) >= MIN(p.x, q.x)) return true;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
void SnakeGame::game_screen() {
|
||||
// Run the snake logic
|
||||
if (game_frame()) do { // Run logic twice for finer resolution
|
||||
|
||||
// Move the snake's head one unit in the current direction
|
||||
const int8_t oldx = FTOB(snakex), oldy = FTOB(snakey);
|
||||
switch (snake_dir) {
|
||||
case 0: snakey -= snakev; break;
|
||||
case 1: snakex += snakev; break;
|
||||
case 2: snakey += snakev; break;
|
||||
case 3: snakex -= snakev; break;
|
||||
}
|
||||
const int8_t x = FTOB(snakex), y = FTOB(snakey);
|
||||
|
||||
// If movement took place...
|
||||
if (oldx != x || oldy != y) {
|
||||
|
||||
if (!WITHIN(x, 0, GAME_W - 1) || !WITHIN(y, 0, GAME_H - 1)) {
|
||||
game_state = 0; // Game Over
|
||||
_BUZZ(400, 40); // Bzzzt!
|
||||
break; // ...out of do-while
|
||||
}
|
||||
|
||||
snake_tail[head_ind].x = x;
|
||||
snake_tail[head_ind].y = y;
|
||||
|
||||
// Change snake direction if set
|
||||
const int8_t enc = int8_t(ui.encoderPosition), diff = enc - old_encoder;
|
||||
if (diff) {
|
||||
old_encoder = enc;
|
||||
turn_snake(diff > 0);
|
||||
}
|
||||
|
||||
if (food_cnt) --food_cnt; else shorten_tail();
|
||||
|
||||
// Did the snake collide with itself or go out of bounds?
|
||||
if (snake_overlap()) {
|
||||
game_state = 0; // Game Over
|
||||
_BUZZ(400, 40); // Bzzzt!
|
||||
}
|
||||
// Is the snake at the food?
|
||||
else if (x == foodx && y == foody) {
|
||||
_BUZZ(5, 220);
|
||||
_BUZZ(5, 280);
|
||||
score++;
|
||||
food_cnt = 2;
|
||||
food_reset();
|
||||
}
|
||||
}
|
||||
|
||||
} while(0);
|
||||
|
||||
u8g.setColorIndex(1);
|
||||
|
||||
// Draw Score
|
||||
if (PAGE_UNDER(HEADER_H)) {
|
||||
lcd_moveto(0, HEADER_H - 1);
|
||||
lcd_put_int(score);
|
||||
}
|
||||
|
||||
// DRAW THE PLAYFIELD BORDER
|
||||
u8g.drawFrame(BOARD_L - 2, BOARD_T - 2, BOARD_R - BOARD_L + 4, BOARD_B - BOARD_T + 4);
|
||||
|
||||
// Draw the snake (tail)
|
||||
#if SNAKE_WH < 2
|
||||
|
||||
// At this scale just draw a line
|
||||
for (uint8_t n = 0; n < head_ind; ++n) {
|
||||
const pos_t &p = snake_tail[n], &q = snake_tail[n + 1];
|
||||
if (p.x == q.x) {
|
||||
const int8_t y1 = GAMEY(MIN(p.y, q.y)), y2 = GAMEY(MAX(p.y, q.y));
|
||||
if (PAGE_CONTAINS(y1, y2))
|
||||
u8g.drawVLine(GAMEX(p.x), y1, y2 - y1 + 1);
|
||||
}
|
||||
else if (PAGE_CONTAINS(GAMEY(p.y), GAMEY(p.y))) {
|
||||
const int8_t x1 = GAMEX(MIN(p.x, q.x)), x2 = GAMEX(MAX(p.x, q.x));
|
||||
u8g.drawHLine(x1, GAMEY(p.y), x2 - x1 + 1);
|
||||
}
|
||||
}
|
||||
|
||||
#elif SNAKE_WH == 2
|
||||
|
||||
// At this scale draw two lines
|
||||
for (uint8_t n = 0; n < head_ind; ++n) {
|
||||
const pos_t &p = snake_tail[n], &q = snake_tail[n + 1];
|
||||
if (p.x == q.x) {
|
||||
const int8_t y1 = GAMEY(MIN(p.y, q.y)), y2 = GAMEY(MAX(p.y, q.y));
|
||||
if (PAGE_CONTAINS(y1, y2 + 1))
|
||||
u8g.drawFrame(GAMEX(p.x), y1, 2, y2 - y1 + 1 + 1);
|
||||
}
|
||||
else {
|
||||
const int8_t py = GAMEY(p.y);
|
||||
if (PAGE_CONTAINS(py, py + 1)) {
|
||||
const int8_t x1 = GAMEX(MIN(p.x, q.x)), x2 = GAMEX(MAX(p.x, q.x));
|
||||
u8g.drawFrame(x1, py, x2 - x1 + 1 + 1, 2);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#else
|
||||
|
||||
// Draw a series of boxes
|
||||
for (uint8_t n = 0; n < head_ind; ++n) {
|
||||
const pos_t &p = snake_tail[n], &q = snake_tail[n + 1];
|
||||
if (p.x == q.x) {
|
||||
const int8_t y1 = MIN(p.y, q.y), y2 = MAX(p.y, q.y);
|
||||
if (PAGE_CONTAINS(GAMEY(y1), GAMEY(y2) + SNAKE_SIZ - 1)) {
|
||||
for (int8_t i = y1; i <= y2; ++i) {
|
||||
const int8_t y = GAMEY(i);
|
||||
if (PAGE_CONTAINS(y, y + SNAKE_SIZ - 1))
|
||||
u8g.drawBox(GAMEX(p.x), y, SNAKE_SIZ, SNAKE_SIZ);
|
||||
}
|
||||
}
|
||||
}
|
||||
else {
|
||||
const int8_t py = GAMEY(p.y);
|
||||
if (PAGE_CONTAINS(py, py + SNAKE_SIZ - 1)) {
|
||||
const int8_t x1 = MIN(p.x, q.x), x2 = MAX(p.x, q.x);
|
||||
for (int8_t i = x1; i <= x2; ++i)
|
||||
u8g.drawBox(GAMEX(i), py, SNAKE_SIZ, SNAKE_SIZ);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
// Draw food
|
||||
const int8_t fy = GAMEY(foody);
|
||||
if (PAGE_CONTAINS(fy, fy + FOOD_WH - 1)) {
|
||||
const int8_t fx = GAMEX(foodx);
|
||||
u8g.drawFrame(fx, fy, FOOD_WH, FOOD_WH);
|
||||
if (FOOD_WH == 5) u8g.drawPixel(fx + 2, fy + 2);
|
||||
}
|
||||
|
||||
// Draw GAME OVER
|
||||
if (!game_state) draw_game_over();
|
||||
|
||||
// A click always exits this game
|
||||
if (ui.use_click()) exit_game();
|
||||
}
|
||||
|
||||
void SnakeGame::enter_game() {
|
||||
init_game(1, game_screen); // 1 = Game running
|
||||
snake_reset();
|
||||
food_reset();
|
||||
}
|
||||
|
||||
#endif // MARLIN_SNAKE
|
|
@ -37,7 +37,7 @@
|
|||
#include "../../module/configuration_store.h"
|
||||
#endif
|
||||
|
||||
#if WATCH_HOTENDS || WATCH_BED || ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
#if WATCH_HOTENDS || WATCH_BED
|
||||
#include "../../module/temperature.h"
|
||||
#endif
|
||||
|
||||
|
@ -54,21 +54,23 @@
|
|||
////////////////////////////////////////////
|
||||
|
||||
// Menu Navigation
|
||||
int8_t encoderTopLine;
|
||||
int8_t encoderTopLine, encoderLine, screen_items;
|
||||
|
||||
typedef struct {
|
||||
screenFunc_t menu_function;
|
||||
uint32_t encoder_position;
|
||||
int8_t top_line, items;
|
||||
} menuPosition;
|
||||
menuPosition screen_history[6];
|
||||
uint8_t screen_history_depth = 0;
|
||||
bool screen_changed;
|
||||
|
||||
// Value Editing
|
||||
PGM_P editLabel;
|
||||
void *editValue;
|
||||
int32_t minEditValue, maxEditValue;
|
||||
screenFunc_t callbackFunc;
|
||||
bool liveEdit;
|
||||
PGM_P MenuItemBase::editLabel;
|
||||
void* MenuItemBase::editValue;
|
||||
int16_t MenuItemBase::minEditValue, MenuItemBase::maxEditValue;
|
||||
screenFunc_t MenuItemBase::callbackFunc;
|
||||
bool MenuItemBase::liveEdit;
|
||||
|
||||
// Prevent recursion into screen handlers
|
||||
bool no_reentry = false;
|
||||
|
@ -80,20 +82,14 @@ bool no_reentry = false;
|
|||
void MarlinUI::return_to_status() { goto_screen(status_screen); }
|
||||
|
||||
void MarlinUI::save_previous_screen() {
|
||||
if (screen_history_depth < COUNT(screen_history)) {
|
||||
screen_history[screen_history_depth].menu_function = currentScreen;
|
||||
screen_history[screen_history_depth].encoder_position = encoderPosition;
|
||||
++screen_history_depth;
|
||||
}
|
||||
if (screen_history_depth < COUNT(screen_history))
|
||||
screen_history[screen_history_depth++] = { currentScreen, encoderPosition, encoderTopLine, screen_items };
|
||||
}
|
||||
|
||||
void MarlinUI::goto_previous_screen() {
|
||||
if (screen_history_depth > 0) {
|
||||
--screen_history_depth;
|
||||
goto_screen(
|
||||
screen_history[screen_history_depth].menu_function,
|
||||
screen_history[screen_history_depth].encoder_position
|
||||
);
|
||||
menuPosition &sh = screen_history[--screen_history_depth];
|
||||
goto_screen(sh.menu_function, sh.encoder_position, sh.top_line, sh.items);
|
||||
}
|
||||
else
|
||||
return_to_status();
|
||||
|
@ -135,8 +131,8 @@ void MenuItem_gcode::action(PGM_P pgcode) { enqueue_and_echo_commands_P(pgcode);
|
|||
*/
|
||||
void MenuItemBase::edit(strfunc_t strfunc, loadfunc_t loadfunc) {
|
||||
ui.encoder_direction_normal();
|
||||
if ((int32_t)ui.encoderPosition < 0) ui.encoderPosition = 0;
|
||||
if ((int32_t)ui.encoderPosition > maxEditValue) ui.encoderPosition = maxEditValue;
|
||||
if (int16_t(ui.encoderPosition) < 0) ui.encoderPosition = 0;
|
||||
if (int16_t(ui.encoderPosition) > maxEditValue) ui.encoderPosition = maxEditValue;
|
||||
if (ui.should_draw())
|
||||
draw_edit_screen(editLabel, strfunc(ui.encoderPosition + minEditValue));
|
||||
if (ui.lcd_clicked || (liveEdit && ui.should_draw())) {
|
||||
|
@ -146,7 +142,7 @@ void MenuItemBase::edit(strfunc_t strfunc, loadfunc_t loadfunc) {
|
|||
}
|
||||
}
|
||||
|
||||
void MenuItemBase::init(PGM_P const el, void * const ev, const int32_t minv, const int32_t maxv, const uint32_t ep, const screenFunc_t cs, const screenFunc_t cb, const bool le) {
|
||||
void MenuItemBase::init(PGM_P const el, void * const ev, const int16_t minv, const int16_t maxv, const uint16_t ep, const screenFunc_t cs, const screenFunc_t cb, const bool le) {
|
||||
ui.save_previous_screen();
|
||||
ui.refresh();
|
||||
editLabel = el;
|
||||
|
@ -197,7 +193,7 @@ bool printer_busy() {
|
|||
/**
|
||||
* General function to go directly to a screen
|
||||
*/
|
||||
void MarlinUI::goto_screen(screenFunc_t screen, const uint32_t encoder/*=0*/) {
|
||||
void MarlinUI::goto_screen(screenFunc_t screen, const uint16_t encoder/*=0*/, const uint8_t top/*=0*/, const uint8_t items/*=0*/) {
|
||||
if (currentScreen != screen) {
|
||||
|
||||
#if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
|
||||
|
@ -246,6 +242,8 @@ void MarlinUI::goto_screen(screenFunc_t screen, const uint32_t encoder/*=0*/) {
|
|||
|
||||
currentScreen = screen;
|
||||
encoderPosition = encoder;
|
||||
encoderTopLine = top;
|
||||
screen_items = items;
|
||||
if (screen == status_screen) {
|
||||
defer_status_screen(false);
|
||||
#if ENABLED(AUTO_BED_LEVELING_UBL)
|
||||
|
@ -314,7 +312,6 @@ void MarlinUI::synchronize(PGM_P const msg/*=NULL*/) {
|
|||
* _thisItemNr is the index of each MENU_ITEM or STATIC_ITEM
|
||||
* screen_items is the total number of items in the menu (after one call)
|
||||
*/
|
||||
int8_t encoderLine, screen_items;
|
||||
void scroll_screen(const uint8_t limit, const bool is_menu) {
|
||||
ui.encoder_direction_menus();
|
||||
ENCODER_RATE_MULTIPLY(false);
|
||||
|
@ -355,6 +352,8 @@ void MarlinUI::completion_feedback(const bool good/*=true*/) {
|
|||
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
|
||||
#include "../../feature/babystep.h"
|
||||
|
||||
void lcd_babystep_zoffset() {
|
||||
if (ui.use_click()) return ui.goto_previous_screen_no_defer();
|
||||
ui.defer_status_screen();
|
||||
|
@ -365,7 +364,7 @@ void MarlinUI::completion_feedback(const bool good/*=true*/) {
|
|||
#endif
|
||||
ui.encoder_direction_normal();
|
||||
if (ui.encoderPosition) {
|
||||
const int16_t babystep_increment = (int32_t)ui.encoderPosition * (BABYSTEP_MULTIPLICATOR);
|
||||
const int16_t babystep_increment = int16_t(ui.encoderPosition) * (BABYSTEP_MULTIPLICATOR);
|
||||
ui.encoderPosition = 0;
|
||||
|
||||
const float diff = planner.steps_to_mm[Z_AXIS] * babystep_increment,
|
||||
|
@ -379,7 +378,7 @@ void MarlinUI::completion_feedback(const bool good/*=true*/) {
|
|||
;
|
||||
if (WITHIN(new_offs, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX)) {
|
||||
|
||||
thermalManager.babystep_axis(Z_AXIS, babystep_increment);
|
||||
babystep.add_steps(Z_AXIS, babystep_increment);
|
||||
|
||||
if (do_probe) zprobe_zoffset = new_offs;
|
||||
#if ENABLED(BABYSTEP_HOTEND_Z_OFFSET)
|
||||
|
@ -392,7 +391,7 @@ void MarlinUI::completion_feedback(const bool good/*=true*/) {
|
|||
if (ui.should_draw()) {
|
||||
#if ENABLED(BABYSTEP_HOTEND_Z_OFFSET)
|
||||
if (!do_probe)
|
||||
draw_edit_screen(PSTR(MSG_IDEX_Z_OFFSET), ftostr43sign(hotend_offset[Z_AXIS][active_extruder]));
|
||||
draw_edit_screen(PSTR(MSG_Z_OFFSET), ftostr43sign(hotend_offset[Z_AXIS][active_extruder]));
|
||||
else
|
||||
#endif
|
||||
draw_edit_screen(PSTR(MSG_ZPROBE_ZOFFSET), ftostr43sign(zprobe_zoffset));
|
||||
|
@ -437,4 +436,12 @@ void _lcd_draw_homing() {
|
|||
void _lcd_toggle_bed_leveling() { set_bed_leveling_enabled(!planner.leveling_active); }
|
||||
#endif
|
||||
|
||||
void do_select_screen(PGM_P const yes, PGM_P const no, bool &yesno, PGM_P const pref, const char * const string, PGM_P const suff) {
|
||||
if (ui.encoderPosition) {
|
||||
yesno = int16_t(ui.encoderPosition) > 0;
|
||||
ui.encoderPosition = 0;
|
||||
}
|
||||
draw_select_screen(yes, no, yesno, pref, string, suff);
|
||||
}
|
||||
|
||||
#endif // HAS_LCD_MENU
|
||||
|
|
|
@ -43,7 +43,7 @@ bool printer_busy();
|
|||
static inline char* strfunc(const float value) { return STRFUNC((TYPE) value); } \
|
||||
};
|
||||
|
||||
DECLARE_MENU_EDIT_TYPE(uint8_t, percent, ui8tostr_percent,1 ); // 100% right-justified
|
||||
DECLARE_MENU_EDIT_TYPE(uint8_t, percent, ui8tostr4pct, 1 ); // 100% right-justified
|
||||
DECLARE_MENU_EDIT_TYPE(int16_t, int3, i16tostr3, 1 ); // 123, -12 right-justified
|
||||
DECLARE_MENU_EDIT_TYPE(int16_t, int4, i16tostr4sign, 1 ); // 1234, -123 right-justified
|
||||
DECLARE_MENU_EDIT_TYPE(int8_t, int8, i8tostr3, 1 ); // 123, -12 right-justified
|
||||
|
@ -64,6 +64,11 @@ DECLARE_MENU_EDIT_TYPE(uint32_t, long5, ftostr5rj, 0.01f ); // 123
|
|||
////////////////////////////////////////////
|
||||
|
||||
void draw_edit_screen(PGM_P const pstr, const char* const value=NULL);
|
||||
void draw_select_screen(PGM_P const yes, PGM_P const no, const bool yesno, PGM_P const pref, const char * const string, PGM_P const suff);
|
||||
void do_select_screen(PGM_P const yes, PGM_P const no, bool &yesno, PGM_P const pref, const char * const string=NULL, PGM_P const suff=NULL);
|
||||
inline void do_select_screen_yn(bool &yesno, PGM_P const pref, const char * const string, PGM_P const suff) {
|
||||
do_select_screen(PSTR(MSG_YES), PSTR(MSG_NO), yesno, pref, string, suff);
|
||||
}
|
||||
void draw_menu_item(const bool sel, const uint8_t row, PGM_P const pstr, const char pre_char, const char post_char);
|
||||
void draw_menu_item_static(const uint8_t row, PGM_P const pstr, const bool center=true, const bool invert=false, const char *valstr=NULL);
|
||||
void _draw_menu_item_edit(const bool sel, const uint8_t row, PGM_P const pstr, const char* const data, const bool pgm);
|
||||
|
@ -151,10 +156,16 @@ class MenuItem_function {
|
|||
////////////////////////////////////////////
|
||||
|
||||
class MenuItemBase {
|
||||
private:
|
||||
static PGM_P editLabel;
|
||||
static void *editValue;
|
||||
static int16_t minEditValue, maxEditValue;
|
||||
static screenFunc_t callbackFunc;
|
||||
static bool liveEdit;
|
||||
protected:
|
||||
typedef char* (*strfunc_t)(const int32_t);
|
||||
typedef void (*loadfunc_t)(void *, const int32_t);
|
||||
static void init(PGM_P const el, void * const ev, const int32_t minv, const int32_t maxv, const uint32_t ep, const screenFunc_t cs, const screenFunc_t cb, const bool le);
|
||||
typedef char* (*strfunc_t)(const int16_t);
|
||||
typedef void (*loadfunc_t)(void *, const int16_t);
|
||||
static void init(PGM_P const el, void * const ev, const int16_t minv, const int16_t maxv, const uint16_t ep, const screenFunc_t cs, const screenFunc_t cb, const bool le);
|
||||
static void edit(strfunc_t, loadfunc_t);
|
||||
};
|
||||
|
||||
|
@ -164,12 +175,12 @@ class TMenuItem : MenuItemBase {
|
|||
typedef typename NAME::type_t type_t;
|
||||
static inline float unscale(const float value) { return value * (1.0f / NAME::scale); }
|
||||
static inline float scale(const float value) { return value * NAME::scale; }
|
||||
static void load(void *ptr, const int32_t value) { *((type_t*)ptr) = unscale(value); }
|
||||
static char* to_string(const int32_t value) { return NAME::strfunc(unscale(value)); }
|
||||
static void load(void *ptr, const int16_t value) { *((type_t*)ptr) = unscale(value); }
|
||||
static char* to_string(const int16_t value) { return NAME::strfunc(unscale(value)); }
|
||||
public:
|
||||
static void action_edit(PGM_P const pstr, type_t * const ptr, const type_t minValue, const type_t maxValue, const screenFunc_t callback=NULL, const bool live=false) {
|
||||
const int32_t minv = scale(minValue);
|
||||
init(pstr, ptr, minv, int32_t(scale(maxValue)) - minv, int32_t(scale(*ptr)) - minv, edit, callback, live);
|
||||
const int16_t minv = scale(minValue);
|
||||
init(pstr, ptr, minv, int16_t(scale(maxValue)) - minv, int16_t(scale(*ptr)) - minv, edit, callback, live);
|
||||
}
|
||||
static void edit() { MenuItemBase::edit(to_string, load); }
|
||||
};
|
||||
|
|
|
@ -120,7 +120,7 @@
|
|||
// Encoder knob or keypad buttons adjust the Z position
|
||||
//
|
||||
if (ui.encoderPosition) {
|
||||
const float z = current_position[Z_AXIS] + float((int32_t)ui.encoderPosition) * (MESH_EDIT_Z_STEP);
|
||||
const float z = current_position[Z_AXIS] + float(int16_t(ui.encoderPosition)) * (MESH_EDIT_Z_STEP);
|
||||
line_to_z(constrain(z, -(LCD_PROBE_Z_RANGE) * 0.5f, (LCD_PROBE_Z_RANGE) * 0.5f));
|
||||
ui.refresh(LCDVIEW_CALL_REDRAW_NEXT);
|
||||
ui.encoderPosition = 0;
|
||||
|
|
|
@ -119,19 +119,37 @@ static void lcd_factory_settings() {
|
|||
|
||||
#endif
|
||||
|
||||
#if ENABLED(DUAL_X_CARRIAGE)
|
||||
|
||||
#if HAS_HOTEND_OFFSET
|
||||
#include "../../module/motion.h"
|
||||
#include "../../gcode/queue.h"
|
||||
|
||||
void _recalc_IDEX_settings() {
|
||||
if (active_extruder) { // For the 2nd extruder re-home so the next tool-change gets the new offsets.
|
||||
void _recalc_offsets() {
|
||||
if (active_extruder && all_axes_known()) { // For the 2nd extruder re-home so the next tool-change gets the new offsets.
|
||||
enqueue_and_echo_commands_P(PSTR("G28")); // In future, we can babystep the 2nd extruder (if active), making homing unnecessary.
|
||||
active_extruder = 0;
|
||||
}
|
||||
}
|
||||
|
||||
void menu_IDEX() {
|
||||
void menu_tool_offsets() {
|
||||
START_MENU();
|
||||
MENU_BACK(MSG_MAIN);
|
||||
#if ENABLED(DUAL_X_CARRIAGE)
|
||||
MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float52, MSG_X_OFFSET, &hotend_offset[X_AXIS][1], MIN(X2_HOME_POS, X2_MAX_POS) - 25.0, MAX(X2_HOME_POS, X2_MAX_POS) + 25.0, _recalc_offsets);
|
||||
#else
|
||||
MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float52, MSG_X_OFFSET, &hotend_offset[X_AXIS][1], -10.0, 10.0, _recalc_offsets);
|
||||
#endif
|
||||
MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float52, MSG_Y_OFFSET, &hotend_offset[Y_AXIS][1], -10.0, 10.0, _recalc_offsets);
|
||||
MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float52, MSG_Z_OFFSET, &hotend_offset[Z_AXIS][1], Z_PROBE_LOW_POINT, 10.0, _recalc_offsets);
|
||||
#if ENABLED(EEPROM_SETTINGS)
|
||||
MENU_ITEM(function, MSG_STORE_EEPROM, lcd_store_settings);
|
||||
#endif
|
||||
END_MENU();
|
||||
}
|
||||
#endif
|
||||
|
||||
#if ENABLED(DUAL_X_CARRIAGE)
|
||||
|
||||
void menu_idex() {
|
||||
START_MENU();
|
||||
MENU_BACK(MSG_MAIN);
|
||||
|
||||
|
@ -146,10 +164,6 @@ static void lcd_factory_settings() {
|
|||
: PSTR("M605 S1\nT0\nM605 S2 X200\nG28 X\nG1 X100\nM605 S3 X200")
|
||||
);
|
||||
MENU_ITEM(gcode, MSG_IDEX_MODE_FULL_CTRL, PSTR("M605 S0\nG28 X"));
|
||||
MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float52, MSG_IDEX_X_OFFSET , &hotend_offset[X_AXIS][1], MIN(X2_HOME_POS, X2_MAX_POS) - 25.0, MAX(X2_HOME_POS, X2_MAX_POS) + 25.0, _recalc_IDEX_settings);
|
||||
MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float52, MSG_IDEX_Y_OFFSET , &hotend_offset[Y_AXIS][1], -10.0, 10.0, _recalc_IDEX_settings);
|
||||
MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float52, MSG_IDEX_Z_OFFSET , &hotend_offset[Z_AXIS][1], -10.0, 10.0, _recalc_IDEX_settings);
|
||||
MENU_ITEM(gcode, MSG_IDEX_SAVE_OFFSETS, PSTR("M500"));
|
||||
END_MENU();
|
||||
}
|
||||
|
||||
|
@ -287,8 +301,12 @@ void menu_configuration() {
|
|||
MENU_ITEM(submenu, MSG_DELTA_CALIBRATE, menu_delta_calibrate);
|
||||
#endif
|
||||
|
||||
#if HAS_HOTEND_OFFSET
|
||||
MENU_ITEM(submenu, MSG_OFFSETS_MENU, menu_tool_offsets);
|
||||
#endif
|
||||
|
||||
#if ENABLED(DUAL_X_CARRIAGE)
|
||||
MENU_ITEM(submenu, MSG_IDEX_MENU, menu_IDEX);
|
||||
MENU_ITEM(submenu, MSG_IDEX_MENU, menu_idex);
|
||||
#endif
|
||||
|
||||
#if ENABLED(BLTOUCH)
|
||||
|
|
|
@ -22,1007 +22,28 @@
|
|||
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if HAS_LCD_MENU && ANY(MARLIN_BRICKOUT, MARLIN_INVADERS, MARLIN_SNAKE)
|
||||
#if HAS_GAME_MENU
|
||||
|
||||
#include "menu.h"
|
||||
#include "../dogm/ultralcd_DOGM.h"
|
||||
#include "../lcdprint.h"
|
||||
#define SCREEN_M ((LCD_PIXEL_WIDTH) / 2)
|
||||
#define _BUZZ(D,F) BUZZ(D,F)
|
||||
//#define _BUZZ(D,F) NOOP
|
||||
|
||||
// Simple 8:8 fixed-point
|
||||
typedef int16_t fixed_t;
|
||||
#define FTOP(F) fixed_t((F)*256.0f)
|
||||
#define PTOF(P) (float(P)*(1.0f/256.0f))
|
||||
#define BTOF(X) (fixed_t(X)<<8)
|
||||
#define FTOB(X) int8_t(fixed_t(X)>>8)
|
||||
|
||||
int score;
|
||||
uint8_t game_state;
|
||||
millis_t next_frame;
|
||||
|
||||
inline void draw_game_over() {
|
||||
constexpr int8_t gowide = (MENU_FONT_WIDTH) * 9,
|
||||
gohigh = MENU_FONT_ASCENT - 3,
|
||||
lx = (LCD_PIXEL_WIDTH - gowide) / 2,
|
||||
ly = (LCD_PIXEL_HEIGHT + gohigh) / 2;
|
||||
if (PAGE_CONTAINS(ly - gohigh - 1, ly + 1)) {
|
||||
u8g.setColorIndex(0);
|
||||
u8g.drawBox(lx - 1, ly - gohigh - 1, gowide + 2, gohigh + 2);
|
||||
u8g.setColorIndex(1);
|
||||
if (ui.get_blink()) {
|
||||
lcd_moveto(lx, ly);
|
||||
lcd_put_u8str_P(PSTR("GAME OVER"));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#if ENABLED(MARLIN_BRICKOUT)
|
||||
|
||||
#define BRICK_H 5
|
||||
#define BRICK_TOP MENU_FONT_ASCENT
|
||||
#define BRICK_ROWS 4
|
||||
#define BRICK_COLS 16
|
||||
|
||||
#define PADDLE_H 2
|
||||
#define PADDLE_VEL 3
|
||||
#define PADDLE_W ((LCD_PIXEL_WIDTH) / 8)
|
||||
#define PADDLE_Y (LCD_PIXEL_HEIGHT - 1 - PADDLE_H)
|
||||
|
||||
#define BRICK_W ((LCD_PIXEL_WIDTH) / (BRICK_COLS))
|
||||
#define BRICK_BOT (BRICK_TOP + BRICK_H * BRICK_ROWS - 1)
|
||||
|
||||
#define BRICK_COL(X) ((X) / (BRICK_W))
|
||||
#define BRICK_ROW(Y) ((Y - (BRICK_TOP)) / (BRICK_H))
|
||||
|
||||
uint8_t balls_left, brick_count;
|
||||
uint16_t bricks[BRICK_ROWS];
|
||||
inline void reset_bricks(const uint16_t v) {
|
||||
brick_count = (BRICK_COLS) * (BRICK_ROWS);
|
||||
LOOP_L_N(i, BRICK_ROWS) bricks[i] = v;
|
||||
}
|
||||
|
||||
int8_t paddle_x, hit_dir;
|
||||
fixed_t ballx, bally, ballh, ballv;
|
||||
|
||||
void reset_ball() {
|
||||
constexpr uint8_t ball_dist = 24;
|
||||
bally = BTOF(PADDLE_Y - ball_dist);
|
||||
ballv = FTOP(1.3f);
|
||||
ballh = -FTOP(1.25f);
|
||||
uint8_t bx = paddle_x + (PADDLE_W) / 2 + ball_dist;
|
||||
if (bx >= LCD_PIXEL_WIDTH - 10) { bx -= ball_dist * 2; ballh = -ballh; }
|
||||
ballx = BTOF(bx);
|
||||
hit_dir = -1;
|
||||
}
|
||||
|
||||
void game_screen_brickout() {
|
||||
static int8_t slew;
|
||||
ui.refresh(LCDVIEW_CALL_NO_REDRAW); // Call as often as possible
|
||||
|
||||
if (ui.first_page) slew = 2;
|
||||
|
||||
if (slew-- > 0) { // Logic runs twice for finer resolution
|
||||
// Update Paddle Position
|
||||
paddle_x = (int8_t)ui.encoderPosition;
|
||||
paddle_x = constrain(paddle_x, 0, (LCD_PIXEL_WIDTH - (PADDLE_W)) / (PADDLE_VEL));
|
||||
ui.encoderPosition = paddle_x;
|
||||
paddle_x *= (PADDLE_VEL);
|
||||
|
||||
// Run the ball logic
|
||||
if (game_state) do {
|
||||
|
||||
// Provisionally update the position
|
||||
const fixed_t newx = ballx + ballh, newy = bally + ballv; // current next position
|
||||
if (!WITHIN(newx, 0, BTOF(LCD_PIXEL_WIDTH - 1))) { // out in x?
|
||||
ballh = -ballh; _BUZZ(5, 220); // bounce x
|
||||
}
|
||||
if (newy < 0) { // out in y?
|
||||
ballv = -ballv; _BUZZ(5, 280); // bounce v
|
||||
hit_dir = 1;
|
||||
}
|
||||
// Did the ball go below the bottom?
|
||||
else if (newy > BTOF(LCD_PIXEL_HEIGHT)) {
|
||||
BUZZ(500, 75);
|
||||
if (--balls_left) reset_ball(); else game_state = 0;
|
||||
break; // done
|
||||
}
|
||||
|
||||
// Is the ball colliding with a brick?
|
||||
if (WITHIN(newy, BTOF(BRICK_TOP), BTOF(BRICK_BOT))) {
|
||||
const int8_t bit = BRICK_COL(FTOB(newx)), row = BRICK_ROW(FTOB(newy));
|
||||
const uint16_t mask = _BV(bit);
|
||||
if (bricks[row] & mask) {
|
||||
// Yes. Remove it!
|
||||
bricks[row] &= ~mask;
|
||||
// Score!
|
||||
score += BRICK_ROWS - row;
|
||||
// If bricks are gone, go to reset state
|
||||
if (!--brick_count) game_state = 2;
|
||||
// Bounce the ball cleverly
|
||||
if ((ballv < 0) == (hit_dir < 0)) { ballv = -ballv; ballh += fixed_t(random(-16, 16)); _BUZZ(5, 880); }
|
||||
else { ballh = -ballh; ballv += fixed_t(random(-16, 16)); _BUZZ(5, 640); }
|
||||
}
|
||||
}
|
||||
// Is the ball moving down and in paddle range?
|
||||
else if (ballv > 0 && WITHIN(newy, BTOF(PADDLE_Y), BTOF(PADDLE_Y + PADDLE_H))) {
|
||||
// Ball actually hitting paddle
|
||||
const int8_t diff = FTOB(newx) - paddle_x;
|
||||
if (WITHIN(diff, 0, PADDLE_W - 1)) {
|
||||
|
||||
// Reverse Y direction
|
||||
ballv = -ballv; _BUZZ(3, 880);
|
||||
hit_dir = -1;
|
||||
|
||||
// Near edges affects X velocity
|
||||
const bool is_left_edge = (diff <= 1);
|
||||
if (is_left_edge || diff >= PADDLE_W-1 - 1) {
|
||||
if ((ballh > 0) == is_left_edge) ballh = -ballh;
|
||||
}
|
||||
else if (diff <= 3) {
|
||||
ballh += fixed_t(random(-64, 0));
|
||||
NOLESS(ballh, BTOF(-2));
|
||||
NOMORE(ballh, BTOF(2));
|
||||
}
|
||||
else if (diff >= PADDLE_W-1 - 3) {
|
||||
ballh += fixed_t(random( 0, 64));
|
||||
NOLESS(ballh, BTOF(-2));
|
||||
NOMORE(ballh, BTOF(2));
|
||||
}
|
||||
|
||||
// Paddle hit after clearing the board? Reset the board.
|
||||
if (game_state == 2) { reset_bricks(0xFFFF); game_state = 1; }
|
||||
}
|
||||
}
|
||||
|
||||
ballx += ballh; bally += ballv; // update with new velocity
|
||||
|
||||
} while (false);
|
||||
}
|
||||
|
||||
u8g.setColorIndex(1);
|
||||
|
||||
// Draw bricks
|
||||
if (PAGE_CONTAINS(BRICK_TOP, BRICK_BOT)) {
|
||||
for (uint8_t y = 0; y < BRICK_ROWS; ++y) {
|
||||
const uint8_t yy = y * BRICK_H + BRICK_TOP;
|
||||
if (PAGE_CONTAINS(yy, yy + BRICK_H - 1)) {
|
||||
for (uint8_t x = 0; x < BRICK_COLS; ++x) {
|
||||
if (TEST(bricks[y], x)) {
|
||||
const uint8_t xx = x * BRICK_W;
|
||||
for (uint8_t v = 0; v < BRICK_H - 1; ++v)
|
||||
if (PAGE_CONTAINS(yy + v, yy + v))
|
||||
u8g.drawHLine(xx, yy + v, BRICK_W - 1);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Draw paddle
|
||||
if (PAGE_CONTAINS(PADDLE_Y-1, PADDLE_Y)) {
|
||||
u8g.drawHLine(paddle_x, PADDLE_Y, PADDLE_W);
|
||||
#if PADDLE_H > 1
|
||||
u8g.drawHLine(paddle_x, PADDLE_Y-1, PADDLE_W);
|
||||
#if PADDLE_H > 2
|
||||
u8g.drawHLine(paddle_x, PADDLE_Y-2, PADDLE_W);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
// Draw ball while game is running
|
||||
if (game_state) {
|
||||
const uint8_t by = FTOB(bally);
|
||||
if (PAGE_CONTAINS(by, by+1))
|
||||
u8g.drawFrame(FTOB(ballx), by, 2, 2);
|
||||
}
|
||||
// Or draw GAME OVER
|
||||
else
|
||||
draw_game_over();
|
||||
|
||||
if (PAGE_UNDER(MENU_FONT_ASCENT)) {
|
||||
// Score Digits
|
||||
//const uint8_t sx = (LCD_PIXEL_WIDTH - (score >= 10 ? score >= 100 ? score >= 1000 ? 4 : 3 : 2 : 1) * MENU_FONT_WIDTH) / 2;
|
||||
constexpr uint8_t sx = 0;
|
||||
lcd_moveto(sx, MENU_FONT_ASCENT - 1);
|
||||
lcd_put_int(score);
|
||||
|
||||
// Balls Left
|
||||
lcd_moveto(LCD_PIXEL_WIDTH - MENU_FONT_WIDTH * 3, MENU_FONT_ASCENT - 1);
|
||||
PGM_P const ohs = PSTR("ooo\0\0");
|
||||
lcd_put_u8str_P(ohs + 3 - balls_left);
|
||||
}
|
||||
|
||||
// A click always exits this game
|
||||
if (ui.use_click()) ui.goto_previous_screen();
|
||||
}
|
||||
|
||||
void lcd_goto_brickout() {
|
||||
constexpr uint8_t paddle_start = SCREEN_M - (PADDLE_W) / 2;
|
||||
paddle_x = paddle_start;
|
||||
game_state = 2; // reset bricks on paddle hit
|
||||
score = 0;
|
||||
balls_left = 3;
|
||||
reset_bricks(0x0000);
|
||||
reset_ball();
|
||||
ui.goto_screen(game_screen_brickout, paddle_start / (PADDLE_VEL));
|
||||
ui.defer_status_screen();
|
||||
}
|
||||
|
||||
#endif // MARLIN_BRICKOUT
|
||||
|
||||
#if ENABLED(MARLIN_INVADERS)
|
||||
|
||||
// 11x8
|
||||
const unsigned char invader[3][2][16] PROGMEM = {
|
||||
{ { B00000110,B00000000,
|
||||
B00001111,B00000000,
|
||||
B00011111,B10000000,
|
||||
B00110110,B11000000,
|
||||
B00111111,B11000000,
|
||||
B00001001,B00000000,
|
||||
B00010110,B10000000,
|
||||
B00101001,B01000000
|
||||
}, {
|
||||
B00000110,B00000000,
|
||||
B00001111,B00000000,
|
||||
B00011111,B10000000,
|
||||
B00110110,B11000000,
|
||||
B00111111,B11000000,
|
||||
B00010110,B10000000,
|
||||
B00100000,B01000000,
|
||||
B00010000,B10000000
|
||||
}
|
||||
}, {
|
||||
{ B00010000,B01000000,
|
||||
B00001000,B10000000,
|
||||
B00011111,B11000000,
|
||||
B00110111,B01100000,
|
||||
B01111111,B11110000,
|
||||
B01011111,B11010000,
|
||||
B01010000,B01010000,
|
||||
B00001101,B10000000
|
||||
}, {
|
||||
B00010000,B01000000,
|
||||
B01001000,B10010000,
|
||||
B01011111,B11010000,
|
||||
B01110111,B01110000,
|
||||
B01111111,B11110000,
|
||||
B00011111,B11000000,
|
||||
B00010000,B01000000,
|
||||
B00100000,B00100000
|
||||
}
|
||||
}, {
|
||||
{ B00001111,B00000000,
|
||||
B01111111,B11100000,
|
||||
B11111111,B11110000,
|
||||
B11100110,B01110000,
|
||||
B11111111,B11110000,
|
||||
B00011001,B10000000,
|
||||
B00110110,B11000000,
|
||||
B11000000,B00110000
|
||||
}, {
|
||||
B00001111,B00000000,
|
||||
B01111111,B11100000,
|
||||
B11111111,B11110000,
|
||||
B11100110,B01110000,
|
||||
B11111111,B11110000,
|
||||
B00011001,B10000000,
|
||||
B00110110,B11000000,
|
||||
B00011001,B10000000
|
||||
}
|
||||
}
|
||||
};
|
||||
const unsigned char cannon[] PROGMEM = {
|
||||
B00000100,B00000000,
|
||||
B00001110,B00000000,
|
||||
B00001110,B00000000,
|
||||
B01111111,B11000000,
|
||||
B11111111,B11100000,
|
||||
B11111111,B11100000,
|
||||
B11111111,B11100000,
|
||||
B11111111,B11100000
|
||||
};
|
||||
const unsigned char life[] PROGMEM = {
|
||||
B00010000,
|
||||
B01111100,
|
||||
B11111110,
|
||||
B11111110,
|
||||
B11111110
|
||||
};
|
||||
const unsigned char explosion[] PROGMEM = {
|
||||
B01000100,B01000000,
|
||||
B00100100,B10000000,
|
||||
B00000000,B00000000,
|
||||
B00110001,B10000000,
|
||||
B00000000,B00000000,
|
||||
B00100100,B10000000,
|
||||
B01000100,B01000000
|
||||
};
|
||||
const unsigned char ufo[] PROGMEM = {
|
||||
B00011111,B11000000,
|
||||
B01111111,B11110000,
|
||||
B11011101,B11011000,
|
||||
B11111111,B11111000,
|
||||
B01111111,B11110000
|
||||
};
|
||||
|
||||
#define INVASION_SIZE 3
|
||||
|
||||
#if INVASION_SIZE == 3
|
||||
#define INVADER_COLS 5
|
||||
#elif INVASION_SIZE == 4
|
||||
#define INVADER_COLS 6
|
||||
#else
|
||||
#define INVADER_COLS 8
|
||||
#undef INVASION_SIZE
|
||||
#define INVASION_SIZE 5
|
||||
#endif
|
||||
|
||||
#define INVADER_ROWS INVASION_SIZE
|
||||
|
||||
constexpr uint8_t inv_type[] = {
|
||||
#if INVADER_ROWS == 5
|
||||
0, 1, 1, 2, 2
|
||||
#elif INVADER_ROWS == 4
|
||||
0, 1, 1, 2
|
||||
#elif INVADER_ROWS == 3
|
||||
0, 1, 2
|
||||
#else
|
||||
#error "INVASION_SIZE must be 3, 4, or 5."
|
||||
#endif
|
||||
};
|
||||
|
||||
#define INVADER_RIGHT ((INVADER_COLS) * (COL_W))
|
||||
|
||||
#define CANNON_W 11
|
||||
#define CANNON_H 8
|
||||
#define CANNON_VEL 4
|
||||
#define CANNON_Y (LCD_PIXEL_HEIGHT - 1 - CANNON_H)
|
||||
|
||||
#define COL_W 14
|
||||
#define INVADER_H 8
|
||||
#define ROW_H (INVADER_H + 2)
|
||||
#define INVADER_VEL 3
|
||||
|
||||
#define INVADER_TOP MENU_FONT_ASCENT
|
||||
#define INVADERS_WIDE ((COL_W) * (INVADER_COLS))
|
||||
#define INVADERS_HIGH ((ROW_H) * (INVADER_ROWS))
|
||||
|
||||
#define UFO_H 5
|
||||
#define UFO_W 13
|
||||
|
||||
#define LASER_H 4
|
||||
#define SHOT_H 3
|
||||
#define EXPL_W 11
|
||||
#define LIFE_W 8
|
||||
#define LIFE_H 5
|
||||
|
||||
#define INVADER_COL(X) ((X - invaders_x) / (COL_W))
|
||||
#define INVADER_ROW(Y) ((Y - invaders_y + 2) / (ROW_H))
|
||||
|
||||
#define INV_X_LEFT(C,T) (invaders_x + (C) * (COL_W) + inv_off[T])
|
||||
#define INV_X_CTR(C,T) (INV_X_LEFT(C,T) + inv_wide[T] / 2)
|
||||
#define INV_Y_BOT(R) (invaders_y + (R + 1) * (ROW_H) - 2)
|
||||
|
||||
uint8_t cannons_left;
|
||||
int8_t cannon_x;
|
||||
typedef struct { int8_t x, y, v; } laser_t;
|
||||
laser_t laser, expl, bullet[10];
|
||||
constexpr uint8_t inv_off[] = { 2, 1, 0 }, inv_wide[] = { 8, 11, 12 };
|
||||
int8_t invaders_x, invaders_y, invaders_dir, leftmost, rightmost, botmost;
|
||||
uint8_t invader_count, invaders[INVADER_ROWS], shooters[(INVADER_ROWS) * (INVADER_COLS)];
|
||||
|
||||
inline void update_invader_data() {
|
||||
uint8_t inv_mask = 0;
|
||||
// Get a list of all active invaders
|
||||
uint8_t sc = 0;
|
||||
LOOP_L_N(y, INVADER_ROWS) {
|
||||
uint8_t m = invaders[y];
|
||||
if (m) botmost = y + 1;
|
||||
inv_mask |= m;
|
||||
for (uint8_t x = 0; x < INVADER_COLS; ++x)
|
||||
if (TEST(m, x)) shooters[sc++] = (y << 4) | x;
|
||||
}
|
||||
leftmost = 0;
|
||||
LOOP_L_N(i, INVADER_COLS) { if (TEST(inv_mask, i)) break; leftmost -= COL_W; }
|
||||
rightmost = LCD_PIXEL_WIDTH - (INVADERS_WIDE);
|
||||
for (uint8_t i = INVADER_COLS; i--;) { if (TEST(inv_mask, i)) break; rightmost += COL_W; }
|
||||
if (invader_count == 2) invaders_dir = invaders_dir > 0 ? INVADER_VEL + 1 : -(INVADER_VEL + 1);
|
||||
}
|
||||
|
||||
inline void reset_bullets() {
|
||||
LOOP_L_N(i, COUNT(bullet)) bullet[i].v = 0;
|
||||
}
|
||||
|
||||
inline void reset_invaders() {
|
||||
invaders_x = 0; invaders_y = INVADER_TOP;
|
||||
invaders_dir = INVADER_VEL;
|
||||
invader_count = (INVADER_COLS) * (INVADER_ROWS);
|
||||
LOOP_L_N(i, INVADER_ROWS) invaders[i] = _BV(INVADER_COLS) - 1;
|
||||
update_invader_data();
|
||||
reset_bullets();
|
||||
}
|
||||
|
||||
int8_t ufox, ufov;
|
||||
inline void spawn_ufo() {
|
||||
ufov = random(0, 2) ? 1 : -1;
|
||||
ufox = ufov > 0 ? -(UFO_W) : LCD_PIXEL_WIDTH - 1;
|
||||
}
|
||||
|
||||
void reset_player() {
|
||||
cannon_x = 0;
|
||||
ui.encoderPosition = 0;
|
||||
}
|
||||
|
||||
inline void fire_cannon() {
|
||||
laser.x = cannon_x + CANNON_W / 2;
|
||||
laser.y = LCD_PIXEL_HEIGHT - CANNON_H - (LASER_H);
|
||||
laser.v = -(LASER_H);
|
||||
}
|
||||
|
||||
inline void explode(const int8_t x, const int8_t y, const int8_t v=4) {
|
||||
expl.x = x - (EXPL_W) / 2; expl.y = y; expl.v = v;
|
||||
}
|
||||
|
||||
inline void kill_cannon(const uint8_t st) {
|
||||
reset_bullets();
|
||||
explode(cannon_x + (CANNON_W) / 2, CANNON_Y, 6);
|
||||
_BUZZ(1000, 10);
|
||||
if (--cannons_left) {
|
||||
laser.v = 0;
|
||||
game_state = st;
|
||||
reset_player();
|
||||
}
|
||||
else
|
||||
game_state = 0;
|
||||
}
|
||||
|
||||
void game_screen_invaders() {
|
||||
static bool game_blink;
|
||||
|
||||
ui.refresh(LCDVIEW_CALL_NO_REDRAW); // Call as often as possible
|
||||
|
||||
// Run game logic once per full screen
|
||||
if (ui.first_page) {
|
||||
|
||||
// Update Cannon Position
|
||||
int32_t ep = (int32_t)ui.encoderPosition;
|
||||
ep = constrain(ep, 0, (LCD_PIXEL_WIDTH - (CANNON_W)) / (CANNON_VEL));
|
||||
ui.encoderPosition = ep;
|
||||
|
||||
ep *= (CANNON_VEL);
|
||||
if (ep > cannon_x) { cannon_x += CANNON_VEL - 1; if (ep - cannon_x < 2) cannon_x = ep; }
|
||||
if (ep < cannon_x) { cannon_x -= CANNON_VEL - 1; if (cannon_x - ep < 2) cannon_x = ep; }
|
||||
|
||||
// Run the game logic
|
||||
if (game_state) do {
|
||||
|
||||
// Move the UFO, if any
|
||||
if (ufov) { ufox += ufov; if (!WITHIN(ufox, -(UFO_W), LCD_PIXEL_WIDTH - 1)) ufov = 0; }
|
||||
|
||||
if (game_state > 1) { if (--game_state == 2) { reset_invaders(); } else if (game_state == 100) { game_state = 1; } break; }
|
||||
|
||||
static uint8_t blink_count;
|
||||
const bool did_blink = (++blink_count > invader_count >> 1);
|
||||
if (did_blink) {
|
||||
game_blink = !game_blink;
|
||||
blink_count = 0;
|
||||
}
|
||||
|
||||
if (invader_count && did_blink) {
|
||||
const int8_t newx = invaders_x + invaders_dir;
|
||||
if (!WITHIN(newx, leftmost, rightmost)) { // Invaders reached the edge?
|
||||
invaders_dir *= -1; // Invaders change direction
|
||||
invaders_y += (ROW_H) / 2; // Invaders move down
|
||||
invaders_x -= invaders_dir; // ...and only move down this time.
|
||||
if (invaders_y + botmost * (ROW_H) - 2 >= CANNON_Y) // Invaders reached the bottom?
|
||||
kill_cannon(20); // Kill the cannon. Reset invaders.
|
||||
}
|
||||
|
||||
invaders_x += invaders_dir; // Invaders take one step left/right
|
||||
|
||||
// Randomly shoot if invaders are listed
|
||||
if (invader_count && !random(0, 20)) {
|
||||
|
||||
// Find a free bullet
|
||||
laser_t *b = NULL;
|
||||
LOOP_L_N(i, COUNT(bullet)) if (!bullet[i].v) { b = &bullet[i]; break; }
|
||||
if (b) {
|
||||
// Pick a random shooter and update the bullet
|
||||
//SERIAL_ECHOLNPGM("free bullet found");
|
||||
const uint8_t inv = shooters[random(0, invader_count + 1)], col = inv & 0x0F, row = inv >> 4, type = inv_type[row];
|
||||
b->x = INV_X_CTR(col, type);
|
||||
b->y = INV_Y_BOT(row);
|
||||
b->v = 2 + random(0, 2);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Update the laser position
|
||||
if (laser.v) {
|
||||
laser.y += laser.v;
|
||||
if (laser.y < 0) laser.v = 0;
|
||||
}
|
||||
|
||||
// Did the laser collide with an invader?
|
||||
if (laser.v && WITHIN(laser.y, invaders_y, invaders_y + INVADERS_HIGH - 1)) {
|
||||
const int8_t col = INVADER_COL(laser.x);
|
||||
if (WITHIN(col, 0, INVADER_COLS - 1)) {
|
||||
const int8_t row = INVADER_ROW(laser.y);
|
||||
if (WITHIN(row, 0, INVADER_ROWS - 1)) {
|
||||
const uint8_t mask = _BV(col);
|
||||
if (invaders[row] & mask) {
|
||||
const uint8_t type = inv_type[row];
|
||||
const int8_t invx = INV_X_LEFT(col, type);
|
||||
if (WITHIN(laser.x, invx, invx + inv_wide[type] - 1)) {
|
||||
// Turn off laser
|
||||
laser.v = 0;
|
||||
// Remove the invader!
|
||||
invaders[row] &= ~mask;
|
||||
// Score!
|
||||
score += INVADER_ROWS - row;
|
||||
// Explode sound!
|
||||
_BUZZ(40, 10);
|
||||
// Explosion bitmap!
|
||||
explode(invx + inv_wide[type] / 2, invaders_y + row * (ROW_H));
|
||||
// If invaders are gone, go to reset invaders state
|
||||
if (--invader_count) update_invader_data(); else { game_state = 20; reset_bullets(); }
|
||||
} // laser x hit
|
||||
} // invader exists
|
||||
} // good row
|
||||
} // good col
|
||||
} // laser in invader zone
|
||||
|
||||
// Handle alien bullets
|
||||
LOOP_L_N(s, COUNT(bullet)) {
|
||||
laser_t *b = &bullet[s];
|
||||
if (b->v) {
|
||||
// Update alien bullet position
|
||||
b->y += b->v;
|
||||
if (b->y >= LCD_PIXEL_HEIGHT)
|
||||
b->v = 0; // Offscreen
|
||||
else if (b->y >= CANNON_Y && WITHIN(b->x, cannon_x, cannon_x + CANNON_W - 1))
|
||||
kill_cannon(120); // Hit the cannon
|
||||
}
|
||||
}
|
||||
|
||||
// Randomly spawn a UFO
|
||||
if (!ufov && !random(0,500)) spawn_ufo();
|
||||
|
||||
// Did the laser hit a ufo?
|
||||
if (laser.v && ufov && laser.y < UFO_H + 2 && WITHIN(laser.x, ufox, ufox + UFO_W - 1)) {
|
||||
// Turn off laser and UFO
|
||||
laser.v = ufov = 0;
|
||||
// Score!
|
||||
score += 10;
|
||||
// Explode!
|
||||
_BUZZ(40, 10);
|
||||
// Explosion bitmap
|
||||
explode(ufox + (UFO_W) / 2, 1);
|
||||
}
|
||||
|
||||
} while (false);
|
||||
|
||||
}
|
||||
|
||||
// Click to fire or exit
|
||||
if (ui.use_click()) {
|
||||
if (!game_state)
|
||||
ui.goto_previous_screen();
|
||||
else if (game_state == 1 && !laser.v)
|
||||
fire_cannon();
|
||||
}
|
||||
|
||||
u8g.setColorIndex(1);
|
||||
|
||||
// Draw invaders
|
||||
if (PAGE_CONTAINS(invaders_y, invaders_y + botmost * (ROW_H) - 2 - 1)) {
|
||||
int8_t yy = invaders_y;
|
||||
for (uint8_t y = 0; y < INVADER_ROWS; ++y) {
|
||||
const uint8_t type = inv_type[y];
|
||||
if (PAGE_CONTAINS(yy, yy + INVADER_H - 1)) {
|
||||
int8_t xx = invaders_x;
|
||||
for (uint8_t x = 0; x < INVADER_COLS; ++x) {
|
||||
if (TEST(invaders[y], x))
|
||||
u8g.drawBitmapP(xx, yy, 2, INVADER_H, invader[type][game_blink]);
|
||||
xx += COL_W;
|
||||
}
|
||||
}
|
||||
yy += ROW_H;
|
||||
}
|
||||
}
|
||||
|
||||
// Draw UFO
|
||||
if (ufov && PAGE_UNDER(UFO_H + 2))
|
||||
u8g.drawBitmapP(ufox, 2, 2, UFO_H, ufo);
|
||||
|
||||
// Draw cannon
|
||||
if (game_state && PAGE_CONTAINS(CANNON_Y, CANNON_Y + CANNON_H - 1) && (game_state < 2 || (game_state & 0x02)))
|
||||
u8g.drawBitmapP(cannon_x, CANNON_Y, 2, CANNON_H, cannon);
|
||||
|
||||
// Draw laser
|
||||
if (laser.v && PAGE_CONTAINS(laser.y, laser.y + LASER_H - 1))
|
||||
u8g.drawVLine(laser.x, laser.y, LASER_H);
|
||||
|
||||
// Draw invader bullets
|
||||
LOOP_L_N (i, COUNT(bullet)) {
|
||||
if (bullet[i].v && PAGE_CONTAINS(bullet[i].y - (SHOT_H - 1), bullet[i].y))
|
||||
u8g.drawVLine(bullet[i].x, bullet[i].y - (SHOT_H - 1), SHOT_H);
|
||||
}
|
||||
|
||||
// Draw explosion
|
||||
if (expl.v && PAGE_CONTAINS(expl.y, expl.y + 7 - 1)) {
|
||||
u8g.drawBitmapP(expl.x, expl.y, 2, 7, explosion);
|
||||
--expl.v;
|
||||
}
|
||||
|
||||
// Blink GAME OVER when game is over
|
||||
if (!game_state) draw_game_over();
|
||||
|
||||
if (PAGE_UNDER(MENU_FONT_ASCENT - 1)) {
|
||||
// Draw Score
|
||||
//const uint8_t sx = (LCD_PIXEL_WIDTH - (score >= 10 ? score >= 100 ? score >= 1000 ? 4 : 3 : 2 : 1) * MENU_FONT_WIDTH) / 2;
|
||||
constexpr uint8_t sx = 0;
|
||||
lcd_moveto(sx, MENU_FONT_ASCENT - 1);
|
||||
lcd_put_int(score);
|
||||
|
||||
// Draw lives
|
||||
if (cannons_left)
|
||||
for (uint8_t i = 1; i <= cannons_left; ++i)
|
||||
u8g.drawBitmapP(LCD_PIXEL_WIDTH - i * (LIFE_W), 6 - (LIFE_H), 1, LIFE_H, life);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void lcd_goto_invaders() {
|
||||
game_state = 20; // countdown to reset invaders
|
||||
score = 0;
|
||||
cannons_left = 3;
|
||||
laser.v = 0;
|
||||
reset_invaders();
|
||||
reset_player();
|
||||
ui.goto_screen(game_screen_invaders, 0);
|
||||
ui.defer_status_screen();
|
||||
}
|
||||
|
||||
#endif // MARLIN_INVADERS
|
||||
|
||||
#if ENABLED(MARLIN_SNAKE)
|
||||
|
||||
#define SNAKE_BOX 4
|
||||
|
||||
#define HEADER_H (MENU_FONT_ASCENT - 2)
|
||||
#define SNAKE_WH (SNAKE_BOX + 1)
|
||||
|
||||
#define IDEAL_L 2
|
||||
#define IDEAL_R (LCD_PIXEL_WIDTH - 1 - 2)
|
||||
#define IDEAL_T (HEADER_H + 2)
|
||||
#define IDEAL_B (LCD_PIXEL_HEIGHT - 1 - 2)
|
||||
#define IDEAL_W (IDEAL_R - (IDEAL_L) + 1)
|
||||
#define IDEAL_H (IDEAL_B - (IDEAL_T) + 1)
|
||||
|
||||
#define GAME_W int((IDEAL_W) / (SNAKE_WH))
|
||||
#define GAME_H int((IDEAL_H) / (SNAKE_WH))
|
||||
|
||||
#define BOARD_W ((SNAKE_WH) * (GAME_W) + 1)
|
||||
#define BOARD_H ((SNAKE_WH) * (GAME_H) + 1)
|
||||
#define BOARD_L ((LCD_PIXEL_WIDTH - (BOARD_W) + 1) / 2)
|
||||
#define BOARD_R (BOARD_L + BOARD_W - 1)
|
||||
#define BOARD_T (((LCD_PIXEL_HEIGHT + IDEAL_T) - (BOARD_H)) / 2)
|
||||
#define BOARD_B (BOARD_T + BOARD_H - 1)
|
||||
|
||||
#define GAMEX(X) (BOARD_L + ((X) * (SNAKE_WH)))
|
||||
#define GAMEY(Y) (BOARD_T + ((Y) * (SNAKE_WH)))
|
||||
|
||||
#if SNAKE_BOX > 2
|
||||
#define FOOD_WH SNAKE_BOX
|
||||
#else
|
||||
#define FOOD_WH 2
|
||||
#endif
|
||||
|
||||
#if SNAKE_BOX < 1
|
||||
#define SNAKE_SIZ 1
|
||||
#else
|
||||
#define SNAKE_SIZ SNAKE_BOX
|
||||
#endif
|
||||
|
||||
constexpr fixed_t snakev = FTOP(0.20);
|
||||
|
||||
int8_t snake_dir, // NESW
|
||||
foodx, foody, food_cnt,
|
||||
old_encoder;
|
||||
fixed_t snakex, snakey;
|
||||
|
||||
// Up to 50 lines, then you win!
|
||||
typedef struct { int8_t x, y; } pos_t;
|
||||
uint8_t head_ind;
|
||||
pos_t snake_tail[50];
|
||||
|
||||
// Remove the first pixel from the tail.
|
||||
// If needed, shift out the first segment.
|
||||
void shorten_tail() {
|
||||
pos_t &p = snake_tail[0], &q = snake_tail[1];
|
||||
bool shift = false;
|
||||
if (p.x == q.x) {
|
||||
// Vertical line
|
||||
p.y += (q.y > p.y) ? 1 : -1;
|
||||
shift = p.y == q.y;
|
||||
}
|
||||
else {
|
||||
// Horizontal line
|
||||
p.x += (q.x > p.x) ? 1 : -1;
|
||||
shift = p.x == q.x;
|
||||
}
|
||||
if (shift) {
|
||||
head_ind--;
|
||||
for (uint8_t i = 0; i <= head_ind; ++i)
|
||||
snake_tail[i] = snake_tail[i + 1];
|
||||
}
|
||||
}
|
||||
|
||||
// The food is on a line
|
||||
inline bool food_on_line() {
|
||||
for (uint8_t n = 0; n < head_ind; ++n) {
|
||||
pos_t &p = snake_tail[n], &q = snake_tail[n + 1];
|
||||
if (p.x == q.x) {
|
||||
if ((foodx == p.x - 1 || foodx == p.x) && WITHIN(foody, MIN(p.y, q.y), MAX(p.y, q.y)))
|
||||
return true;
|
||||
}
|
||||
else if ((foody == p.y - 1 || foody == p.y) && WITHIN(foodx, MIN(p.x, q.x), MAX(p.x, q.x)))
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
// Add a new food blob
|
||||
void food_reset() {
|
||||
do {
|
||||
foodx = random(0, GAME_W);
|
||||
foody = random(0, GAME_H);
|
||||
} while (food_on_line());
|
||||
}
|
||||
|
||||
// Turn the snake cw or ccw
|
||||
inline void turn_snake(const bool cw) {
|
||||
snake_dir += cw ? 1 : -1;
|
||||
snake_dir &= 0x03;
|
||||
head_ind++;
|
||||
snake_tail[head_ind].x = FTOB(snakex);
|
||||
snake_tail[head_ind].y = FTOB(snakey);
|
||||
}
|
||||
|
||||
// Reset the snake for a new game
|
||||
void snake_reset() {
|
||||
// Init the head and velocity
|
||||
snakex = BTOF(1);
|
||||
snakey = BTOF(GAME_H / 2);
|
||||
//snakev = FTOP(0.25);
|
||||
|
||||
// Init the tail with a cw turn
|
||||
snake_dir = 0;
|
||||
head_ind = 0;
|
||||
snake_tail[0].x = 0;
|
||||
snake_tail[0].y = GAME_H / 2;
|
||||
turn_snake(true);
|
||||
|
||||
// Clear food flag
|
||||
food_cnt = 5;
|
||||
|
||||
// Clear the controls
|
||||
ui.encoderPosition = 0;
|
||||
old_encoder = 0;
|
||||
}
|
||||
|
||||
// Check if head segment overlaps another
|
||||
bool snake_overlap() {
|
||||
// 4 lines must exist before a collision is possible
|
||||
if (head_ind < 4) return false;
|
||||
// Is the last segment crossing any others?
|
||||
const pos_t &h1 = snake_tail[head_ind - 1], &h2 = snake_tail[head_ind];
|
||||
// VERTICAL head segment?
|
||||
if (h1.x == h2.x) {
|
||||
// Loop from oldest to segment two away from head
|
||||
for (uint8_t n = 0; n < head_ind - 2; ++n) {
|
||||
// Segment p to q
|
||||
const pos_t &p = snake_tail[n], &q = snake_tail[n + 1];
|
||||
if (p.x != q.x) {
|
||||
// Crossing horizontal segment
|
||||
if (WITHIN(h1.x, MIN(p.x, q.x), MAX(p.x, q.x)) && (h1.y <= p.y) == (h2.y >= p.y)) return true;
|
||||
} // Overlapping vertical segment
|
||||
else if (h1.x == p.x && MIN(h1.y, h2.y) <= MAX(p.y, q.y) && MAX(h1.y, h2.y) >= MIN(p.y, q.y)) return true;
|
||||
}
|
||||
}
|
||||
else {
|
||||
// Loop from oldest to segment two away from head
|
||||
for (uint8_t n = 0; n < head_ind - 2; ++n) {
|
||||
// Segment p to q
|
||||
const pos_t &p = snake_tail[n], &q = snake_tail[n + 1];
|
||||
if (p.y != q.y) {
|
||||
// Crossing vertical segment
|
||||
if (WITHIN(h1.y, MIN(p.y, q.y), MAX(p.y, q.y)) && (h1.x <= p.x) == (h2.x >= p.x)) return true;
|
||||
} // Overlapping horizontal segment
|
||||
else if (h1.y == p.y && MIN(h1.x, h2.x) <= MAX(p.x, q.x) && MAX(h1.x, h2.x) >= MIN(p.x, q.x)) return true;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
void game_screen_snake() {
|
||||
static int8_t slew;
|
||||
if (ui.first_page) slew = 2;
|
||||
ui.refresh(LCDVIEW_CALL_NO_REDRAW); // Call as often as possible
|
||||
|
||||
// Run the snake logic
|
||||
if (game_state && slew-- > 0) do { // Run logic twice for finer resolution
|
||||
|
||||
// Move the snake's head one unit in the current direction
|
||||
const int8_t oldx = FTOB(snakex), oldy = FTOB(snakey);
|
||||
switch (snake_dir) {
|
||||
case 0: snakey -= snakev; break;
|
||||
case 1: snakex += snakev; break;
|
||||
case 2: snakey += snakev; break;
|
||||
case 3: snakex -= snakev; break;
|
||||
}
|
||||
const int8_t x = FTOB(snakex), y = FTOB(snakey);
|
||||
|
||||
// If movement took place...
|
||||
if (oldx != x || oldy != y) {
|
||||
|
||||
if (!WITHIN(x, 0, GAME_W - 1) || !WITHIN(y, 0, GAME_H - 1)) {
|
||||
game_state = 0; // Game Over
|
||||
_BUZZ(400, 40); // Bzzzt!
|
||||
break; // ...out of do-while
|
||||
}
|
||||
|
||||
snake_tail[head_ind].x = x;
|
||||
snake_tail[head_ind].y = y;
|
||||
|
||||
// Change snake direction if set
|
||||
const int8_t enc = int8_t(ui.encoderPosition), diff = enc - old_encoder;
|
||||
if (diff) {
|
||||
old_encoder = enc;
|
||||
turn_snake(diff > 0);
|
||||
}
|
||||
|
||||
if (food_cnt) --food_cnt; else shorten_tail();
|
||||
|
||||
// Did the snake collide with itself or go out of bounds?
|
||||
if (snake_overlap()) {
|
||||
game_state = 0; // Game Over
|
||||
_BUZZ(400, 40); // Bzzzt!
|
||||
}
|
||||
// Is the snake at the food?
|
||||
else if (x == foodx && y == foody) {
|
||||
_BUZZ(5, 220);
|
||||
_BUZZ(5, 280);
|
||||
score++;
|
||||
food_cnt = 2;
|
||||
food_reset();
|
||||
}
|
||||
}
|
||||
|
||||
} while(0);
|
||||
|
||||
u8g.setColorIndex(1);
|
||||
|
||||
// Draw Score
|
||||
if (PAGE_UNDER(HEADER_H)) {
|
||||
lcd_moveto(0, HEADER_H - 1);
|
||||
lcd_put_int(score);
|
||||
}
|
||||
|
||||
// DRAW THE PLAYFIELD BORDER
|
||||
u8g.drawFrame(BOARD_L - 2, BOARD_T - 2, BOARD_R - BOARD_L + 4, BOARD_B - BOARD_T + 4);
|
||||
|
||||
// Draw the snake (tail)
|
||||
#if SNAKE_WH < 2
|
||||
|
||||
// At this scale just draw a line
|
||||
for (uint8_t n = 0; n < head_ind; ++n) {
|
||||
const pos_t &p = snake_tail[n], &q = snake_tail[n + 1];
|
||||
if (p.x == q.x) {
|
||||
const int8_t y1 = GAMEY(MIN(p.y, q.y)), y2 = GAMEY(MAX(p.y, q.y));
|
||||
if (PAGE_CONTAINS(y1, y2))
|
||||
u8g.drawVLine(GAMEX(p.x), y1, y2 - y1 + 1);
|
||||
}
|
||||
else if (PAGE_CONTAINS(GAMEY(p.y), GAMEY(p.y))) {
|
||||
const int8_t x1 = GAMEX(MIN(p.x, q.x)), x2 = GAMEX(MAX(p.x, q.x));
|
||||
u8g.drawHLine(x1, GAMEY(p.y), x2 - x1 + 1);
|
||||
}
|
||||
}
|
||||
|
||||
#elif SNAKE_WH == 2
|
||||
|
||||
// At this scale draw two lines
|
||||
for (uint8_t n = 0; n < head_ind; ++n) {
|
||||
const pos_t &p = snake_tail[n], &q = snake_tail[n + 1];
|
||||
if (p.x == q.x) {
|
||||
const int8_t y1 = GAMEY(MIN(p.y, q.y)), y2 = GAMEY(MAX(p.y, q.y));
|
||||
if (PAGE_CONTAINS(y1, y2 + 1))
|
||||
u8g.drawFrame(GAMEX(p.x), y1, 2, y2 - y1 + 1 + 1);
|
||||
}
|
||||
else {
|
||||
const int8_t py = GAMEY(p.y);
|
||||
if (PAGE_CONTAINS(py, py + 1)) {
|
||||
const int8_t x1 = GAMEX(MIN(p.x, q.x)), x2 = GAMEX(MAX(p.x, q.x));
|
||||
u8g.drawFrame(x1, py, x2 - x1 + 1 + 1, 2);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#else
|
||||
|
||||
// Draw a series of boxes
|
||||
for (uint8_t n = 0; n < head_ind; ++n) {
|
||||
const pos_t &p = snake_tail[n], &q = snake_tail[n + 1];
|
||||
if (p.x == q.x) {
|
||||
const int8_t y1 = MIN(p.y, q.y), y2 = MAX(p.y, q.y);
|
||||
if (PAGE_CONTAINS(GAMEY(y1), GAMEY(y2) + SNAKE_SIZ - 1)) {
|
||||
for (int8_t i = y1; i <= y2; ++i) {
|
||||
const int8_t y = GAMEY(i);
|
||||
if (PAGE_CONTAINS(y, y + SNAKE_SIZ - 1))
|
||||
u8g.drawBox(GAMEX(p.x), y, SNAKE_SIZ, SNAKE_SIZ);
|
||||
}
|
||||
}
|
||||
}
|
||||
else {
|
||||
const int8_t py = GAMEY(p.y);
|
||||
if (PAGE_CONTAINS(py, py + SNAKE_SIZ - 1)) {
|
||||
const int8_t x1 = MIN(p.x, q.x), x2 = MAX(p.x, q.x);
|
||||
for (int8_t i = x1; i <= x2; ++i)
|
||||
u8g.drawBox(GAMEX(i), py, SNAKE_SIZ, SNAKE_SIZ);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
// Draw food
|
||||
const int8_t fy = GAMEY(foody);
|
||||
if (PAGE_CONTAINS(fy, fy + FOOD_WH - 1)) {
|
||||
const int8_t fx = GAMEX(foodx);
|
||||
u8g.drawFrame(fx, fy, FOOD_WH, FOOD_WH);
|
||||
if (FOOD_WH == 5) u8g.drawPixel(fx + 2, fy + 2);
|
||||
}
|
||||
|
||||
// Draw GAME OVER
|
||||
if (!game_state) draw_game_over();
|
||||
|
||||
// A click always exits this game
|
||||
if (ui.use_click()) ui.goto_previous_screen();
|
||||
}
|
||||
|
||||
void lcd_goto_snake() {
|
||||
game_state = 1; // Game running
|
||||
score = 0;
|
||||
snake_reset();
|
||||
food_reset();
|
||||
ui.encoder_direction_normal();
|
||||
ui.goto_screen(game_screen_snake);
|
||||
ui.defer_status_screen();
|
||||
}
|
||||
|
||||
#endif // MARLIN_SNAKE
|
||||
|
||||
#if HAS_GAME_MENU
|
||||
#include "game/game.h"
|
||||
|
||||
void menu_game() {
|
||||
START_MENU();
|
||||
MENU_BACK(MSG_MAIN);
|
||||
#if ENABLED(MARLIN_BRICKOUT)
|
||||
MENU_ITEM(submenu, MSG_BRICKOUT, lcd_goto_brickout);
|
||||
MENU_ITEM(submenu, MSG_BRICKOUT, brickout.enter_game);
|
||||
#endif
|
||||
#if ENABLED(MARLIN_INVADERS)
|
||||
MENU_ITEM(submenu, MSG_INVADERS, lcd_goto_invaders);
|
||||
MENU_ITEM(submenu, MSG_INVADERS, invaders.enter_game);
|
||||
#endif
|
||||
#if ENABLED(MARLIN_SNAKE)
|
||||
MENU_ITEM(submenu, MSG_SNAKE, lcd_goto_snake);
|
||||
MENU_ITEM(submenu, MSG_SNAKE, snake.enter_game);
|
||||
#endif
|
||||
#if ENABLED(MARLIN_MAZE)
|
||||
MENU_ITEM(submenu, MSG_MAZE, maze.enter_game);
|
||||
#endif
|
||||
END_MENU();
|
||||
}
|
||||
|
||||
#endif
|
||||
#endif // HAS_GAME_MENU
|
||||
|
||||
#endif // HAS_LCD_MENU && (MARLIN_BRICKOUT || MARLIN_INVADERS || MARLIN_SNAKE)
|
||||
|
|
|
@ -33,19 +33,20 @@
|
|||
#include "../../gcode/queue.h"
|
||||
#include "../../module/printcounter.h"
|
||||
#include "../../module/stepper.h"
|
||||
#include "../../sd/cardreader.h"
|
||||
|
||||
#if ENABLED(POWER_LOSS_RECOVERY)
|
||||
#include "../../feature/power_loss_recovery.h"
|
||||
#endif
|
||||
|
||||
#if ENABLED(SDSUPPORT)
|
||||
#include "../../sd/cardreader.h"
|
||||
#endif
|
||||
|
||||
#if ENABLED(HOST_ACTION_COMMANDS)
|
||||
#include "../../feature/host_actions.h"
|
||||
#endif
|
||||
|
||||
#if HAS_GAMES
|
||||
#include "game/game.h"
|
||||
#endif
|
||||
|
||||
#define MACHINE_CAN_STOP (EITHER(SDSUPPORT, HOST_PROMPT_SUPPORT) || defined(ACTION_ON_CANCEL))
|
||||
#define MACHINE_CAN_PAUSE (ANY(SDSUPPORT, HOST_PROMPT_SUPPORT, PARK_HEAD_ON_PAUSE) || defined(ACTION_ON_PAUSE))
|
||||
|
||||
|
@ -152,7 +153,7 @@ void menu_main() {
|
|||
START_MENU();
|
||||
MENU_BACK(MSG_WATCH);
|
||||
|
||||
const bool busy = printer_busy()
|
||||
const bool busy = IS_SD_PRINTING() || print_job_timer.isRunning()
|
||||
#if ENABLED(SDSUPPORT)
|
||||
, card_detected = card.isDetected()
|
||||
, card_open = card_detected && card.isFileOpen()
|
||||
|
@ -286,16 +287,19 @@ void menu_main() {
|
|||
#endif
|
||||
#endif
|
||||
|
||||
#if ANY(MARLIN_BRICKOUT, MARLIN_INVADERS, MARLIN_SNAKE)
|
||||
#if ANY(MARLIN_BRICKOUT, MARLIN_INVADERS, MARLIN_SNAKE, MARLIN_MAZE)
|
||||
MENU_ITEM(submenu, "Game", (
|
||||
#if HAS_GAME_MENU
|
||||
menu_game
|
||||
#elif ENABLED(MARLIN_BRICKOUT)
|
||||
lcd_goto_brickout
|
||||
brickout.enter_game
|
||||
#elif ENABLED(MARLIN_INVADERS)
|
||||
lcd_goto_invaders
|
||||
invaders.enter_game
|
||||
#elif ENABLED(MARLIN_SNAKE)
|
||||
lcd_goto_snake
|
||||
snake.enter_game
|
||||
#elif ENABLED(MARLIN_MAZE)
|
||||
maze.enter_game
|
||||
#endif
|
||||
));
|
||||
#endif
|
||||
|
||||
|
|
|
@ -44,7 +44,7 @@
|
|||
ui.encoder_direction_normal();
|
||||
ENCODER_RATE_MULTIPLY(true);
|
||||
if (ui.encoderPosition != 0) {
|
||||
mixer.gradient.start_z += float((int)ui.encoderPosition) * 0.1;
|
||||
mixer.gradient.start_z += float(int16_t(ui.encoderPosition)) * 0.1;
|
||||
ui.encoderPosition = 0;
|
||||
NOLESS(mixer.gradient.start_z, 0);
|
||||
NOMORE(mixer.gradient.start_z, Z_MAX_POS);
|
||||
|
@ -69,7 +69,7 @@
|
|||
ui.encoder_direction_normal();
|
||||
ENCODER_RATE_MULTIPLY(true);
|
||||
if (ui.encoderPosition != 0) {
|
||||
mixer.gradient.end_z += float((int)ui.encoderPosition) * 0.1;
|
||||
mixer.gradient.end_z += float(int16_t(ui.encoderPosition)) * 0.1;
|
||||
ui.encoderPosition = 0;
|
||||
NOLESS(mixer.gradient.end_z, 0);
|
||||
NOMORE(mixer.gradient.end_z, Z_MAX_POS);
|
||||
|
@ -185,7 +185,7 @@ void lcd_mixer_mix_edit() {
|
|||
#elif DUAL_MIXING_EXTRUDER
|
||||
|
||||
if (ui.encoderPosition != 0) {
|
||||
mixer.mix[0] += (int)ui.encoderPosition;
|
||||
mixer.mix[0] += int16_t(ui.encoderPosition);
|
||||
ui.encoderPosition = 0;
|
||||
if (mixer.mix[0] < 0) mixer.mix[0] += 101;
|
||||
if (mixer.mix[0] > 100) mixer.mix[0] -= 101;
|
||||
|
|
|
@ -35,60 +35,60 @@ bool mmuMenuWait;
|
|||
// Load Filament
|
||||
//
|
||||
|
||||
void _mmu2_loadFilamentToNozzle(uint8_t index) {
|
||||
void _mmu2_load_filamentToNozzle(uint8_t index) {
|
||||
ui.reset_status();
|
||||
ui.return_to_status();
|
||||
ui.status_printf_P(0, PSTR(MSG_MMU2_LOADING_FILAMENT), int(index + 1));
|
||||
if (mmu2.loadFilamentToNozzle(index)) ui.reset_status();
|
||||
if (mmu2.load_filament_to_nozzle(index)) ui.reset_status();
|
||||
}
|
||||
|
||||
inline void action_mmu2_loadFilamentToNozzle(const uint8_t tool) {
|
||||
_mmu2_loadFilamentToNozzle(tool);
|
||||
inline void action_mmu2_load_filament_to_nozzl_e(const uint8_t tool) {
|
||||
_mmu2_load_filamentToNozzle(tool);
|
||||
ui.return_to_status();
|
||||
}
|
||||
inline void action_mmu2_loadFilamentToNozzle0() { action_mmu2_loadFilamentToNozzle(0); }
|
||||
inline void action_mmu2_loadFilamentToNozzle1() { action_mmu2_loadFilamentToNozzle(1); }
|
||||
inline void action_mmu2_loadFilamentToNozzle2() { action_mmu2_loadFilamentToNozzle(2); }
|
||||
inline void action_mmu2_loadFilamentToNozzle3() { action_mmu2_loadFilamentToNozzle(3); }
|
||||
inline void action_mmu2_loadFilamentToNozzle4() { action_mmu2_loadFilamentToNozzle(4); }
|
||||
inline void action_mmu2_load_filament_to_nozzle_0() { action_mmu2_load_filament_to_nozzl_e(0); }
|
||||
inline void action_mmu2_load_filament_to_nozzle_1() { action_mmu2_load_filament_to_nozzl_e(1); }
|
||||
inline void action_mmu2_load_filament_to_nozzle_2() { action_mmu2_load_filament_to_nozzl_e(2); }
|
||||
inline void action_mmu2_load_filament_to_nozzle_3() { action_mmu2_load_filament_to_nozzl_e(3); }
|
||||
inline void action_mmu2_load_filament_to_nozzle_4() { action_mmu2_load_filament_to_nozzl_e(4); }
|
||||
|
||||
void _mmu2_loadFilament(uint8_t index) {
|
||||
void _mmu2_load_filament(uint8_t index) {
|
||||
ui.return_to_status();
|
||||
ui.status_printf_P(0, PSTR(MSG_MMU2_LOADING_FILAMENT), int(index + 1));
|
||||
mmu2.loadFilament(index);
|
||||
mmu2.load_filament(index);
|
||||
ui.reset_status();
|
||||
}
|
||||
void action_mmu2_loadAll() {
|
||||
void action_mmu2_load_all() {
|
||||
for (uint8_t i = 0; i < EXTRUDERS; i++)
|
||||
_mmu2_loadFilament(i);
|
||||
_mmu2_load_filament(i);
|
||||
ui.return_to_status();
|
||||
}
|
||||
inline void action_mmu2_loadFilament0() { _mmu2_loadFilament(0); }
|
||||
inline void action_mmu2_loadFilament1() { _mmu2_loadFilament(1); }
|
||||
inline void action_mmu2_loadFilament2() { _mmu2_loadFilament(2); }
|
||||
inline void action_mmu2_loadFilament3() { _mmu2_loadFilament(3); }
|
||||
inline void action_mmu2_loadFilament4() { _mmu2_loadFilament(4); }
|
||||
inline void action_mmu2_load_filament_0() { _mmu2_load_filament(0); }
|
||||
inline void action_mmu2_load_filament_1() { _mmu2_load_filament(1); }
|
||||
inline void action_mmu2_load_filament_2() { _mmu2_load_filament(2); }
|
||||
inline void action_mmu2_load_filament_3() { _mmu2_load_filament(3); }
|
||||
inline void action_mmu2_load_filament_4() { _mmu2_load_filament(4); }
|
||||
|
||||
void menu_mmu2_loadFilament() {
|
||||
void menu_mmu2_load_filament() {
|
||||
START_MENU();
|
||||
MENU_BACK(MSG_MMU2_MENU);
|
||||
MENU_ITEM(function, MSG_MMU2_ALL, action_mmu2_loadAll);
|
||||
MENU_ITEM(function, MSG_MMU2_FILAMENT0, action_mmu2_loadFilament0);
|
||||
MENU_ITEM(function, MSG_MMU2_FILAMENT1, action_mmu2_loadFilament1);
|
||||
MENU_ITEM(function, MSG_MMU2_FILAMENT2, action_mmu2_loadFilament2);
|
||||
MENU_ITEM(function, MSG_MMU2_FILAMENT3, action_mmu2_loadFilament3);
|
||||
MENU_ITEM(function, MSG_MMU2_FILAMENT4, action_mmu2_loadFilament4);
|
||||
MENU_ITEM(function, MSG_MMU2_ALL, action_mmu2_load_all);
|
||||
MENU_ITEM(function, MSG_MMU2_FILAMENT0, action_mmu2_load_filament_0);
|
||||
MENU_ITEM(function, MSG_MMU2_FILAMENT1, action_mmu2_load_filament_1);
|
||||
MENU_ITEM(function, MSG_MMU2_FILAMENT2, action_mmu2_load_filament_2);
|
||||
MENU_ITEM(function, MSG_MMU2_FILAMENT3, action_mmu2_load_filament_3);
|
||||
MENU_ITEM(function, MSG_MMU2_FILAMENT4, action_mmu2_load_filament_4);
|
||||
END_MENU();
|
||||
}
|
||||
|
||||
void menu_mmu2_loadToNozzle() {
|
||||
void menu_mmu2_load_to_nozzle() {
|
||||
START_MENU();
|
||||
MENU_BACK(MSG_MMU2_MENU);
|
||||
MENU_ITEM(function, MSG_MMU2_FILAMENT0, action_mmu2_loadFilamentToNozzle0);
|
||||
MENU_ITEM(function, MSG_MMU2_FILAMENT1, action_mmu2_loadFilamentToNozzle1);
|
||||
MENU_ITEM(function, MSG_MMU2_FILAMENT2, action_mmu2_loadFilamentToNozzle2);
|
||||
MENU_ITEM(function, MSG_MMU2_FILAMENT3, action_mmu2_loadFilamentToNozzle3);
|
||||
MENU_ITEM(function, MSG_MMU2_FILAMENT4, action_mmu2_loadFilamentToNozzle4);
|
||||
MENU_ITEM(function, MSG_MMU2_FILAMENT0, action_mmu2_load_filament_to_nozzle_0);
|
||||
MENU_ITEM(function, MSG_MMU2_FILAMENT1, action_mmu2_load_filament_to_nozzle_1);
|
||||
MENU_ITEM(function, MSG_MMU2_FILAMENT2, action_mmu2_load_filament_to_nozzle_2);
|
||||
MENU_ITEM(function, MSG_MMU2_FILAMENT3, action_mmu2_load_filament_to_nozzle_3);
|
||||
MENU_ITEM(function, MSG_MMU2_FILAMENT4, action_mmu2_load_filament_to_nozzle_4);
|
||||
END_MENU();
|
||||
}
|
||||
|
||||
|
@ -96,19 +96,19 @@ void menu_mmu2_loadToNozzle() {
|
|||
// Eject Filament
|
||||
//
|
||||
|
||||
void _mmu2_ejectFilament(uint8_t index) {
|
||||
void _mmu2_eject_filament(uint8_t index) {
|
||||
ui.reset_status();
|
||||
ui.return_to_status();
|
||||
ui.status_printf_P(0, PSTR(MSG_MMU2_EJECTING_FILAMENT), int(index + 1));
|
||||
if (mmu2.ejectFilament(index, true)) ui.reset_status();
|
||||
if (mmu2.eject_filament(index, true)) ui.reset_status();
|
||||
}
|
||||
inline void action_mmu2_ejectFilament0() { _mmu2_ejectFilament(0); }
|
||||
inline void action_mmu2_ejectFilament1() { _mmu2_ejectFilament(1); }
|
||||
inline void action_mmu2_ejectFilament2() { _mmu2_ejectFilament(2); }
|
||||
inline void action_mmu2_ejectFilament3() { _mmu2_ejectFilament(3); }
|
||||
inline void action_mmu2_ejectFilament4() { _mmu2_ejectFilament(4); }
|
||||
inline void action_mmu2_eject_filament_0() { _mmu2_eject_filament(0); }
|
||||
inline void action_mmu2_eject_filament_1() { _mmu2_eject_filament(1); }
|
||||
inline void action_mmu2_eject_filament_2() { _mmu2_eject_filament(2); }
|
||||
inline void action_mmu2_eject_filament_3() { _mmu2_eject_filament(3); }
|
||||
inline void action_mmu2_eject_filament_4() { _mmu2_eject_filament(4); }
|
||||
|
||||
void action_mmu2_unloadFilament() {
|
||||
void action_mmu2_unload_filament() {
|
||||
ui.reset_status();
|
||||
ui.return_to_status();
|
||||
LCD_MESSAGEPGM(MSG_MMU2_UNLOADING_FILAMENT);
|
||||
|
@ -116,14 +116,14 @@ void action_mmu2_unloadFilament() {
|
|||
if (mmu2.unload()) ui.reset_status();
|
||||
}
|
||||
|
||||
void menu_mmu2_ejectFilament() {
|
||||
void menu_mmu2_eject_filament() {
|
||||
START_MENU();
|
||||
MENU_BACK(MSG_MMU2_MENU);
|
||||
MENU_ITEM(function, MSG_MMU2_FILAMENT0, action_mmu2_ejectFilament0);
|
||||
MENU_ITEM(function, MSG_MMU2_FILAMENT1, action_mmu2_ejectFilament1);
|
||||
MENU_ITEM(function, MSG_MMU2_FILAMENT2, action_mmu2_ejectFilament2);
|
||||
MENU_ITEM(function, MSG_MMU2_FILAMENT3, action_mmu2_ejectFilament3);
|
||||
MENU_ITEM(function, MSG_MMU2_FILAMENT4, action_mmu2_ejectFilament4);
|
||||
MENU_ITEM(function, MSG_MMU2_FILAMENT0, action_mmu2_eject_filament_0);
|
||||
MENU_ITEM(function, MSG_MMU2_FILAMENT1, action_mmu2_eject_filament_1);
|
||||
MENU_ITEM(function, MSG_MMU2_FILAMENT2, action_mmu2_eject_filament_2);
|
||||
MENU_ITEM(function, MSG_MMU2_FILAMENT3, action_mmu2_eject_filament_3);
|
||||
MENU_ITEM(function, MSG_MMU2_FILAMENT4, action_mmu2_eject_filament_4);
|
||||
END_MENU();
|
||||
}
|
||||
|
||||
|
@ -139,10 +139,10 @@ void action_mmu2_reset() {
|
|||
void menu_mmu2() {
|
||||
START_MENU();
|
||||
MENU_BACK(MSG_MAIN);
|
||||
MENU_ITEM(submenu, MSG_MMU2_LOAD_FILAMENT, menu_mmu2_loadFilament);
|
||||
MENU_ITEM(submenu, MSG_MMU2_LOAD_TO_NOZZLE, menu_mmu2_loadToNozzle);
|
||||
MENU_ITEM(submenu, MSG_MMU2_EJECT_FILAMENT, menu_mmu2_ejectFilament);
|
||||
MENU_ITEM(function, MSG_MMU2_UNLOAD_FILAMENT, action_mmu2_unloadFilament);
|
||||
MENU_ITEM(submenu, MSG_MMU2_LOAD_FILAMENT, menu_mmu2_load_filament);
|
||||
MENU_ITEM(submenu, MSG_MMU2_LOAD_TO_NOZZLE, menu_mmu2_load_to_nozzle);
|
||||
MENU_ITEM(submenu, MSG_MMU2_EJECT_FILAMENT, menu_mmu2_eject_filament);
|
||||
MENU_ITEM(function, MSG_MMU2_UNLOAD_FILAMENT, action_mmu2_unload_filament);
|
||||
MENU_ITEM(function, MSG_MMU2_RESET, action_mmu2_reset);
|
||||
END_MENU();
|
||||
}
|
||||
|
@ -161,7 +161,7 @@ inline void action_mmu2_choose2() { action_mmu2_choose(2); }
|
|||
inline void action_mmu2_choose3() { action_mmu2_choose(3); }
|
||||
inline void action_mmu2_choose4() { action_mmu2_choose(4); }
|
||||
|
||||
void menu_mmu2_chooseFilament() {
|
||||
void menu_mmu2_choose_filament() {
|
||||
START_MENU();
|
||||
#if LCD_HEIGHT > 2
|
||||
STATIC_ITEM(MSG_MMU2_CHOOSE_FILAMENT_HEADER, true, true);
|
||||
|
@ -178,21 +178,21 @@ void menu_mmu2_chooseFilament() {
|
|||
// MMU2 Filament Runout
|
||||
//
|
||||
|
||||
inline void action_mmu2_M600_loadCurrentFilament() { mmu2.loadFilament(currentTool); }
|
||||
inline void action_mmu2_M600_loadCurrentFilamentToNozzle() { mmu2.loadFilamentToNozzle(currentTool); }
|
||||
inline void action_mmu2_M600_unloadFilament() { mmu2.unload(); }
|
||||
inline void action_mmu2_M600_load_current_filament() { mmu2.load_filament(currentTool); }
|
||||
inline void action_mmu2_M600_load_current_filament_to_nozzle() { mmu2.load_filament_to_nozzle(currentTool); }
|
||||
inline void action_mmu2_M600_unload_filament() { mmu2.unload(); }
|
||||
inline void action_mmu2_M600_resume() { mmuMenuWait = false; }
|
||||
|
||||
void menu_mmu2_pause() {
|
||||
currentTool = mmu2.getCurrentTool();
|
||||
currentTool = mmu2.get_current_tool();
|
||||
START_MENU();
|
||||
#if LCD_HEIGHT > 2
|
||||
STATIC_ITEM(MSG_MMU2_FILAMENT_CHANGE_HEADER, true, true);
|
||||
#endif
|
||||
MENU_ITEM(function, MSG_MMU2_RESUME, action_mmu2_M600_resume);
|
||||
MENU_ITEM(function, MSG_MMU2_UNLOAD_FILAMENT, action_mmu2_M600_unloadFilament);
|
||||
MENU_ITEM(function, MSG_MMU2_LOAD_FILAMENT, action_mmu2_M600_loadCurrentFilament);
|
||||
MENU_ITEM(function, MSG_MMU2_LOAD_TO_NOZZLE, action_mmu2_M600_loadCurrentFilamentToNozzle);
|
||||
MENU_ITEM(function, MSG_MMU2_UNLOAD_FILAMENT, action_mmu2_M600_unload_filament);
|
||||
MENU_ITEM(function, MSG_MMU2_LOAD_FILAMENT, action_mmu2_M600_load_current_filament);
|
||||
MENU_ITEM(function, MSG_MMU2_LOAD_TO_NOZZLE, action_mmu2_M600_load_current_filament_to_nozzle);
|
||||
END_MENU();
|
||||
}
|
||||
|
||||
|
@ -203,9 +203,9 @@ void mmu2_M600() {
|
|||
while (mmuMenuWait) idle();
|
||||
}
|
||||
|
||||
uint8_t mmu2_chooseFilament() {
|
||||
uint8_t mmu2_choose_filament() {
|
||||
ui.defer_status_screen();
|
||||
ui.goto_screen(menu_mmu2_chooseFilament);
|
||||
ui.goto_screen(menu_mmu2_choose_filament);
|
||||
mmuMenuWait = true;
|
||||
while (mmuMenuWait) idle();
|
||||
ui.return_to_status();
|
||||
|
|
|
@ -25,4 +25,4 @@
|
|||
|
||||
void menu_mmu2();
|
||||
void mmu2_M600();
|
||||
uint8_t mmu2_chooseFilament();
|
||||
uint8_t mmu2_choose_filament();
|
||||
|
|
|
@ -121,16 +121,16 @@ static void _lcd_move_xyz(PGM_P name, AxisEnum axis) {
|
|||
#endif
|
||||
|
||||
// Get the new position
|
||||
const float diff = float((int32_t)ui.encoderPosition) * move_menu_scale;
|
||||
const float diff = float(int16_t(ui.encoderPosition)) * move_menu_scale;
|
||||
#if IS_KINEMATIC
|
||||
manual_move_offset += diff;
|
||||
if ((int32_t)ui.encoderPosition < 0)
|
||||
if (int16_t(ui.encoderPosition) < 0)
|
||||
NOLESS(manual_move_offset, min - current_position[axis]);
|
||||
else
|
||||
NOMORE(manual_move_offset, max - current_position[axis]);
|
||||
#else
|
||||
current_position[axis] += diff;
|
||||
if ((int32_t)ui.encoderPosition < 0)
|
||||
if (int16_t(ui.encoderPosition) < 0)
|
||||
NOLESS(current_position[axis], min);
|
||||
else
|
||||
NOMORE(current_position[axis], max);
|
||||
|
@ -161,7 +161,7 @@ static void _lcd_move_e(
|
|||
ui.encoder_direction_normal();
|
||||
if (ui.encoderPosition) {
|
||||
if (!ui.processing_manual_move) {
|
||||
const float diff = float((int32_t)ui.encoderPosition) * move_menu_scale;
|
||||
const float diff = float(int16_t(ui.encoderPosition)) * move_menu_scale;
|
||||
#if IS_KINEMATIC
|
||||
manual_move_offset += diff;
|
||||
#else
|
||||
|
@ -335,7 +335,7 @@ void menu_move() {
|
|||
else
|
||||
MENU_ITEM(gcode, MSG_AUTO_HOME, PSTR("G28"));
|
||||
|
||||
#if EITHER(SWITCHING_EXTRUDER, SWITCHING_NOZZLE)
|
||||
#if ANY(SWITCHING_EXTRUDER, SWITCHING_NOZZLE, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
|
||||
#if EXTRUDERS == 6
|
||||
switch (active_extruder) {
|
||||
|
@ -465,7 +465,7 @@ void menu_motion() {
|
|||
#if DISABLED(PROBE_MANUALLY)
|
||||
MENU_ITEM(gcode, MSG_LEVEL_BED, PSTR("G28\nG29"));
|
||||
#endif
|
||||
if (leveling_is_valid()) {
|
||||
if (all_axes_homed() && leveling_is_valid()) {
|
||||
bool new_level_state = planner.leveling_active;
|
||||
MENU_ITEM_EDIT_CALLBACK(bool, MSG_BED_LEVELING, &new_level_state, _lcd_toggle_bed_leveling);
|
||||
}
|
||||
|
|
|
@ -47,10 +47,11 @@ void lcd_sd_updir() {
|
|||
|
||||
#if ENABLED(SD_REPRINT_LAST_SELECTED_FILE)
|
||||
|
||||
uint32_t last_sdfile_encoderPosition = 0xFFFF;
|
||||
uint16_t sd_encoder_position = 0xFFFF;
|
||||
int8_t sd_top_line, sd_items;
|
||||
|
||||
void MarlinUI::reselect_last_file() {
|
||||
if (last_sdfile_encoderPosition == 0xFFFF) return;
|
||||
if (sd_encoder_position == 0xFFFF) return;
|
||||
//#if HAS_GRAPHICAL_LCD
|
||||
// // This is a hack to force a screen update.
|
||||
// ui.refresh(LCDVIEW_CALL_REDRAW_NEXT);
|
||||
|
@ -61,8 +62,8 @@ void lcd_sd_updir() {
|
|||
// ui.drawing_screen = screen_changed = true;
|
||||
//#endif
|
||||
|
||||
goto_screen(menu_sdcard, last_sdfile_encoderPosition);
|
||||
last_sdfile_encoderPosition = 0xFFFF;
|
||||
goto_screen(menu_sdcard, sd_encoder_position, sd_top_line, sd_items);
|
||||
sd_encoder_position = 0xFFFF;
|
||||
|
||||
defer_status_screen();
|
||||
|
||||
|
@ -72,15 +73,44 @@ void lcd_sd_updir() {
|
|||
}
|
||||
#endif
|
||||
|
||||
inline void sdcard_start_selected_file() {
|
||||
card.openAndPrintFile(card.filename);
|
||||
ui.return_to_status();
|
||||
ui.reset_status();
|
||||
}
|
||||
|
||||
#if ENABLED(SD_MENU_CONFIRM_START)
|
||||
|
||||
bool do_print_file;
|
||||
void menu_sd_confirm() {
|
||||
if (ui.should_draw())
|
||||
do_select_screen(PSTR(MSG_BUTTON_PRINT), PSTR(MSG_BUTTON_CANCEL), do_print_file, PSTR(MSG_START_PRINT " "), card.longest_filename(), PSTR("?"));
|
||||
|
||||
if (ui.use_click()) {
|
||||
if (do_print_file)
|
||||
sdcard_start_selected_file();
|
||||
else
|
||||
ui.goto_previous_screen();
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
class MenuItem_sdfile {
|
||||
public:
|
||||
static void action(CardReader &theCard) {
|
||||
#if ENABLED(SD_REPRINT_LAST_SELECTED_FILE)
|
||||
last_sdfile_encoderPosition = ui.encoderPosition; // Save which file was selected for later use
|
||||
// Save menu state for the selected file
|
||||
sd_encoder_position = ui.encoderPosition;
|
||||
sd_top_line = encoderTopLine;
|
||||
sd_items = screen_items;
|
||||
#endif
|
||||
#if ENABLED(SD_MENU_CONFIRM_START)
|
||||
do_print_file = false;
|
||||
MenuItem_submenu::action(menu_sd_confirm);
|
||||
#else
|
||||
sdcard_start_selected_file();
|
||||
#endif
|
||||
card.openAndPrintFile(theCard.filename);
|
||||
ui.return_to_status();
|
||||
ui.reset_status();
|
||||
}
|
||||
};
|
||||
|
||||
|
@ -89,7 +119,7 @@ class MenuItem_sdfolder {
|
|||
static void action(CardReader &theCard) {
|
||||
card.chdir(theCard.filename);
|
||||
encoderTopLine = 0;
|
||||
ui.encoderPosition = 2 * ENCODER_STEPS_PER_MENU_ITEM;
|
||||
ui.encoderPosition = 2 * (ENCODER_STEPS_PER_MENU_ITEM);
|
||||
screen_changed = true;
|
||||
#if HAS_GRAPHICAL_LCD
|
||||
ui.drawing_screen = false;
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
|
|
|
@ -65,32 +65,60 @@
|
|||
|
||||
#if ENABLED(BABYSTEPPING)
|
||||
|
||||
long babysteps_done = 0;
|
||||
#include "../../feature/babystep.h"
|
||||
#include "../lcdprint.h"
|
||||
#if HAS_GRAPHICAL_LCD
|
||||
#include "../dogm/ultralcd_DOGM.h"
|
||||
#endif
|
||||
|
||||
void _lcd_babystep(const AxisEnum axis, PGM_P msg) {
|
||||
void _lcd_babystep(const AxisEnum axis, PGM_P const msg) {
|
||||
if (ui.use_click()) return ui.goto_previous_screen_no_defer();
|
||||
ui.encoder_direction_normal();
|
||||
if (ui.encoderPosition) {
|
||||
const int16_t babystep_increment = (int32_t)ui.encoderPosition * (BABYSTEP_MULTIPLICATOR);
|
||||
const int16_t steps = int16_t(ui.encoderPosition) * (BABYSTEP_MULTIPLICATOR);
|
||||
ui.encoderPosition = 0;
|
||||
ui.refresh(LCDVIEW_REDRAW_NOW);
|
||||
thermalManager.babystep_axis(axis, babystep_increment);
|
||||
babysteps_done += babystep_increment;
|
||||
babystep.add_steps(axis, steps);
|
||||
}
|
||||
if (ui.should_draw())
|
||||
draw_edit_screen(msg, ftostr43sign(planner.steps_to_mm[axis] * babysteps_done));
|
||||
if (ui.should_draw()) {
|
||||
const float spm = planner.steps_to_mm[axis];
|
||||
draw_edit_screen(msg, ftostr54sign(spm * babystep.accum));
|
||||
#if ENABLED(BABYSTEP_DISPLAY_TOTAL)
|
||||
const bool in_view = (true
|
||||
#if HAS_GRAPHICAL_LCD
|
||||
&& PAGE_CONTAINS(LCD_PIXEL_HEIGHT - MENU_FONT_HEIGHT, LCD_PIXEL_HEIGHT - 1)
|
||||
#endif
|
||||
);
|
||||
if (in_view) {
|
||||
#if HAS_GRAPHICAL_LCD
|
||||
ui.set_font(FONT_MENU);
|
||||
lcd_moveto(0, LCD_PIXEL_HEIGHT - MENU_FONT_DESCENT);
|
||||
#else
|
||||
lcd_moveto(0, LCD_HEIGHT - 1);
|
||||
#endif
|
||||
lcd_put_u8str_P(PSTR(MSG_BABYSTEP_TOTAL ":"));
|
||||
lcd_put_u8str(ftostr54sign(spm * babystep.axis_total[BS_TOTAL_AXIS(axis)]));
|
||||
}
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
inline void _lcd_babystep_go(const screenFunc_t screen) {
|
||||
ui.goto_screen(screen);
|
||||
ui.defer_status_screen();
|
||||
babystep.accum = 0;
|
||||
}
|
||||
|
||||
#if ENABLED(BABYSTEP_XY)
|
||||
void _lcd_babystep_x() { _lcd_babystep(X_AXIS, PSTR(MSG_BABYSTEP_X)); }
|
||||
void _lcd_babystep_y() { _lcd_babystep(Y_AXIS, PSTR(MSG_BABYSTEP_Y)); }
|
||||
void lcd_babystep_x() { ui.goto_screen(_lcd_babystep_x); babysteps_done = 0; ui.defer_status_screen(); }
|
||||
void lcd_babystep_y() { ui.goto_screen(_lcd_babystep_y); babysteps_done = 0; ui.defer_status_screen(); }
|
||||
void lcd_babystep_x() { _lcd_babystep_go(_lcd_babystep_x); }
|
||||
void lcd_babystep_y() { _lcd_babystep_go(_lcd_babystep_y); }
|
||||
#endif
|
||||
|
||||
#if DISABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
void _lcd_babystep_z() { _lcd_babystep(Z_AXIS, PSTR(MSG_BABYSTEP_Z)); }
|
||||
void lcd_babystep_z() { ui.goto_screen(_lcd_babystep_z); babysteps_done = 0; ui.defer_status_screen(); }
|
||||
void lcd_babystep_z() { _lcd_babystep_go(_lcd_babystep_z); }
|
||||
#endif
|
||||
|
||||
#endif // BABYSTEPPING
|
||||
|
|
|
@ -471,7 +471,7 @@ void _lcd_ubl_output_map_lcd() {
|
|||
ui.encoder_direction_normal();
|
||||
|
||||
if (ui.encoderPosition) {
|
||||
step_scaler += (int32_t)ui.encoderPosition;
|
||||
step_scaler += int16_t(ui.encoderPosition);
|
||||
x_plot += step_scaler / (ENCODER_STEPS_PER_MENU_ITEM);
|
||||
ui.encoderPosition = 0;
|
||||
ui.refresh(LCDVIEW_REDRAW_NOW);
|
||||
|
|
|
@ -118,7 +118,7 @@ millis_t next_button_update_ms;
|
|||
|
||||
// Encoder Handling
|
||||
#if HAS_ENCODER_ACTION
|
||||
uint32_t MarlinUI::encoderPosition;
|
||||
uint16_t MarlinUI::encoderPosition;
|
||||
volatile int8_t encoderDiff; // Updated in update_buttons, added to encoderPosition every LCD update
|
||||
#endif
|
||||
|
||||
|
@ -192,7 +192,25 @@ millis_t next_button_update_ms;
|
|||
|
||||
#endif
|
||||
|
||||
#endif
|
||||
void wrap_string(uint8_t y, const char * const string) {
|
||||
uint8_t x = LCD_WIDTH;
|
||||
if (string) {
|
||||
uint8_t *p = (uint8_t*)string;
|
||||
for (;;) {
|
||||
if (x >= LCD_WIDTH) {
|
||||
x = 0;
|
||||
SETCURSOR(0, y++);
|
||||
}
|
||||
wchar_t ch;
|
||||
p = get_utf8_value_cb(p, read_byte_ram, &ch);
|
||||
if (!ch) break;
|
||||
lcd_put_wchar(ch);
|
||||
x++;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#endif // HAS_LCD_MENU
|
||||
|
||||
void MarlinUI::init() {
|
||||
|
||||
|
@ -462,13 +480,13 @@ void MarlinUI::status_screen() {
|
|||
#if ENABLED(ULTIPANEL_FEEDMULTIPLY)
|
||||
|
||||
const int16_t old_frm = feedrate_percentage;
|
||||
int16_t new_frm = old_frm + (int32_t)encoderPosition;
|
||||
int16_t new_frm = old_frm + int16_t(encoderPosition);
|
||||
|
||||
// Dead zone at 100% feedrate
|
||||
if (old_frm == 100) {
|
||||
if ((int32_t)encoderPosition > ENCODER_FEEDRATE_DEADZONE)
|
||||
if (int16_t(encoderPosition) > ENCODER_FEEDRATE_DEADZONE)
|
||||
new_frm -= ENCODER_FEEDRATE_DEADZONE;
|
||||
else if ((int32_t)encoderPosition < -(ENCODER_FEEDRATE_DEADZONE))
|
||||
else if (int16_t(encoderPosition) < -(ENCODER_FEEDRATE_DEADZONE))
|
||||
new_frm += ENCODER_FEEDRATE_DEADZONE;
|
||||
else
|
||||
new_frm = old_frm;
|
||||
|
@ -809,10 +827,13 @@ void MarlinUI::update() {
|
|||
#if HAS_LCD_MENU && ENABLED(SCROLL_LONG_FILENAMES)
|
||||
// If scrolling of long file names is enabled and we are in the sd card menu,
|
||||
// cause a refresh to occur until all the text has scrolled into view.
|
||||
if (currentScreen == menu_sdcard && filename_scroll_pos < filename_scroll_max && !lcd_status_update_delay--) {
|
||||
lcd_status_update_delay = 6;
|
||||
if (currentScreen == menu_sdcard && !lcd_status_update_delay--) {
|
||||
lcd_status_update_delay = 4;
|
||||
if (++filename_scroll_pos > filename_scroll_max) {
|
||||
filename_scroll_pos = 0;
|
||||
lcd_status_update_delay = 12;
|
||||
}
|
||||
refresh(LCDVIEW_REDRAW_NOW);
|
||||
filename_scroll_pos++;
|
||||
#if LCD_TIMEOUT_TO_STATUS
|
||||
return_to_status_ms = ms + LCD_TIMEOUT_TO_STATUS;
|
||||
#endif
|
||||
|
|
|
@ -56,21 +56,23 @@
|
|||
uint8_t get_ADC_keyValue();
|
||||
#endif
|
||||
|
||||
#define LCD_UPDATE_INTERVAL 100
|
||||
|
||||
#if HAS_LCD_MENU
|
||||
|
||||
#if HAS_GRAPHICAL_LCD
|
||||
#define SETCURSOR(col, row) lcd_moveto(col * (MENU_FONT_WIDTH), (row + 1) * (MENU_FONT_HEIGHT))
|
||||
#define SETCURSOR_RJ(len, row) lcd_moveto(LCD_PIXEL_WIDTH - len * (MENU_FONT_WIDTH), (row + 1) * (MENU_FONT_HEIGHT))
|
||||
#define SETCURSOR_RJ(len, row) lcd_moveto(LCD_PIXEL_WIDTH - (len) * (MENU_FONT_WIDTH), (row + 1) * (MENU_FONT_HEIGHT))
|
||||
#define LCDPRINT(p) u8g.print(p)
|
||||
#define LCDWRITE(c) u8g.print(c)
|
||||
#else
|
||||
#define SETCURSOR(col, row) lcd_moveto(col, row)
|
||||
#define SETCURSOR_RJ(len, row) lcd_moveto(LCD_WIDTH - len, row)
|
||||
#define SETCURSOR_RJ(len, row) lcd_moveto(LCD_WIDTH - (len), row)
|
||||
#define LCDPRINT(p) lcd_put_u8str(p)
|
||||
#define LCDWRITE(c) lcd_put_wchar(c)
|
||||
#endif
|
||||
|
||||
#define LCD_UPDATE_INTERVAL 100
|
||||
|
||||
#if HAS_LCD_MENU
|
||||
void wrap_string(uint8_t y, const char * const string);
|
||||
|
||||
#if ENABLED(SDSUPPORT)
|
||||
#include "../sd/cardreader.h"
|
||||
|
@ -419,7 +421,7 @@ public:
|
|||
static void synchronize(PGM_P const msg=NULL);
|
||||
|
||||
static screenFunc_t currentScreen;
|
||||
static void goto_screen(const screenFunc_t screen, const uint32_t encoder=0);
|
||||
static void goto_screen(const screenFunc_t screen, const uint16_t encoder=0, const uint8_t top=0, const uint8_t items=0);
|
||||
static void save_previous_screen();
|
||||
static void goto_previous_screen();
|
||||
static void return_to_status();
|
||||
|
@ -494,7 +496,7 @@ public:
|
|||
static void wait_for_release();
|
||||
#endif
|
||||
|
||||
static uint32_t encoderPosition;
|
||||
static uint16_t encoderPosition;
|
||||
|
||||
#if ENABLED(REVERSE_ENCODER_DIRECTION)
|
||||
#define ENCODERBASE -1
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
|
|
|
@ -63,6 +63,10 @@
|
|||
#include "../feature/fwretract.h"
|
||||
#endif
|
||||
|
||||
#if ENABLED(BABYSTEP_DISPLAY_TOTAL)
|
||||
#include "../feature/babystep.h"
|
||||
#endif
|
||||
|
||||
#define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE)
|
||||
#include "../core/debug_out.h"
|
||||
|
||||
|
@ -859,11 +863,10 @@ void clean_up_after_endstop_or_probe_move() {
|
|||
#if HAS_DUPLICATION_MODE
|
||||
bool extruder_duplication_enabled,
|
||||
mirrored_duplication_mode;
|
||||
#endif
|
||||
|
||||
#if ENABLED(MULTI_NOZZLE_DUPLICATION) && HOTENDS > 2
|
||||
#if ENABLED(MULTI_NOZZLE_DUPLICATION)
|
||||
uint8_t duplication_e_mask; // = 0
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if ENABLED(DUAL_X_CARRIAGE)
|
||||
|
||||
|
@ -1317,6 +1320,14 @@ void set_axis_is_at_home(const AxisEnum axis) {
|
|||
}
|
||||
#endif
|
||||
|
||||
#if ENABLED(I2C_POSITION_ENCODERS)
|
||||
I2CPEM.homed(axis);
|
||||
#endif
|
||||
|
||||
#if ENABLED(BABYSTEP_DISPLAY_TOTAL)
|
||||
babystep.reset_total(axis);
|
||||
#endif
|
||||
|
||||
if (DEBUGGING(LEVELING)) {
|
||||
#if HAS_HOME_OFFSET
|
||||
DEBUG_ECHOLNPAIR("> home_offset[", axis_codes[axis], "] = ", home_offset[axis]);
|
||||
|
@ -1324,10 +1335,6 @@ void set_axis_is_at_home(const AxisEnum axis) {
|
|||
DEBUG_POS("", current_position);
|
||||
DEBUG_ECHOLNPAIR("<<< set_axis_is_at_home(", axis_codes[axis], ")");
|
||||
}
|
||||
|
||||
#if ENABLED(I2C_POSITION_ENCODERS)
|
||||
I2CPEM.homed(axis);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
|
|
|
@ -318,10 +318,9 @@ void homeaxis(const AxisEnum axis);
|
|||
#if HAS_DUPLICATION_MODE
|
||||
extern bool extruder_duplication_enabled, // Used in Dual X mode 2
|
||||
mirrored_duplication_mode; // Used in Dual X mode 3
|
||||
#if ENABLED(MULTI_NOZZLE_DUPLICATION)
|
||||
extern uint8_t duplication_e_mask;
|
||||
#endif
|
||||
|
||||
#if ENABLED(MULTI_NOZZLE_DUPLICATION) && HOTENDS > 2
|
||||
uint8_t duplication_e_mask;
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
|
|
@ -618,14 +618,20 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset
|
|||
#define _REV_E_DIR(E) do{ if (E == 0) { E0_DIR_WRITE( INVERT_E0_DIR); } else { E1_DIR_WRITE( INVERT_E1_DIR); } }while(0)
|
||||
#endif
|
||||
|
||||
#if EITHER(DUAL_X_CARRIAGE, MULTI_NOZZLE_DUPLICATION)
|
||||
#if HAS_DUPLICATION_MODE
|
||||
|
||||
#if ENABLED(MULTI_NOZZLE_DUPLICATION)
|
||||
#define _DUPE(N,T,V) do{ if (TEST(duplication_e_mask, N)) E##N##_##T##_WRITE(V); }while(0)
|
||||
#else
|
||||
#define _DUPE(N,T,V) E##N##_##T##_WRITE(V)
|
||||
#endif
|
||||
|
||||
#define NDIR(N) _DUPE(N,DIR,!INVERT_E##N##_DIR)
|
||||
#define RDIR(N) _DUPE(N,DIR, INVERT_E##N##_DIR)
|
||||
|
||||
#define NDIR(N) _DUPE(DIR,!INVERT_E##N##_DIR)
|
||||
#define RDIR(N) _DUPE(DIR, INVERT_E##N##_DIR)
|
||||
#define E_STEP_WRITE(E,V) do{ if (extruder_duplication_enabled) { DUPE(STEP,V); } else _E_STEP_WRITE(E,V); }while(0)
|
||||
|
||||
#if E_STEPPERS > 2
|
||||
#define _DUPE(N,T,V) do{ if (duplication_e_mask <= (N)) E##N##_##T##_WRITE(V); }while(0)
|
||||
#if E_STEPPERS > 5
|
||||
#define DUPE(T,V) do{ _DUPE(0,T,V); _DUPE(1,T,V); _DUPE(2,T,V); _DUPE(3,T,V); _DUPE(4,T,V); _DUPE(5,T,V); }while(0)
|
||||
#define NORM_E_DIR(E) do{ if (extruder_duplication_enabled) { NDIR(0); NDIR(1); NDIR(2); NDIR(3); NDIR(4); NDIR(5); } else _NORM_E_DIR(E); }while(0)
|
||||
|
@ -644,8 +650,7 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset
|
|||
#define REV_E_DIR(E) do{ if (extruder_duplication_enabled) { RDIR(0); RDIR(1); RDIR(2); } else _REV_E_DIR(E); }while(0)
|
||||
#endif
|
||||
#else
|
||||
#define _DUPE(T,V) do{ E0_##T##_WRITE(V); E1_##T##_WRITE(V); }while(0)
|
||||
#define DUPE(T,V) _DUPE(T,V)
|
||||
#define DUPE(T,V) do{ _DUPE(0,T,V); _DUPE(1,T,V); } while(0)
|
||||
#define NORM_E_DIR(E) do{ if (extruder_duplication_enabled) { NDIR(0); NDIR(1); } else _NORM_E_DIR(E); }while(0)
|
||||
#define REV_E_DIR(E) do{ if (extruder_duplication_enabled) { RDIR(0); RDIR(1); } else _REV_E_DIR(E); }while(0)
|
||||
#endif
|
||||
|
|
|
@ -44,7 +44,7 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(BABYSTEPPING)
|
||||
#include "../module/motion.h"
|
||||
#include "../feature/babystep.h"
|
||||
#if ENABLED(BABYSTEP_ALWAYS_AVAILABLE)
|
||||
#include "../gcode/gcode.h"
|
||||
#endif
|
||||
|
@ -239,10 +239,6 @@ hotend_info_t Temperature::temp_hotend[HOTENDS]; // = { 0 }
|
|||
//hotend_pid_t Temperature::pid[HOTENDS];
|
||||
#endif
|
||||
|
||||
#if ENABLED(BABYSTEPPING)
|
||||
volatile int16_t Temperature::babystepsTodo[XYZ] = { 0 };
|
||||
#endif
|
||||
|
||||
#if ENABLED(PREVENT_COLD_EXTRUSION)
|
||||
bool Temperature::allow_cold_extrude = false;
|
||||
int16_t Temperature::extrude_min_temp = EXTRUDE_MINTEMP;
|
||||
|
@ -599,10 +595,23 @@ temp_range_t Temperature::temp_range[HOTENDS] = ARRAY_BY_HOTENDS(sensor_heater_0
|
|||
|
||||
Temperature::Temperature() { }
|
||||
|
||||
int Temperature::getHeaterPower(const int heater) {
|
||||
int16_t Temperature::getHeaterPower(const int8_t heater) {
|
||||
return (
|
||||
#if HAS_HEATED_CHAMBER
|
||||
#if HAS_HEATED_BED
|
||||
heater < 0 ? temp_bed.soft_pwm_amount :
|
||||
heater == -2
|
||||
#else
|
||||
heater < 0
|
||||
#endif
|
||||
? temp_chamber.soft_pwm_amount :
|
||||
#endif
|
||||
#if HAS_HEATED_BED
|
||||
#if HAS_HEATED_CHAMBER
|
||||
heater == -1
|
||||
#else
|
||||
heater < 0
|
||||
#endif
|
||||
? temp_bed.soft_pwm_amount :
|
||||
#endif
|
||||
temp_hotend[heater].soft_pwm_amount
|
||||
);
|
||||
|
@ -1077,11 +1086,11 @@ void Temperature::manage_heater() {
|
|||
|
||||
if (WITHIN(temp_chamber.current, CHAMBER_MINTEMP, CHAMBER_MAXTEMP)) {
|
||||
#if ENABLED(CHAMBER_LIMIT_SWITCHING)
|
||||
if (temp_chamber.current >= temp_chamber.target + CHAMBER_HYSTERESIS)
|
||||
if (temp_chamber.current >= temp_chamber.target + TEMP_CHAMBER_HYSTERESIS)
|
||||
temp_chamber.soft_pwm_amount = 0;
|
||||
else if (temp_chamber.current <= temp_chamber.target - (CHAMBER_HYSTERESIS))
|
||||
else if (temp_chamber.current <= temp_chamber.target - (TEMP_CHAMBER_HYSTERESIS))
|
||||
temp_chamber.soft_pwm_amount = MAX_CHAMBER_POWER >> 1;
|
||||
#else // !PIDTEMPCHAMBER && !CHAMBER_LIMIT_SWITCHING
|
||||
#else
|
||||
temp_chamber.soft_pwm_amount = temp_chamber.current < temp_chamber.target ? MAX_CHAMBER_POWER >> 1 : 0;
|
||||
#endif
|
||||
}
|
||||
|
@ -2021,11 +2030,7 @@ void Temperature::readings_ready() {
|
|||
#else
|
||||
#define CHAMBERCMP(A,B) ((A)>=(B))
|
||||
#endif
|
||||
const bool chamber_on = (temp_chamber.target > 0)
|
||||
#if ENABLED(PIDTEMPCHAMBER)
|
||||
|| (temp_chamber.soft_pwm_amount > 0)
|
||||
#endif
|
||||
;
|
||||
const bool chamber_on = (temp_chamber.target > 0);
|
||||
if (CHAMBERCMP(temp_chamber.raw, maxtemp_raw_CHAMBER)) max_temp_error(-2);
|
||||
if (chamber_on && CHAMBERCMP(mintemp_raw_CHAMBER, temp_chamber.raw)) min_temp_error(-2);
|
||||
#endif
|
||||
|
@ -2516,21 +2521,7 @@ void Temperature::isr() {
|
|||
//
|
||||
|
||||
#if ENABLED(BABYSTEPPING)
|
||||
#if EITHER(BABYSTEP_XY, I2C_POSITION_ENCODERS)
|
||||
LOOP_XYZ(axis) {
|
||||
const int16_t curTodo = babystepsTodo[axis]; // get rid of volatile for performance
|
||||
if (curTodo) {
|
||||
stepper.babystep((AxisEnum)axis, curTodo > 0);
|
||||
if (curTodo > 0) babystepsTodo[axis]--; else babystepsTodo[axis]++;
|
||||
}
|
||||
}
|
||||
#else
|
||||
const int16_t curTodo = babystepsTodo[Z_AXIS];
|
||||
if (curTodo) {
|
||||
stepper.babystep(Z_AXIS, curTodo > 0);
|
||||
if (curTodo > 0) babystepsTodo[Z_AXIS]--; else babystepsTodo[Z_AXIS]++;
|
||||
}
|
||||
#endif
|
||||
babystep.task();
|
||||
#endif
|
||||
|
||||
// Poll endstops state, if required
|
||||
|
@ -2540,70 +2531,6 @@ void Temperature::isr() {
|
|||
planner.tick();
|
||||
}
|
||||
|
||||
#if ENABLED(BABYSTEPPING)
|
||||
|
||||
#if ENABLED(BABYSTEP_ALWAYS_AVAILABLE)
|
||||
#define BSA_ENABLE(AXIS) do{ switch (AXIS) { case X_AXIS: enable_X(); break; case Y_AXIS: enable_Y(); break; case Z_AXIS: enable_Z(); } }while(0)
|
||||
#else
|
||||
#define BSA_ENABLE(AXIS) NOOP
|
||||
#endif
|
||||
|
||||
#if ENABLED(BABYSTEP_WITHOUT_HOMING)
|
||||
#define CAN_BABYSTEP(AXIS) true
|
||||
#else
|
||||
#define CAN_BABYSTEP(AXIS) TEST(axis_known_position, AXIS)
|
||||
#endif
|
||||
|
||||
extern uint8_t axis_known_position;
|
||||
|
||||
void Temperature::babystep_axis(const AxisEnum axis, const int16_t distance) {
|
||||
if (!CAN_BABYSTEP(axis)) return;
|
||||
#if IS_CORE
|
||||
#if ENABLED(BABYSTEP_XY)
|
||||
switch (axis) {
|
||||
case CORE_AXIS_1: // X on CoreXY and CoreXZ, Y on CoreYZ
|
||||
BSA_ENABLE(CORE_AXIS_1);
|
||||
BSA_ENABLE(CORE_AXIS_2);
|
||||
babystepsTodo[CORE_AXIS_1] += distance * 2;
|
||||
babystepsTodo[CORE_AXIS_2] += distance * 2;
|
||||
break;
|
||||
case CORE_AXIS_2: // Y on CoreXY, Z on CoreXZ and CoreYZ
|
||||
BSA_ENABLE(CORE_AXIS_1);
|
||||
BSA_ENABLE(CORE_AXIS_2);
|
||||
babystepsTodo[CORE_AXIS_1] += CORESIGN(distance * 2);
|
||||
babystepsTodo[CORE_AXIS_2] -= CORESIGN(distance * 2);
|
||||
break;
|
||||
case NORMAL_AXIS: // Z on CoreXY, Y on CoreXZ, X on CoreYZ
|
||||
default:
|
||||
BSA_ENABLE(NORMAL_AXIS);
|
||||
babystepsTodo[NORMAL_AXIS] += distance;
|
||||
break;
|
||||
}
|
||||
#elif CORE_IS_XZ || CORE_IS_YZ
|
||||
// Only Z stepping needs to be handled here
|
||||
BSA_ENABLE(CORE_AXIS_1);
|
||||
BSA_ENABLE(CORE_AXIS_2);
|
||||
babystepsTodo[CORE_AXIS_1] += CORESIGN(distance * 2);
|
||||
babystepsTodo[CORE_AXIS_2] -= CORESIGN(distance * 2);
|
||||
#else
|
||||
BSA_ENABLE(Z_AXIS);
|
||||
babystepsTodo[Z_AXIS] += distance;
|
||||
#endif
|
||||
#else
|
||||
#if ENABLED(BABYSTEP_XY)
|
||||
BSA_ENABLE(axis);
|
||||
#else
|
||||
BSA_ENABLE(Z_AXIS);
|
||||
#endif
|
||||
babystepsTodo[axis] += distance;
|
||||
#endif
|
||||
#if ENABLED(BABYSTEP_ALWAYS_AVAILABLE)
|
||||
gcode.reset_stepper_timeout();
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif // BABYSTEPPING
|
||||
|
||||
#if HAS_TEMP_SENSOR
|
||||
|
||||
#include "../gcode/gcode.h"
|
||||
|
@ -2684,11 +2611,12 @@ void Temperature::isr() {
|
|||
, e
|
||||
);
|
||||
#endif
|
||||
SERIAL_ECHOPGM(" @:");
|
||||
SERIAL_ECHO(getHeaterPower(target_extruder));
|
||||
SERIAL_ECHOPAIR(" @:", getHeaterPower(target_extruder));
|
||||
#if HAS_HEATED_BED
|
||||
SERIAL_ECHOPGM(" B@:");
|
||||
SERIAL_ECHO(getHeaterPower(-1));
|
||||
SERIAL_ECHOPAIR(" B@:", getHeaterPower(-1));
|
||||
#endif
|
||||
#if HAS_HEATED_CHAMBER
|
||||
SERIAL_ECHOPAIR(" C@:", getHeaterPower(-2));
|
||||
#endif
|
||||
#if HOTENDS > 1
|
||||
HOTEND_LOOP() {
|
||||
|
|
|
@ -206,17 +206,11 @@ struct PIDHeaterInfo : public HeaterInfo {
|
|||
typedef heater_info_t bed_info_t;
|
||||
#endif
|
||||
#endif
|
||||
#if HAS_TEMP_CHAMBER
|
||||
#if HAS_HEATED_CHAMBER
|
||||
#if ENABLED(PIDTEMPCHAMBER)
|
||||
typedef struct PIDHeaterInfo<PID_t> chamber_info_t;
|
||||
#else
|
||||
typedef heater_info_t chamber_info_t;
|
||||
#endif
|
||||
#else
|
||||
#elif HAS_TEMP_CHAMBER
|
||||
typedef temp_info_t chamber_info_t;
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// Heater idle handling
|
||||
typedef struct {
|
||||
|
@ -266,10 +260,6 @@ class Temperature {
|
|||
soft_pwm_count_fan[FAN_COUNT];
|
||||
#endif
|
||||
|
||||
#if ENABLED(BABYSTEPPING)
|
||||
static volatile int16_t babystepsTodo[3];
|
||||
#endif
|
||||
|
||||
#if ENABLED(PREVENT_COLD_EXTRUSION)
|
||||
static bool allow_cold_extrude;
|
||||
static int16_t extrude_min_temp;
|
||||
|
@ -343,9 +333,7 @@ class Temperature {
|
|||
#if WATCH_CHAMBER
|
||||
static heater_watch_t watch_chamber;
|
||||
#endif
|
||||
#if DISABLED(PIDTEMPCHAMBER)
|
||||
static millis_t next_chamber_check_ms;
|
||||
#endif
|
||||
#ifdef CHAMBER_MINTEMP
|
||||
static int16_t mintemp_raw_CHAMBER;
|
||||
#endif
|
||||
|
@ -572,7 +560,7 @@ class Temperature {
|
|||
#if HAS_HEATED_CHAMBER
|
||||
temp_chamber.target =
|
||||
#ifdef CHAMBER_MAXTEMP
|
||||
min(celsius, CHAMBER_MAXTEMP)
|
||||
MIN(celsius, CHAMBER_MAXTEMP)
|
||||
#else
|
||||
celsius
|
||||
#endif
|
||||
|
@ -657,7 +645,7 @@ class Temperature {
|
|||
/**
|
||||
* The software PWM power for a heater
|
||||
*/
|
||||
static int getHeaterPower(const int heater);
|
||||
static int16_t getHeaterPower(const int8_t heater);
|
||||
|
||||
/**
|
||||
* Switch off all heaters, set all target temperatures to 0
|
||||
|
@ -673,7 +661,7 @@ class Temperature {
|
|||
#if ENABLED(NO_FAN_SLOWING_IN_PID_TUNING)
|
||||
static bool adaptive_fan_slowing;
|
||||
#elif ENABLED(ADAPTIVE_FAN_SLOWING)
|
||||
constexpr static bool adaptive_fan_slowing = true;
|
||||
static constexpr bool adaptive_fan_slowing = true;
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -689,10 +677,6 @@ class Temperature {
|
|||
|
||||
#endif
|
||||
|
||||
#if ENABLED(BABYSTEPPING)
|
||||
static void babystep_axis(const AxisEnum axis, const int16_t distance);
|
||||
#endif
|
||||
|
||||
#if ENABLED(PROBING_HEATERS_OFF)
|
||||
static void pause(const bool p);
|
||||
FORCE_INLINE static bool is_paused() { return paused; }
|
||||
|
|
|
@ -121,7 +121,7 @@
|
|||
|
||||
void move_nozzle_servo(const uint8_t angle_index) {
|
||||
planner.synchronize();
|
||||
MOVE_SERVO(SWITCHING_NOZZLE_SERVO_NR, servo_angles[SWITCHING_NOZZLE_SERVO_NR][e]);
|
||||
MOVE_SERVO(SWITCHING_NOZZLE_SERVO_NR, servo_angles[SWITCHING_NOZZLE_SERVO_NR][angle_index]);
|
||||
safe_delay(500);
|
||||
}
|
||||
|
||||
|
@ -369,12 +369,6 @@ inline void fast_line_to_current(const AxisEnum fr_axis) {
|
|||
pe_activate_solenoid(active_extruder); // Just save power for inverted magnets
|
||||
#endif
|
||||
}
|
||||
|
||||
#if HAS_HOTEND_OFFSET
|
||||
current_position[Z_AXIS] += hotend_offset[Z_AXIS][active_extruder] - hotend_offset[Z_AXIS][tmp_extruder];
|
||||
#endif
|
||||
|
||||
if (DEBUGGING(LEVELING)) DEBUG_POS("Applying Z-offset", current_position);
|
||||
}
|
||||
|
||||
#endif // PARKING_EXTRUDER
|
||||
|
@ -493,6 +487,133 @@ inline void fast_line_to_current(const AxisEnum fr_axis) {
|
|||
|
||||
#endif // SWITCHING_TOOLHEAD
|
||||
|
||||
#if ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
|
||||
inline void magnetic_switching_toolhead_tool_change(const uint8_t tmp_extruder, const float fr_mm_s/*=0.0*/, bool no_move/*=false*/) {
|
||||
if (no_move) return;
|
||||
|
||||
const float toolheadposx[] = SWITCHING_TOOLHEAD_X_POS,
|
||||
placexpos = toolheadposx[active_extruder],
|
||||
grabxpos = toolheadposx[tmp_extruder];
|
||||
|
||||
/**
|
||||
* 1. Raise Z to give enough clearance
|
||||
* 2. Move to switch position of current toolhead
|
||||
* 3. Release and place toolhead in the dock
|
||||
* 4. Move to the new toolhead
|
||||
* 5. Grab the new toolhead and move to security position
|
||||
*/
|
||||
|
||||
if (DEBUGGING(LEVELING)) DEBUG_POS("Starting Toolhead change", current_position);
|
||||
|
||||
// 1. Raise Z to give enough clearance
|
||||
|
||||
current_position[Z_AXIS] += toolchange_settings.z_raise;
|
||||
|
||||
if (DEBUGGING(LEVELING)) DEBUG_POS("(1) Raise Z-Axis", current_position);
|
||||
|
||||
planner.buffer_line(current_position, planner.settings.max_feedrate_mm_s[Z_AXIS], active_extruder);
|
||||
planner.synchronize();
|
||||
|
||||
// 2. Move to switch position current toolhead
|
||||
|
||||
current_position[Y_AXIS] = SWITCHING_TOOLHEAD_Y_POS + SWITCHING_TOOLHEAD_Y_CLEAR;
|
||||
|
||||
if (DEBUGGING(LEVELING)) {
|
||||
SERIAL_ECHOLNPAIR("(2) Place old tool ", int(active_extruder));
|
||||
DEBUG_POS("Move Y SwitchPos + Security", current_position);
|
||||
}
|
||||
|
||||
planner.buffer_line(current_position, planner.settings.max_feedrate_mm_s[Y_AXIS], active_extruder);
|
||||
planner.synchronize();
|
||||
|
||||
current_position[X_AXIS] = placexpos + SWITCHING_TOOLHEAD_X_SECURITY;
|
||||
|
||||
if (DEBUGGING(LEVELING)) DEBUG_POS("Move X SwitchPos + Security", current_position);
|
||||
|
||||
planner.buffer_line(current_position, planner.settings.max_feedrate_mm_s[X_AXIS], active_extruder);
|
||||
planner.synchronize();
|
||||
|
||||
current_position[Y_AXIS] = SWITCHING_TOOLHEAD_Y_POS;
|
||||
|
||||
if (DEBUGGING(LEVELING)) DEBUG_POS("Move Y SwitchPos", current_position);
|
||||
|
||||
planner.buffer_line(current_position, planner.settings.max_feedrate_mm_s[Y_AXIS], active_extruder);
|
||||
planner.synchronize();
|
||||
|
||||
current_position[X_AXIS] = placexpos;
|
||||
|
||||
if (DEBUGGING(LEVELING)) DEBUG_POS("Move X SwitchPos", current_position);
|
||||
|
||||
planner.buffer_line(current_position, (planner.settings.max_feedrate_mm_s[X_AXIS] * 0.25), active_extruder);
|
||||
planner.synchronize();
|
||||
|
||||
// 3. Release and place toolhead in the dock
|
||||
|
||||
if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("(3) Release and Place Toolhead");
|
||||
|
||||
current_position[Y_AXIS] = SWITCHING_TOOLHEAD_Y_POS + SWITCHING_TOOLHEAD_Y_RELEASE;
|
||||
|
||||
if (DEBUGGING(LEVELING)) DEBUG_POS("Move Y SwitchPos + Release", current_position);
|
||||
|
||||
planner.buffer_line(current_position, (planner.settings.max_feedrate_mm_s[Y_AXIS] * 0.1), active_extruder);
|
||||
planner.synchronize();
|
||||
|
||||
current_position[Y_AXIS] = SWITCHING_TOOLHEAD_Y_POS + SWITCHING_TOOLHEAD_Y_SECURITY;
|
||||
|
||||
if (DEBUGGING(LEVELING)) DEBUG_POS("Move Y SwitchPos + Security", current_position);
|
||||
|
||||
planner.buffer_line(current_position, (planner.settings.max_feedrate_mm_s[Y_AXIS]), active_extruder);
|
||||
planner.synchronize();
|
||||
|
||||
// 4. Move to new toolhead position
|
||||
|
||||
if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("(4) Move to new toolhead position");
|
||||
|
||||
current_position[X_AXIS] = grabxpos;
|
||||
|
||||
if (DEBUGGING(LEVELING)) DEBUG_POS("Move to new toolhead X", current_position);
|
||||
|
||||
planner.buffer_line(current_position, planner.settings.max_feedrate_mm_s[X_AXIS], active_extruder);
|
||||
planner.synchronize();
|
||||
|
||||
// 5. Grab the new toolhead and move to security position
|
||||
|
||||
if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("(5) Grab new toolhead and move to security position");
|
||||
|
||||
current_position[Y_AXIS] = SWITCHING_TOOLHEAD_Y_POS + SWITCHING_TOOLHEAD_Y_RELEASE;
|
||||
|
||||
if (DEBUGGING(LEVELING)) DEBUG_POS("Move Y SwitchPos + Release", current_position);
|
||||
|
||||
planner.buffer_line(current_position, (planner.settings.max_feedrate_mm_s[Y_AXIS]), active_extruder);
|
||||
planner.synchronize();
|
||||
|
||||
current_position[Y_AXIS] = SWITCHING_TOOLHEAD_Y_POS;
|
||||
|
||||
if (DEBUGGING(LEVELING)) DEBUG_POS("Move Y SwitchPos", current_position);
|
||||
|
||||
planner.buffer_line(current_position, planner.settings.max_feedrate_mm_s[Y_AXIS] * 0.2, active_extruder);
|
||||
planner.synchronize();
|
||||
safe_delay(100);
|
||||
|
||||
current_position[X_AXIS] = grabxpos + SWITCHING_TOOLHEAD_X_SECURITY;
|
||||
|
||||
if (DEBUGGING(LEVELING)) DEBUG_POS("Move to new toolhead X + Security", current_position);
|
||||
|
||||
planner.buffer_line(current_position, planner.settings.max_feedrate_mm_s[X_AXIS] * 0.1, active_extruder);
|
||||
planner.synchronize();
|
||||
safe_delay(100);
|
||||
|
||||
current_position[Y_AXIS] += SWITCHING_TOOLHEAD_Y_CLEAR;
|
||||
|
||||
if (DEBUGGING(LEVELING)) DEBUG_POS("Move back Y clear", current_position);
|
||||
|
||||
planner.buffer_line(current_position, planner.settings.max_feedrate_mm_s[Y_AXIS], active_extruder); // move away from docked toolhead
|
||||
planner.synchronize();
|
||||
}
|
||||
|
||||
#endif // MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
inline void invalid_extruder_error(const uint8_t e) {
|
||||
SERIAL_ECHO_START();
|
||||
SERIAL_CHAR('T'); SERIAL_ECHO(int(e));
|
||||
|
@ -525,10 +646,6 @@ inline void invalid_extruder_error(const uint8_t e) {
|
|||
planner.synchronize();
|
||||
}
|
||||
|
||||
// Apply Y & Z extruder offset (X offset is used as home pos with Dual X)
|
||||
current_position[Y_AXIS] -= hotend_offset[Y_AXIS][active_extruder] - hotend_offset[Y_AXIS][tmp_extruder];
|
||||
current_position[Z_AXIS] -= hotend_offset[Z_AXIS][active_extruder] - hotend_offset[Z_AXIS][tmp_extruder];
|
||||
|
||||
// Activate the new extruder ahead of calling set_axis_is_at_home!
|
||||
active_extruder = tmp_extruder;
|
||||
|
||||
|
@ -567,6 +684,11 @@ inline void invalid_extruder_error(const uint8_t e) {
|
|||
* previous tool out of the way and the new tool into place.
|
||||
*/
|
||||
void tool_change(const uint8_t tmp_extruder, const float fr_mm_s/*=0.0*/, bool no_move/*=false*/) {
|
||||
|
||||
#if ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
if (tmp_extruder == active_extruder) return;
|
||||
#endif
|
||||
|
||||
#if ENABLED(MIXING_EXTRUDER)
|
||||
|
||||
UNUSED(fr_mm_s); UNUSED(no_move);
|
||||
|
@ -583,7 +705,7 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_s/*=0.0*/, bool n
|
|||
|
||||
UNUSED(fr_mm_s); UNUSED(no_move);
|
||||
|
||||
mmu2.toolChange(tmp_extruder);
|
||||
mmu2.tool_change(tmp_extruder);
|
||||
|
||||
#elif EXTRUDERS < 2
|
||||
|
||||
|
@ -696,6 +818,8 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_s/*=0.0*/, bool n
|
|||
magnetic_parking_extruder_tool_change(tmp_extruder);
|
||||
#elif ENABLED(SWITCHING_TOOLHEAD) // Switching Toolhead
|
||||
switching_toolhead_tool_change(tmp_extruder, fr_mm_s, no_move);
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD) // Magnetic Switching Toolhead
|
||||
magnetic_switching_toolhead_tool_change(tmp_extruder, fr_mm_s, no_move);
|
||||
#elif ENABLED(SWITCHING_NOZZLE) && !SWITCHING_NOZZLE_TWO_SERVOS
|
||||
// Raise by a configured distance to avoid workpiece, except with
|
||||
// SWITCHING_NOZZLE_TWO_SERVOS, as both nozzles will lift instead.
|
||||
|
@ -765,7 +889,16 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_s/*=0.0*/, bool n
|
|||
#endif
|
||||
|
||||
// Prevent a move outside physical bounds
|
||||
#if ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
// If the original position is within tool store area, go to X origin at once
|
||||
if (destination[Y_AXIS] < SWITCHING_TOOLHEAD_Y_POS + SWITCHING_TOOLHEAD_Y_CLEAR) {
|
||||
current_position[X_AXIS] = 0;
|
||||
planner.buffer_line(current_position, planner.settings.max_feedrate_mm_s[X_AXIS], active_extruder);
|
||||
planner.synchronize();
|
||||
}
|
||||
#else
|
||||
apply_motion_limits(destination);
|
||||
#endif
|
||||
|
||||
// Move back to the original (or tweaked) position
|
||||
do_blocking_move_to(destination);
|
||||
|
@ -783,27 +916,13 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_s/*=0.0*/, bool n
|
|||
#endif
|
||||
|
||||
#if ENABLED(PRUSA_MMU2)
|
||||
mmu2.toolChange(tmp_extruder);
|
||||
mmu2.tool_change(tmp_extruder);
|
||||
#endif
|
||||
|
||||
#if SWITCHING_NOZZLE_TWO_SERVOS
|
||||
lower_nozzle(active_extruder);
|
||||
#endif
|
||||
|
||||
#if ENABLED(TOOLCHANGE_FILAMENT_SWAP) && ADVANCED_PAUSE_RESUME_PRIME != 0
|
||||
if (should_swap && !too_cold) {
|
||||
const float resume_eaxis = current_position[E_AXIS];
|
||||
#if ENABLED(ADVANCED_PAUSE_FEATURE)
|
||||
do_pause_e_move(toolchange_settings.swap_length, toolchange_settings.prime_speed);
|
||||
#else
|
||||
current_position[E_AXIS] += (ADVANCED_PAUSE_RESUME_PRIME) / planner.e_factor[active_extruder];
|
||||
planner.buffer_line(current_position, ADVANCED_PAUSE_PURGE_FEEDRATE, active_extruder);
|
||||
#endif
|
||||
planner.synchronize();
|
||||
planner.set_e_position_mm((destination[E_AXIS] = current_position[E_AXIS] = resume_eaxis));
|
||||
}
|
||||
#endif
|
||||
|
||||
} // (tmp_extruder != active_extruder)
|
||||
|
||||
planner.synchronize();
|
||||
|
|
|
@ -320,6 +320,8 @@
|
|||
#include "pins_AZSMZ_MINI.h" // LPC1768 env:LPC1768
|
||||
#elif MB(AZTEEG_X5_GT)
|
||||
#include "pins_AZTEEG_X5_GT.h" // LPC1769 env:LPC1769
|
||||
#elif MB(AZTEEG_X5_MINI)
|
||||
#include "pins_AZTEEG_X5_MINI.h" // LPC1769 env:LPC1769
|
||||
#elif MB(AZTEEG_X5_MINI_WIFI)
|
||||
#include "pins_AZTEEG_X5_MINI_WIFI.h" // LPC1769 env:LPC1769
|
||||
#elif MB(BIQU_BQ111_A4)
|
||||
|
@ -417,7 +419,7 @@
|
|||
#elif MB(MORPHEUS)
|
||||
#include "pins_MORPHEUS.h" // STM32F1 env:STM32F1
|
||||
#elif MB(MKS_ROBIN)
|
||||
#include "pins_MKS_ROBIN.h" // STM32F1 env:STM32F1
|
||||
#include "pins_MKS_ROBIN.h" // STM32F1 env:mks_robin
|
||||
|
||||
//
|
||||
// STM32 ARM Cortex-M4F
|
||||
|
@ -435,9 +437,13 @@
|
|||
#include "pins_ARMED.h" // STM32F4 env:ARMED
|
||||
#elif MB(RUMBA32)
|
||||
#include "pins_RUMBA32.h" // STM32F4 env:RUMBA32
|
||||
#elif MB(BLACK_STM32F407VE)
|
||||
#include "pins_BLACK_STM32F407VE.h" // STM32F4 env:black_stm32f407ve
|
||||
#elif MB(STEVAL)
|
||||
#include "pins_STEVAL.h" // STM32F4 env:STM32F4
|
||||
|
||||
|
||||
|
||||
//
|
||||
// ARM Cortex M7
|
||||
//
|
||||
|
|
|
@ -102,6 +102,9 @@ const PinInfo pin_array[] PROGMEM = {
|
|||
|
||||
#include HAL_PATH(../HAL, pinsDebug.h) // get the correct support file for this CPU
|
||||
|
||||
#ifndef M43_NEVER_TOUCH
|
||||
#define M43_NEVER_TOUCH(Q) false
|
||||
#endif
|
||||
|
||||
static void print_input_or_output(const bool isout) {
|
||||
serialprintPGM(isout ? PSTR("Output = ") : PSTR("Input = "));
|
||||
|
|
|
@ -788,8 +788,8 @@
|
|||
#if PIN_EXISTS(SPINDLE_ENABLE)
|
||||
REPORT_NAME_DIGITAL(__LINE__, SPINDLE_ENABLE_PIN)
|
||||
#endif
|
||||
#if PIN_EXISTS(SPINDLE_LASER_ENABLE)
|
||||
REPORT_NAME_DIGITAL(__LINE__, SPINDLE_LASER_ENABLE_PIN)
|
||||
#if PIN_EXISTS(SPINDLE_LASER_ENA)
|
||||
REPORT_NAME_DIGITAL(__LINE__, SPINDLE_LASER_ENA_PIN)
|
||||
#endif
|
||||
#if PIN_EXISTS(SPINDLE_LASER_PWM)
|
||||
REPORT_NAME_DIGITAL(__LINE__, SPINDLE_LASER_PWM_PIN)
|
||||
|
|
|
@ -124,7 +124,7 @@
|
|||
*
|
||||
* stepper signal socket name socket name
|
||||
* -------
|
||||
* SPINDLE_LASER_ENABLE_PIN /ENABLE O| |O VMOT
|
||||
* SPINDLE_LASER_ENA_PIN /ENABLE O| |O VMOT
|
||||
* MS1 O| |O GND
|
||||
* MS2 O| |O 2B
|
||||
* MS3 O| |O 2A
|
||||
|
@ -137,7 +137,7 @@
|
|||
* Note: Socket names vary from vendor to vendor
|
||||
*/
|
||||
#undef SPINDLE_LASER_PWM_PIN // Definitions in pins_RAMPS.h are not good with 3DRAG
|
||||
#undef SPINDLE_LASER_ENABLE_PIN
|
||||
#undef SPINDLE_LASER_ENA_PIN
|
||||
#undef SPINDLE_DIR_PIN
|
||||
|
||||
#if ENABLED(SPINDLE_LASER_ENABLE)
|
||||
|
@ -152,10 +152,10 @@
|
|||
#define Z_ENABLE_PIN 24
|
||||
#define Z_STEP_PIN 26
|
||||
#define SPINDLE_LASER_PWM_PIN 46 // MUST BE HARDWARE PWM
|
||||
#define SPINDLE_LASER_ENABLE_PIN 62 // Pin should have a pullup!
|
||||
#define SPINDLE_LASER_ENA_PIN 62 // Pin should have a pullup!
|
||||
#define SPINDLE_DIR_PIN 48
|
||||
#elif !BOTH(ULTRA_LCD, NEWPANEL) // use expansion header if no LCD in use
|
||||
#define SPINDLE_LASER_ENABLE_PIN 16 // Pin should have a pullup/pulldown!
|
||||
#define SPINDLE_LASER_ENA_PIN 16 // Pin should have a pullup/pulldown!
|
||||
#define SPINDLE_DIR_PIN 17
|
||||
#endif
|
||||
#endif
|
||||
|
|
|
@ -142,4 +142,6 @@
|
|||
#define SDSS 20 // B0
|
||||
|
||||
//DIGIPOTS slave addresses
|
||||
#ifndef DIGIPOT_I2C_ADDRESS_A
|
||||
#define DIGIPOT_I2C_ADDRESS_A 0x2C // unshifted slave address for DIGIPOT 0x2C (0x58 <- 0x2C << 1)
|
||||
#endif
|
||||
|
|
|
@ -83,7 +83,7 @@
|
|||
// M3/M4/M5 - Spindle/Laser Control
|
||||
//
|
||||
#undef SPINDLE_LASER_PWM_PIN // Definitions in pins_RAMPS.h are no good with the AzteegX3 board
|
||||
#undef SPINDLE_LASER_ENABLE_PIN
|
||||
#undef SPINDLE_LASER_ENA_PIN
|
||||
#undef SPINDLE_DIR_PIN
|
||||
|
||||
#if ENABLED(SPINDLE_LASER_ENABLE)
|
||||
|
@ -94,6 +94,6 @@
|
|||
#define SERVO0_PIN 11
|
||||
#endif
|
||||
#define SPINDLE_LASER_PWM_PIN 7 // MUST BE HARDWARE PWM
|
||||
#define SPINDLE_LASER_ENABLE_PIN 20 // Pin should have a pullup!
|
||||
#define SPINDLE_LASER_ENA_PIN 20 // Pin should have a pullup!
|
||||
#define SPINDLE_DIR_PIN 21
|
||||
#endif
|
||||
|
|
|
@ -48,8 +48,12 @@
|
|||
#include "pins_RAMPS.h"
|
||||
|
||||
// DIGIPOT slave addresses
|
||||
#ifndef DIGIPOT_I2C_ADDRESS_A
|
||||
#define DIGIPOT_I2C_ADDRESS_A 0x2C // unshifted slave address for first DIGIPOT 0x2C (0x58 <- 0x2C << 1)
|
||||
#endif
|
||||
#ifndef DIGIPOT_I2C_ADDRESS_B
|
||||
#define DIGIPOT_I2C_ADDRESS_B 0x2E // unshifted slave address for second DIGIPOT 0x2E (0x5C <- 0x2E << 1)
|
||||
#endif
|
||||
|
||||
//
|
||||
// Servos
|
||||
|
@ -162,7 +166,7 @@
|
|||
// M3/M4/M5 - Spindle/Laser Control
|
||||
//
|
||||
#undef SPINDLE_LASER_PWM_PIN // Definitions in pins_RAMPS.h are no good with the AzteegX3pro board
|
||||
#undef SPINDLE_LASER_ENABLE_PIN
|
||||
#undef SPINDLE_LASER_ENA_PIN
|
||||
#undef SPINDLE_DIR_PIN
|
||||
|
||||
#if ENABLED(SPINDLE_LASER_ENABLE) // EXP2 header
|
||||
|
@ -171,6 +175,6 @@
|
|||
#define BTN_EN2 31 // need 7 for the spindle speed PWM
|
||||
#endif
|
||||
#define SPINDLE_LASER_PWM_PIN 7 // must have a hardware PWM
|
||||
#define SPINDLE_LASER_ENABLE_PIN 20 // Pin should have a pullup!
|
||||
#define SPINDLE_LASER_ENA_PIN 20 // Pin should have a pullup!
|
||||
#define SPINDLE_DIR_PIN 21
|
||||
#endif
|
||||
|
|
218
Marlin/src/pins/pins_AZTEEG_X5_MINI.h
Normal file
218
Marlin/src/pins/pins_AZTEEG_X5_MINI.h
Normal file
|
@ -0,0 +1,218 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2019 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/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* Azteeg X5 MINI pin assignments
|
||||
*/
|
||||
|
||||
#ifndef LPC1769
|
||||
#error "Oops! Make sure you have the LPC1769 environment selected in your IDE."
|
||||
#endif
|
||||
|
||||
#ifndef BOARD_NAME
|
||||
#define BOARD_NAME "Azteeg X5 MINI"
|
||||
#endif
|
||||
#define BOARD_WEBSITE_URL "http://www.panucatt.com/azteeg_X5_mini_reprap_3d_printer_controller_p/ax5mini.htm"
|
||||
|
||||
//
|
||||
// LED
|
||||
//
|
||||
#define LED_PIN P1_18
|
||||
|
||||
//
|
||||
// Servos
|
||||
//
|
||||
#define SERVO0_PIN P1_29
|
||||
|
||||
//
|
||||
// Limit Switches
|
||||
//
|
||||
#define X_STOP_PIN P1_24
|
||||
#define Y_STOP_PIN P1_26
|
||||
#define Z_STOP_PIN P1_28
|
||||
|
||||
#ifndef FILWIDTH_PIN
|
||||
#define FILWIDTH_PIN P2_04
|
||||
#endif
|
||||
|
||||
//
|
||||
// Steppers
|
||||
//
|
||||
#define X_STEP_PIN P2_01
|
||||
#define X_DIR_PIN P0_11
|
||||
#define X_ENABLE_PIN P0_10
|
||||
|
||||
#define Y_STEP_PIN P2_02
|
||||
#define Y_DIR_PIN P0_20
|
||||
#define Y_ENABLE_PIN P0_19
|
||||
|
||||
#define Z_STEP_PIN P2_03
|
||||
#define Z_DIR_PIN P0_22
|
||||
#define Z_ENABLE_PIN P0_21
|
||||
|
||||
#define E0_STEP_PIN P2_00
|
||||
#define E0_DIR_PIN P0_05
|
||||
#define E0_ENABLE_PIN P0_04
|
||||
|
||||
//
|
||||
// DIGIPOT slave addresses
|
||||
//
|
||||
#ifndef DIGIPOT_I2C_ADDRESS_A
|
||||
#define DIGIPOT_I2C_ADDRESS_A 0x2C // unshifted slave address for first DIGIPOT
|
||||
#endif
|
||||
|
||||
#ifndef DIGIPOT_I2C_ADDRESS_B
|
||||
#define DIGIPOT_I2C_ADDRESS_B 0x2E // unshifted slave address for second DIGIPOT
|
||||
#endif
|
||||
|
||||
//
|
||||
// Temperature Sensors
|
||||
// 3.3V max when defined as an analog input
|
||||
//
|
||||
#define TEMP_BED_PIN 0 // A0 (TH1)
|
||||
#define TEMP_0_PIN 1 // A1 (TH2)
|
||||
|
||||
//
|
||||
// Heaters / Fans
|
||||
//
|
||||
#define HEATER_BED_PIN P2_07
|
||||
#define HEATER_0_PIN P2_05
|
||||
#ifndef FAN_PIN
|
||||
#define FAN_PIN P0_26
|
||||
#endif
|
||||
#define FAN1_PIN P1_25
|
||||
|
||||
//
|
||||
// Display
|
||||
//
|
||||
#if ENABLED(ULTRA_LCD)
|
||||
|
||||
#if ENABLED(CR10_STOCKDISPLAY)
|
||||
|
||||
// Re-Arm can support Creality stock display without SD card reader and single cable on EXP3.
|
||||
// Re-Arm J3 pins 1 (p1.31) & 2 (P3.26) are not used. Stock cable will need to have one
|
||||
// 10-pin IDC connector trimmed or replaced with a 12-pin IDC connector to fit J3.
|
||||
// Requires REVERSE_ENCODER_DIRECTION in Configuration.h
|
||||
|
||||
#define BEEPER_PIN P2_11 // J3-3 & AUX-4
|
||||
|
||||
#define BTN_EN1 P0_16 // J3-7 & AUX-4
|
||||
#define BTN_EN2 P1_23 // J3-5 & AUX-4
|
||||
#define BTN_ENC P3_25 // J3-4 & AUX-4
|
||||
|
||||
#define LCD_PINS_RS P0_15 // J3-9 & AUX-4 (CS)
|
||||
#define LCD_PINS_ENABLE P0_18 // J3-10 & AUX-3 (SID, MOSI)
|
||||
#define LCD_PINS_D4 P2_06 // J3-8 & AUX-3 (SCK, CLK)
|
||||
|
||||
#else
|
||||
|
||||
#define BTN_EN1 P3_26 // (31) J3-2 & AUX-4
|
||||
#define BTN_EN2 P3_25 // (33) J3-4 & AUX-4
|
||||
#define BTN_ENC P2_11 // (35) J3-3 & AUX-4
|
||||
|
||||
#define SD_DETECT_PIN P1_31 // (49) not 5V tolerant J3-1 & AUX-3
|
||||
#define KILL_PIN P1_22 // (41) J5-4 & AUX-4
|
||||
#define LCD_PINS_RS P0_16 // (16) J3-7 & AUX-4
|
||||
#define LCD_SDSS P0_16 // (16) J3-7 & AUX-4
|
||||
#define LCD_BACKLIGHT_PIN P0_16 // (16) J3-7 & AUX-4 - only used on DOGLCD controllers
|
||||
#define LCD_PINS_ENABLE P0_18 // (51) (MOSI) J3-10 & AUX-3
|
||||
#define LCD_PINS_D4 P0_15 // (52) (SCK) J3-9 & AUX-3
|
||||
|
||||
#define DOGLCD_A0 P2_06 // (59) J3-8 & AUX-2
|
||||
|
||||
#if ENABLED(REPRAPWORLD_KEYPAD)
|
||||
#define SHIFT_OUT P0_18 // (51) (MOSI) J3-10 & AUX-3
|
||||
#define SHIFT_CLK P0_15 // (52) (SCK) J3-9 & AUX-3
|
||||
#define SHIFT_LD P1_31 // (49) not 5V tolerant J3-1 & AUX-3
|
||||
#elif DISABLED(NEWPANEL)
|
||||
//#define SHIFT_OUT P2_11 // (35) J3-3 & AUX-4
|
||||
//#define SHIFT_CLK P3_26 // (31) J3-2 & AUX-4
|
||||
//#define SHIFT_LD P3_25 // (33) J3-4 & AUX-4
|
||||
//#define SHIFT_EN P1_22 // (41) J5-4 & AUX-4
|
||||
#endif
|
||||
|
||||
#if ANY(VIKI2, miniVIKI)
|
||||
//#define LCD_SCREEN_ROT_180
|
||||
|
||||
#define BEEPER_PIN P1_30 // (37) may change if cable changes
|
||||
#define DOGLCD_CS P0_26 // (63) J5-3 & AUX-2
|
||||
#define DOGLCD_SCK SCK_PIN
|
||||
#define DOGLCD_MOSI MOSI_PIN
|
||||
|
||||
#define STAT_LED_BLUE_PIN P0_26 // (63) may change if cable changes
|
||||
#define STAT_LED_RED_PIN P1_21 // ( 6) may change if cable changes
|
||||
#else
|
||||
#if ENABLED(ULTIPANEL)
|
||||
#define LCD_PINS_D5 P1_17 // (71) ENET_MDIO
|
||||
#define LCD_PINS_D6 P1_14 // (73) ENET_RX_ER
|
||||
#define LCD_PINS_D7 P1_10 // (75) ENET_RXD1
|
||||
#endif
|
||||
#define BEEPER_PIN P1_30 // (37) not 5V tolerant
|
||||
#define DOGLCD_CS P0_16 // (16)
|
||||
#endif
|
||||
|
||||
#if ENABLED(MINIPANEL)
|
||||
// GLCD features
|
||||
// Uncomment screen orientation
|
||||
//#define LCD_SCREEN_ROT_90
|
||||
//#define LCD_SCREEN_ROT_180
|
||||
//#define LCD_SCREEN_ROT_270
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
#endif // ULTRA_LCD
|
||||
|
||||
//
|
||||
// SD Support
|
||||
//
|
||||
//#define USB_SD_DISABLED // Disable host access to SD card as mass storage device through USB
|
||||
//#define USB_SD_ONBOARD // Enable host access to SD card as mass storage device through USB
|
||||
|
||||
//#define LPC_SD_LCD // Marlin uses the SD drive attached to the LCD
|
||||
#define LPC_SD_ONBOARD // Marlin uses the SD drive on the control board. There is no SD detect pin
|
||||
// for the onboard card. Init card from LCD menu or send M21 whenever printer
|
||||
// is powered on to enable SD access.
|
||||
|
||||
#if ENABLED(LPC_SD_LCD)
|
||||
|
||||
#define SCK_PIN P0_15
|
||||
#define MISO_PIN P0_17
|
||||
#define MOSI_PIN P0_18
|
||||
#define SS_PIN P1_23 // Chip select for SD card used by Marlin
|
||||
#define ONBOARD_SD_CS P0_06 // Chip select for "System" SD card
|
||||
|
||||
#elif ENABLED(LPC_SD_ONBOARD)
|
||||
|
||||
#if ENABLED(USB_SD_ONBOARD)
|
||||
// When sharing the SD card with a PC we want the menu options to
|
||||
// mount/unmount the card and refresh it. So we disable card detect.
|
||||
#define SHARED_SD_CARD
|
||||
#undef SD_DETECT_PIN // there is also no detect pin for the onboard card
|
||||
#endif
|
||||
#define SCK_PIN P0_07
|
||||
#define MISO_PIN P0_08
|
||||
#define MOSI_PIN P0_09
|
||||
#define SS_PIN P0_06 // Chip select for SD card used by Marlin
|
||||
#define ONBOARD_SD_CS P0_06 // Chip select for "System" SD card
|
||||
|
||||
#endif
|
|
@ -29,183 +29,15 @@
|
|||
#endif
|
||||
|
||||
#define BOARD_NAME "Azteeg X5 MINI WIFI"
|
||||
#define BOARD_WEBSITE_URL "http://www.panucatt.com/azteeg_X5_mini_reprap_3d_printer_controller_p/ax5mini.htm"
|
||||
|
||||
//
|
||||
// LED
|
||||
//
|
||||
#define LED_PIN P1_18
|
||||
|
||||
//
|
||||
// Servos
|
||||
//
|
||||
#define SERVO0_PIN P1_29
|
||||
|
||||
//
|
||||
// Limit Switches
|
||||
//
|
||||
#define X_STOP_PIN P1_24
|
||||
#define Y_STOP_PIN P1_26
|
||||
#define Z_STOP_PIN P1_28
|
||||
|
||||
#ifndef FILWIDTH_PIN
|
||||
#define FILWIDTH_PIN P2_04
|
||||
#endif
|
||||
|
||||
//
|
||||
// Steppers
|
||||
//
|
||||
#define X_STEP_PIN P2_01
|
||||
#define X_DIR_PIN P0_11
|
||||
#define X_ENABLE_PIN P0_10
|
||||
|
||||
#define Y_STEP_PIN P2_02
|
||||
#define Y_DIR_PIN P0_20
|
||||
#define Y_ENABLE_PIN P0_19
|
||||
|
||||
#define Z_STEP_PIN P2_03
|
||||
#define Z_DIR_PIN P0_22
|
||||
#define Z_ENABLE_PIN P0_21
|
||||
|
||||
#define E0_STEP_PIN P2_00
|
||||
#define E0_DIR_PIN P0_05
|
||||
#define E0_ENABLE_PIN P0_04
|
||||
|
||||
//
|
||||
// DIGIPOT slave addresses
|
||||
//
|
||||
#ifndef DIGIPOT_I2C_ADDRESS_A
|
||||
#define DIGIPOT_I2C_ADDRESS_A 0x58 // shifted slave address for first DIGIPOT (0x58 <- 0x2C << 1)
|
||||
#endif
|
||||
#ifndef DIGIPOT_I2C_ADDRESS_B
|
||||
#define DIGIPOT_I2C_ADDRESS_B 0x5C // shifted slave address for second DIGIPOT (0x5C <- 0x2E << 1)
|
||||
|
||||
//
|
||||
// Temperature Sensors
|
||||
// 3.3V max when defined as an analog input
|
||||
//
|
||||
#define TEMP_BED_PIN 0 // A0 (TH1)
|
||||
#define TEMP_0_PIN 1 // A1 (TH2)
|
||||
|
||||
//
|
||||
// Heaters / Fans
|
||||
//
|
||||
#define HEATER_BED_PIN P2_07
|
||||
#define HEATER_0_PIN P2_05
|
||||
#ifndef FAN_PIN
|
||||
#define FAN_PIN P0_26
|
||||
#endif
|
||||
#define FAN1_PIN P1_25
|
||||
|
||||
//
|
||||
// Display
|
||||
//
|
||||
#if ENABLED(ULTRA_LCD)
|
||||
|
||||
#if ENABLED(CR10_STOCKDISPLAY)
|
||||
|
||||
// Re-Arm can support Creality stock display without SD card reader and single cable on EXP3.
|
||||
// Re-Arm J3 pins 1 (p1.31) & 2 (P3.26) are not used. Stock cable will need to have one
|
||||
// 10-pin IDC connector trimmed or replaced with a 12-pin IDC connector to fit J3.
|
||||
// Requires REVERSE_ENCODER_DIRECTION in Configuration.h
|
||||
|
||||
#define BEEPER_PIN P2_11 // J3-3 & AUX-4
|
||||
|
||||
#define BTN_EN1 P0_16 // J3-7 & AUX-4
|
||||
#define BTN_EN2 P1_23 // J3-5 & AUX-4
|
||||
#define BTN_ENC P3_25 // J3-4 & AUX-4
|
||||
|
||||
#define LCD_PINS_RS P0_15 // J3-9 & AUX-4 (CS)
|
||||
#define LCD_PINS_ENABLE P0_18 // J3-10 & AUX-3 (SID, MOSI)
|
||||
#define LCD_PINS_D4 P2_06 // J3-8 & AUX-3 (SCK, CLK)
|
||||
|
||||
#else
|
||||
|
||||
#define BTN_EN1 P3_26 // (31) J3-2 & AUX-4
|
||||
#define BTN_EN2 P3_25 // (33) J3-4 & AUX-4
|
||||
#define BTN_ENC P2_11 // (35) J3-3 & AUX-4
|
||||
|
||||
#define SD_DETECT_PIN P1_31 // (49) not 5V tolerant J3-1 & AUX-3
|
||||
#define KILL_PIN P1_22 // (41) J5-4 & AUX-4
|
||||
#define LCD_PINS_RS P0_16 // (16) J3-7 & AUX-4
|
||||
#define LCD_SDSS P0_16 // (16) J3-7 & AUX-4
|
||||
#define LCD_BACKLIGHT_PIN P0_16 // (16) J3-7 & AUX-4 - only used on DOGLCD controllers
|
||||
#define LCD_PINS_ENABLE P0_18 // (51) (MOSI) J3-10 & AUX-3
|
||||
#define LCD_PINS_D4 P0_15 // (52) (SCK) J3-9 & AUX-3
|
||||
|
||||
#define DOGLCD_A0 P2_06 // (59) J3-8 & AUX-2
|
||||
|
||||
#if ENABLED(REPRAPWORLD_KEYPAD)
|
||||
#define SHIFT_OUT P0_18 // (51) (MOSI) J3-10 & AUX-3
|
||||
#define SHIFT_CLK P0_15 // (52) (SCK) J3-9 & AUX-3
|
||||
#define SHIFT_LD P1_31 // (49) not 5V tolerant J3-1 & AUX-3
|
||||
#elif DISABLED(NEWPANEL)
|
||||
//#define SHIFT_OUT P2_11 // (35) J3-3 & AUX-4
|
||||
//#define SHIFT_CLK P3_26 // (31) J3-2 & AUX-4
|
||||
//#define SHIFT_LD P3_25 // (33) J3-4 & AUX-4
|
||||
//#define SHIFT_EN P1_22 // (41) J5-4 & AUX-4
|
||||
#endif
|
||||
|
||||
#if ANY(VIKI2, miniVIKI)
|
||||
//#define LCD_SCREEN_ROT_180
|
||||
|
||||
#define BEEPER_PIN P1_30 // (37) may change if cable changes
|
||||
#define DOGLCD_CS P0_26 // (63) J5-3 & AUX-2
|
||||
#define DOGLCD_SCK SCK_PIN
|
||||
#define DOGLCD_MOSI MOSI_PIN
|
||||
|
||||
#define STAT_LED_BLUE_PIN P0_26 // (63) may change if cable changes
|
||||
#define STAT_LED_RED_PIN P1_21 // ( 6) may change if cable changes
|
||||
#else
|
||||
#if ENABLED(ULTIPANEL)
|
||||
#define LCD_PINS_D5 P1_17 // (71) ENET_MDIO
|
||||
#define LCD_PINS_D6 P1_14 // (73) ENET_RX_ER
|
||||
#define LCD_PINS_D7 P1_10 // (75) ENET_RXD1
|
||||
#endif
|
||||
#define BEEPER_PIN P1_30 // (37) not 5V tolerant
|
||||
#define DOGLCD_CS P0_16 // (16)
|
||||
#endif
|
||||
|
||||
#if ENABLED(MINIPANEL)
|
||||
// GLCD features
|
||||
// Uncomment screen orientation
|
||||
//#define LCD_SCREEN_ROT_90
|
||||
//#define LCD_SCREEN_ROT_180
|
||||
//#define LCD_SCREEN_ROT_270
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
#endif // ULTRA_LCD
|
||||
|
||||
//
|
||||
// SD Support
|
||||
//
|
||||
//#define USB_SD_DISABLED // Disable host access to SD card as mass storage device through USB
|
||||
//#define USB_SD_ONBOARD // Enable host access to SD card as mass storage device through USB
|
||||
|
||||
//#define LPC_SD_LCD // Marlin uses the SD drive attached to the LCD
|
||||
#define LPC_SD_ONBOARD // Marlin uses the SD drive on the control board. There is no SD detect pin
|
||||
// for the onboard card. Init card from LCD menu or send M21 whenever printer
|
||||
// is powered on to enable SD access.
|
||||
|
||||
#if ENABLED(LPC_SD_LCD)
|
||||
|
||||
#define SCK_PIN P0_15
|
||||
#define MISO_PIN P0_17
|
||||
#define MOSI_PIN P0_18
|
||||
#define SS_PIN P1_23 // Chip select for SD card used by Marlin
|
||||
#define ONBOARD_SD_CS P0_06 // Chip select for "System" SD card
|
||||
|
||||
#elif ENABLED(LPC_SD_ONBOARD)
|
||||
|
||||
#if ENABLED(USB_SD_ONBOARD)
|
||||
// When sharing the SD card with a PC we want the menu options to
|
||||
// mount/unmount the card and refresh it. So we disable card detect.
|
||||
#define SHARED_SD_CARD
|
||||
#undef SD_DETECT_PIN // there is also no detect pin for the onboard card
|
||||
#endif
|
||||
#define SCK_PIN P0_07
|
||||
#define MISO_PIN P0_08
|
||||
#define MOSI_PIN P0_09
|
||||
#define SS_PIN P0_06 // Chip select for SD card used by Marlin
|
||||
#define ONBOARD_SD_CS P0_06 // Chip select for "System" SD card
|
||||
|
||||
#endif
|
||||
#include "pins_AZTEEG_X5_MINI.h"
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
//
|
||||
// M3/M4/M5 - Spindle/Laser Control
|
||||
//
|
||||
#define SPINDLE_LASER_ENABLE_PIN 66 // Pin should have a pullup/pulldown!
|
||||
#define SPINDLE_LASER_ENA_PIN 66 // Pin should have a pullup/pulldown!
|
||||
#define SPINDLE_DIR_PIN 67
|
||||
#define SPINDLE_LASER_PWM_PIN 44 // MUST BE HARDWARE PWM
|
||||
|
||||
|
|
131
Marlin/src/pins/pins_BLACK_STM32F407VE.h
Normal file
131
Marlin/src/pins/pins_BLACK_STM32F407VE.h
Normal file
|
@ -0,0 +1,131 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2019 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/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* STM32F407VET6 with RAMPS-like shield
|
||||
* 'Black' STM32F407VET6 board - http://wiki.stm32duino.com/index.php?title=STM32F407
|
||||
* Shield - https://github.com/jmz52/Hardware
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#if !defined(STM32F4) && !defined(STM32F4xx)
|
||||
#error "Oops! Select an STM32F4 board in 'Tools > Board.'"
|
||||
#endif
|
||||
|
||||
#define DEFAULT_MACHINE_NAME "STM32F407VET6"
|
||||
//#define BOARD_NAME "Black STM32F4VET6"
|
||||
|
||||
//#define I2C_EEPROM
|
||||
//#define E2END 0x1FFF // EEPROM end address (8kB)
|
||||
#define EEPROM_EMULATED_WITH_SRAM
|
||||
|
||||
#if HOTENDS > 2 || E_STEPPERS > 2
|
||||
#error "Black STM32F4VET6 supports up to 2 hotends / E-steppers."
|
||||
#endif
|
||||
|
||||
//
|
||||
// Servos
|
||||
//
|
||||
#define SERVO0_PIN PC6
|
||||
#define SERVO1_PIN PC7
|
||||
|
||||
//
|
||||
// Limit Switches
|
||||
//
|
||||
#define X_MIN_PIN PC13
|
||||
#define X_MAX_PIN PA15
|
||||
#define Y_MIN_PIN PA5
|
||||
#define Y_MAX_PIN PD12
|
||||
#define Z_MIN_PIN PD14
|
||||
#define Z_MAX_PIN PD15
|
||||
|
||||
//
|
||||
// Steppers
|
||||
//
|
||||
#define X_STEP_PIN PC4
|
||||
#define X_DIR_PIN PA4
|
||||
#define X_ENABLE_PIN PE7
|
||||
|
||||
#define Y_STEP_PIN PE5
|
||||
#define Y_DIR_PIN PE2
|
||||
#define Y_ENABLE_PIN PE6
|
||||
|
||||
#define Z_STEP_PIN PD5
|
||||
#define Z_DIR_PIN PD3
|
||||
#define Z_ENABLE_PIN PD6
|
||||
|
||||
#define E0_STEP_PIN PD7
|
||||
#define E0_DIR_PIN PD0
|
||||
#define E0_ENABLE_PIN PB9
|
||||
|
||||
#define E1_STEP_PIN PE0
|
||||
#define E1_DIR_PIN PE1
|
||||
#define E1_ENABLE_PIN PB8
|
||||
|
||||
//
|
||||
// Temperature Sensors
|
||||
//
|
||||
#define TEMP_0_PIN PC0 // T0
|
||||
#define TEMP_1_PIN PC1 // T1
|
||||
#define TEMP_BED_PIN PC2 // TB
|
||||
#define TEMP_CHAMBER_PIN PC3 // TC
|
||||
|
||||
//
|
||||
// Heaters / Fans
|
||||
//
|
||||
#define HEATER_0_PIN PA2 // Heater0
|
||||
#define HEATER_1_PIN PA3 // Heater1
|
||||
#define HEATER_BED_PIN PA1 // Hotbed
|
||||
|
||||
#define FAN_PIN PE9 // Fan0
|
||||
#define FAN1_PIN PE11 // Fan1
|
||||
#define FAN2_PIN PE13 // Fan2
|
||||
#define FAN3_PIN PE14 // Fan3
|
||||
|
||||
//
|
||||
// Misc. Functions
|
||||
//
|
||||
#define SDSS PB12
|
||||
#define LED_PIN PA6
|
||||
//#define LED_PIN PA7
|
||||
#define KILL_PIN PB1
|
||||
|
||||
//
|
||||
// LCD / Controller
|
||||
//
|
||||
#define SD_DETECT_PIN PC5
|
||||
//#define SD_DETECT_PIN PA8 // SDIO SD_DETECT_PIN, external SDIO card reader only
|
||||
|
||||
#define BEEPER_PIN PD10
|
||||
#define LCD_PINS_RS PE15
|
||||
#define LCD_PINS_ENABLE PD8
|
||||
#define LCD_PINS_D4 PE10
|
||||
#define LCD_PINS_D5 PE12
|
||||
#define LCD_PINS_D6 PD1
|
||||
#define LCD_PINS_D7 PE8
|
||||
#define BTN_ENC PD9
|
||||
#define BTN_EN1 PD4
|
||||
#define BTN_EN2 PD13
|
||||
|
||||
#define DOGLCD_CS LCD_PINS_D5
|
||||
#define DOGLCD_A0 LCD_PINS_D6
|
|
@ -49,7 +49,7 @@
|
|||
//
|
||||
// M3/M4/M5 - Spindle/Laser Control
|
||||
//
|
||||
#define SPINDLE_LASER_ENABLE_PIN 40 // Pin should have a pullup/pulldown!
|
||||
#define SPINDLE_LASER_ENA_PIN 40 // Pin should have a pullup/pulldown!
|
||||
#define SPINDLE_LASER_PWM_PIN 44 // MUST BE HARDWARE PWM
|
||||
#define SPINDLE_DIR_PIN 42
|
||||
|
||||
|
|
|
@ -118,7 +118,7 @@
|
|||
//
|
||||
#if ENABLED(SPINDLE_LASER_ENABLE)
|
||||
#undef HEATER_0_PIN
|
||||
#define SPINDLE_LASER_ENABLE_PIN P2_07 // FET 1
|
||||
#define SPINDLE_LASER_ENA_PIN P2_07 // FET 1
|
||||
#undef HEATER_BED_PIN
|
||||
#define SPINDLE_LASER_PWM_PIN P2_05 // Bed FET
|
||||
#undef FAN_PIN
|
||||
|
|
|
@ -139,7 +139,7 @@
|
|||
//
|
||||
#if ENABLED(SPINDLE_LASER_ENABLE)
|
||||
#undef HEATER_0_PIN
|
||||
#define SPINDLE_LASER_ENABLE_PIN P2_07 // FET 1
|
||||
#define SPINDLE_LASER_ENA_PIN P2_07 // FET 1
|
||||
#undef HEATER_BED_PIN
|
||||
#define SPINDLE_LASER_PWM_PIN P2_05 // Bed FET
|
||||
#undef FAN_PIN
|
||||
|
|
|
@ -135,7 +135,7 @@
|
|||
//
|
||||
// use P1 connector for spindle pins
|
||||
#define SPINDLE_LASER_PWM_PIN 9 // MUST BE HARDWARE PWM
|
||||
#define SPINDLE_LASER_ENABLE_PIN 18 // Pin should have a pullup!
|
||||
#define SPINDLE_LASER_ENA_PIN 18 // Pin should have a pullup!
|
||||
#define SPINDLE_DIR_PIN 19
|
||||
|
||||
//
|
||||
|
|
|
@ -149,7 +149,7 @@
|
|||
//
|
||||
// use P1 connector for spindle pins
|
||||
#define SPINDLE_LASER_PWM_PIN 9 // MUST BE HARDWARE PWM
|
||||
#define SPINDLE_LASER_ENABLE_PIN 18 // Pin should have a pullup!
|
||||
#define SPINDLE_LASER_ENA_PIN 18 // Pin should have a pullup!
|
||||
#define SPINDLE_DIR_PIN 19
|
||||
|
||||
//
|
||||
|
|
|
@ -59,5 +59,5 @@
|
|||
// M3/M4/M5 - Spindle/Laser Control
|
||||
//
|
||||
#undef SPINDLE_LASER_PWM_PIN // Definitions in pins_RAMPS.h are not valid with this board
|
||||
#undef SPINDLE_LASER_ENABLE_PIN
|
||||
#undef SPINDLE_LASER_ENA_PIN
|
||||
#undef SPINDLE_DIR_PIN
|
||||
|
|
|
@ -149,6 +149,10 @@
|
|||
#define FAN_PIN 9
|
||||
#endif
|
||||
|
||||
#ifndef FIL_RUNOUT_PIN
|
||||
#define FIL_RUNOUT_PIN 57
|
||||
#endif
|
||||
|
||||
#if !HAS_FILAMENT_SENSOR
|
||||
#define FAN1_PIN 4
|
||||
#endif
|
||||
|
@ -169,6 +173,8 @@
|
|||
#define PS_ON_PIN 12
|
||||
#endif
|
||||
|
||||
#define CASE_LIGHT_PIN 5
|
||||
|
||||
//
|
||||
// LCD / Controller
|
||||
//
|
||||
|
|
|
@ -29,24 +29,24 @@
|
|||
|
||||
#define FAN_PIN 6
|
||||
|
||||
#include "pins_FORMBOT_RAPTOR.h"
|
||||
|
||||
#ifndef FIL_RUNOUT_PIN
|
||||
#define FIL_RUNOUT_PIN 22
|
||||
#endif
|
||||
|
||||
#include "pins_FORMBOT_RAPTOR.h"
|
||||
|
||||
#define GREEDY_PANEL ANY(PANEL_ONE, VIKI2, miniVIKI, MINIPANEL, REPRAPWORLD_KEYPAD)
|
||||
|
||||
//
|
||||
// M3/M4/M5 - Spindle/Laser Control
|
||||
//
|
||||
#if ENABLED(SPINDLE_LASER_ENABLE) && !PIN_EXISTS(SPINDLE_LASER_ENABLE)
|
||||
#if ENABLED(SPINDLE_LASER_ENABLE) && !PIN_EXISTS(SPINDLE_LASER_ENA)
|
||||
#if !NUM_SERVOS // Try to use servo connector first
|
||||
#define SPINDLE_LASER_ENABLE_PIN 6 // Pin should have a pullup/pulldown!
|
||||
#define SPINDLE_LASER_ENA_PIN 6 // Pin should have a pullup/pulldown!
|
||||
#define SPINDLE_LASER_PWM_PIN 4 // MUST BE HARDWARE PWM
|
||||
#define SPINDLE_DIR_PIN 5
|
||||
#elif !GREEDY_PANEL // Try to use AUX2
|
||||
#define SPINDLE_LASER_ENABLE_PIN 40 // Pin should have a pullup/pulldown!
|
||||
#define SPINDLE_LASER_ENA_PIN 40 // Pin should have a pullup/pulldown!
|
||||
#define SPINDLE_LASER_PWM_PIN 44 // MUST BE HARDWARE PWM
|
||||
#define SPINDLE_DIR_PIN 65
|
||||
#endif
|
||||
|
@ -62,6 +62,6 @@
|
|||
|
||||
#undef GREEDY_PANEL
|
||||
|
||||
#if ENABLED(CASE_LIGHT_ENABLE) && PIN_EXISTS(CASE_LIGHT) && (CASE_LIGHT_PIN == SPINDLE_LASER_ENABLE_PIN || CASE_LIGHT_PIN == SPINDLE_LASER_PWM_PIN)
|
||||
#if ENABLED(CASE_LIGHT_ENABLE) && PIN_EXISTS(CASE_LIGHT) && (CASE_LIGHT_PIN == SPINDLE_LASER_ENA_PIN || CASE_LIGHT_PIN == SPINDLE_LASER_PWM_PIN)
|
||||
#error "CASE_LIGHT_PIN conflicts with a Spindle / Laser pin."
|
||||
#endif
|
||||
|
|
|
@ -144,7 +144,7 @@
|
|||
#endif
|
||||
|
||||
#define SPINDLE_LASER_PWM_PIN 7 // MUST BE HARDWARE PWM
|
||||
#define SPINDLE_LASER_ENABLE_PIN 4 // Pin should have a pullup!
|
||||
#define SPINDLE_LASER_ENA_PIN 4 // Pin should have a pullup!
|
||||
|
||||
// Use the RAMPS 1.4 Analog input 5 on the AUX2 connector
|
||||
#define FILWIDTH_PIN 5 // Analog Input
|
||||
|
|
|
@ -116,7 +116,6 @@
|
|||
// the jumper next to the limit switch socket when using sensorless homing.
|
||||
//
|
||||
|
||||
|
||||
#if HAS_DRIVER(TMC2208)
|
||||
// Software serial
|
||||
#define X_SERIAL_RX_PIN 71
|
||||
|
@ -168,18 +167,16 @@
|
|||
#define PS_ON_PIN SERVO1_PIN
|
||||
#endif
|
||||
|
||||
#ifndef RGB_LED_R_PIN
|
||||
#define RGB_LED_R_PIN 3
|
||||
#endif
|
||||
#ifndef RGB_LED_G_PIN
|
||||
#define RGB_LED_G_PIN SERVO3_PIN
|
||||
#endif
|
||||
#ifndef RGB_LED_B_PIN
|
||||
#define RGB_LED_B_PIN 9
|
||||
#endif
|
||||
#ifndef RGB_LED_W_PIN
|
||||
#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
/**
|
||||
* ----- -----
|
||||
* 5V/D41 | · · | GND 5V | · · | GND
|
||||
* RESET | · · | D49 (SD_DETECT) (LCD_D7) D29 | · · | D27 (LCD_D6)
|
||||
* (MOSI) D51 | · · | D33 (BTN_EN2) (LCD_D5) D25 | · · | D23 (LCD_D4)
|
||||
* (SD_SS) D53 | · · | D31 (BTN_EN1) (LCD_RS) D16 | · · | D17 (LCD_EN)
|
||||
* (SCK) D52 | · · | D50 (MISO) (BTN_ENC) D35 | · · | D37 (BEEPER)
|
||||
* ----- -----
|
||||
* EXP2 EXP1
|
||||
*/
|
||||
|
||||
//
|
||||
// LCDs and Controllers
|
||||
|
@ -187,6 +184,29 @@
|
|||
#define BEEPER_PIN 37
|
||||
#define SD_DETECT_PIN 49
|
||||
|
||||
#if ENABLED(MKS_MINI_12864)
|
||||
#define DOGLCD_A0 27
|
||||
#define DOGLCD_CS 25
|
||||
#endif
|
||||
|
||||
#if ENABLED(FYSETC_MINI_12864)
|
||||
//
|
||||
// See https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
#define DOGLCD_A0 16
|
||||
#define DOGLCD_CS 17
|
||||
#ifndef RGB_LED_R_PIN
|
||||
#define RGB_LED_R_PIN 25
|
||||
#endif
|
||||
#ifndef RGB_LED_G_PIN
|
||||
#define RGB_LED_G_PIN 27
|
||||
#endif
|
||||
#ifndef RGB_LED_B_PIN
|
||||
#define RGB_LED_B_PIN 29
|
||||
#endif
|
||||
|
||||
#elif HAS_GRAPHICAL_LCD
|
||||
|
||||
#define LCD_PINS_RS 16
|
||||
#define LCD_PINS_ENABLE 17
|
||||
#define LCD_PINS_D4 23
|
||||
|
@ -194,13 +214,37 @@
|
|||
#define LCD_PINS_D6 27
|
||||
#define LCD_PINS_D7 29
|
||||
|
||||
#endif
|
||||
|
||||
#if ENABLED(NEWPANEL)
|
||||
#define BTN_EN1 31
|
||||
#define BTN_EN2 33
|
||||
#define BTN_ENC 35
|
||||
#endif
|
||||
|
||||
#if ENABLED(MKS_MINI_12864)
|
||||
#define DOGLCD_A0 27
|
||||
#define DOGLCD_CS 25
|
||||
#if ENABLED(FYSETC_MINI_12864)
|
||||
#define LCD_BACKLIGHT_PIN -1
|
||||
#define LCD_RESET_PIN 23
|
||||
#define KILL_PIN 41
|
||||
#ifndef RGB_LED_R_PIN
|
||||
#define RGB_LED_R_PIN 25
|
||||
#endif
|
||||
#ifndef RGB_LED_G_PIN
|
||||
#define RGB_LED_G_PIN 27
|
||||
#endif
|
||||
#ifndef RGB_LED_B_PIN
|
||||
#define RGB_LED_B_PIN 29
|
||||
#endif
|
||||
#endif
|
||||
#ifndef RGB_LED_R_PIN
|
||||
#define RGB_LED_R_PIN 3
|
||||
#endif
|
||||
#ifndef RGB_LED_G_PIN
|
||||
#define RGB_LED_G_PIN 4
|
||||
#endif
|
||||
#ifndef RGB_LED_B_PIN
|
||||
#define RGB_LED_B_PIN 9
|
||||
#endif
|
||||
#ifndef RGB_LED_W_PIN
|
||||
#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
|
|
@ -114,6 +114,6 @@
|
|||
//
|
||||
// M3/M4/M5 - Spindle/Laser Control
|
||||
//
|
||||
#define SPINDLE_LASER_ENABLE_PIN 5 // Pin should have a pullup/pulldown!
|
||||
#define SPINDLE_LASER_ENA_PIN 5 // Pin should have a pullup/pulldown!
|
||||
#define SPINDLE_LASER_PWM_PIN 16 // MUST BE HARDWARE PWM
|
||||
#define SPINDLE_DIR_PIN 6
|
||||
|
|
|
@ -140,7 +140,7 @@
|
|||
//
|
||||
// M3/M4/M5 - Spindle/Laser Control
|
||||
//
|
||||
#define SPINDLE_LASER_ENABLE_PIN 10 // Pin should have a pullup/pulldown!
|
||||
#define SPINDLE_LASER_ENA_PIN 10 // Pin should have a pullup/pulldown!
|
||||
#define SPINDLE_DIR_PIN 11
|
||||
#if GEN7_VERSION < 13
|
||||
#define SPINDLE_LASER_PWM_PIN 16 // MUST BE HARDWARE PWM
|
||||
|
|
|
@ -113,6 +113,6 @@
|
|||
//
|
||||
// M3/M4/M5 - Spindle/Laser Control
|
||||
//
|
||||
#define SPINDLE_LASER_ENABLE_PIN 20 // Pin should have a pullup/pulldown!
|
||||
#define SPINDLE_LASER_ENA_PIN 20 // Pin should have a pullup/pulldown!
|
||||
#define SPINDLE_LASER_PWM_PIN 16 // MUST BE HARDWARE PWM
|
||||
#define SPINDLE_DIR_PIN 21
|
||||
|
|
|
@ -133,6 +133,6 @@
|
|||
//
|
||||
// M3/M4/M5 - Spindle/Laser Control
|
||||
//
|
||||
#define SPINDLE_LASER_ENABLE_PIN 5 // Pin should have a pullup/pulldown!
|
||||
#define SPINDLE_LASER_ENA_PIN 5 // Pin should have a pullup/pulldown!
|
||||
#define SPINDLE_LASER_PWM_PIN 16 // MUST BE HARDWARE PWM
|
||||
#define SPINDLE_DIR_PIN 6
|
||||
|
|
|
@ -161,5 +161,5 @@
|
|||
// M3/M4/M5 - Spindle/Laser Control
|
||||
//
|
||||
#define SPINDLE_LASER_PWM_PIN 6 // MUST BE HARDWARE PWM
|
||||
#define SPINDLE_LASER_ENABLE_PIN 7 // Pin should have a pullup!
|
||||
#define SPINDLE_LASER_ENA_PIN 7 // Pin should have a pullup!
|
||||
#define SPINDLE_DIR_PIN 8
|
||||
|
|
|
@ -126,5 +126,5 @@
|
|||
// M3/M4/M5 - Spindle/Laser Control
|
||||
//
|
||||
#define SPINDLE_LASER_PWM_PIN 3 // MUST BE HARDWARE PWM
|
||||
#define SPINDLE_LASER_ENABLE_PIN 4 // Pin should have a pullup!
|
||||
#define SPINDLE_LASER_ENA_PIN 4 // Pin should have a pullup!
|
||||
#define SPINDLE_DIR_PIN 11
|
||||
|
|
|
@ -141,5 +141,5 @@
|
|||
// M3/M4/M5 - Spindle/Laser Control
|
||||
//
|
||||
#define SPINDLE_LASER_PWM_PIN 3 // MUST BE HARDWARE PWM
|
||||
#define SPINDLE_LASER_ENABLE_PIN 16 // Pin should have a pullup!
|
||||
#define SPINDLE_LASER_ENA_PIN 16 // Pin should have a pullup!
|
||||
#define SPINDLE_DIR_PIN 11
|
||||
|
|
|
@ -174,7 +174,7 @@
|
|||
//
|
||||
#if DISABLED(REPRAPWORLD_KEYPAD) // try to use the keypad connector first
|
||||
#define SPINDLE_LASER_PWM_PIN 44 // MUST BE HARDWARE PWM
|
||||
#define SPINDLE_LASER_ENABLE_PIN 43 // Pin should have a pullup!
|
||||
#define SPINDLE_LASER_ENA_PIN 43 // Pin should have a pullup!
|
||||
#define SPINDLE_DIR_PIN 42
|
||||
#elif EXTRUDERS <= 2
|
||||
// Hijack the last extruder so that we can get the PWM signal off the Y breakout
|
||||
|
@ -189,6 +189,6 @@
|
|||
#define Y_STEP_PIN 22
|
||||
#define Y_DIR_PIN 60
|
||||
#define SPINDLE_LASER_PWM_PIN 4 // MUST BE HARDWARE PWM
|
||||
#define SPINDLE_LASER_ENABLE_PIN 17 // Pin should have a pullup!
|
||||
#define SPINDLE_LASER_ENA_PIN 17 // Pin should have a pullup!
|
||||
#define SPINDLE_DIR_PIN 5
|
||||
#endif
|
||||
|
|
|
@ -104,7 +104,9 @@
|
|||
#define DIGIPOTS_I2C_SDA_E0 27 // A5
|
||||
#define DIGIPOTS_I2C_SDA_E1 77 // J6
|
||||
|
||||
#ifndef DIGIPOT_I2C_ADDRESS_A
|
||||
#define DIGIPOT_I2C_ADDRESS_A 0x2F // unshifted slave address (5E <- 2F << 1)
|
||||
#endif
|
||||
|
||||
//
|
||||
// Temperature Sensors
|
||||
|
@ -263,7 +265,7 @@
|
|||
//
|
||||
// M3/M4/M5 - Spindle/Laser Control
|
||||
//
|
||||
#define SPINDLE_LASER_ENABLE_PIN 66 // K4 Pin should have a pullup!
|
||||
#define SPINDLE_LASER_ENA_PIN 66 // K4 Pin should have a pullup!
|
||||
#define SPINDLE_LASER_PWM_PIN 8 // H5 MUST BE HARDWARE PWM
|
||||
#define SPINDLE_DIR_PIN 67 // K5
|
||||
|
||||
|
|
|
@ -125,7 +125,7 @@
|
|||
//
|
||||
// use P1 connector for spindle pins
|
||||
#define SPINDLE_LASER_PWM_PIN 9 // MUST BE HARDWARE PWM
|
||||
#define SPINDLE_LASER_ENABLE_PIN 18 // Pin should have a pullup!
|
||||
#define SPINDLE_LASER_ENA_PIN 18 // Pin should have a pullup!
|
||||
#define SPINDLE_DIR_PIN 19
|
||||
|
||||
//
|
||||
|
|
|
@ -138,7 +138,7 @@
|
|||
#define HEATER_BED_PIN 4 // won't compile
|
||||
#define TEMP_BED_PIN 50
|
||||
#define TEMP_0_PIN 51
|
||||
#define SPINDLE_LASER_ENABLE_PIN 52 // using A6 because it already has a pullup
|
||||
#define SPINDLE_LASER_ENA_PIN 52 // using A6 because it already has a pullup
|
||||
#define SPINDLE_LASER_PWM_PIN 3 // WARNING - LED & resistor pull up to +12/+24V stepper voltage
|
||||
#define SPINDLE_DIR_PIN 53
|
||||
#endif
|
||||
|
|
|
@ -44,7 +44,7 @@
|
|||
// M3/M4/M5 - Spindle/Laser Control
|
||||
//
|
||||
#define SPINDLE_LASER_PWM_PIN 2 // MUST BE HARDWARE PWM
|
||||
#define SPINDLE_LASER_ENABLE_PIN 15 // Pin should have a pullup!
|
||||
#define SPINDLE_LASER_ENA_PIN 15 // Pin should have a pullup!
|
||||
#define SPINDLE_DIR_PIN 19
|
||||
|
||||
#include "pins_RAMPS.h"
|
||||
|
|
|
@ -47,7 +47,7 @@
|
|||
// M3/M4/M5 - Spindle/Laser Control
|
||||
//
|
||||
#define SPINDLE_LASER_PWM_PIN 2 // X+ // PE4 ** Pin6 ** PWM2 **MUST BE HARDWARE PWM
|
||||
#define SPINDLE_LASER_ENABLE_PIN 15 // Y+ // PJ0 ** Pin63 ** USART3_RX **Pin should have a pullup!
|
||||
#define SPINDLE_LASER_ENA_PIN 15 // Y+ // PJ0 ** Pin63 ** USART3_RX **Pin should have a pullup!
|
||||
#define SPINDLE_DIR_PIN 19 // Z+ // PD2 ** Pin45 ** USART1_RX
|
||||
|
||||
//
|
||||
|
@ -64,6 +64,16 @@
|
|||
#define E1_MS1_PIN 57 // PF3 ** Pin94 ** A3
|
||||
#define E1_MS2_PIN 4 // PG5 ** Pin1 ** PWM4
|
||||
|
||||
#ifndef RGB_LED_R_PIN
|
||||
#define RGB_LED_R_PIN 50
|
||||
#endif
|
||||
#ifndef RGB_LED_R_PIN
|
||||
#define RGB_LED_G_PIN 51
|
||||
#endif
|
||||
#ifndef RGB_LED_R_PIN
|
||||
#define RGB_LED_B_PIN 52
|
||||
#endif
|
||||
|
||||
#include "pins_RAMPS.h"
|
||||
|
||||
/*
|
||||
|
|
|
@ -149,7 +149,7 @@
|
|||
// M3/M4/M5 - Spindle/Laser Control
|
||||
//
|
||||
#define SPINDLE_LASER_PWM_PIN 45 // MUST BE HARDWARE PWM
|
||||
#define SPINDLE_LASER_ENABLE_PIN 31 // Pin should have a pullup!
|
||||
#define SPINDLE_LASER_ENA_PIN 31 // Pin should have a pullup!
|
||||
#define SPINDLE_DIR_PIN 32
|
||||
|
||||
//
|
||||
|
|
|
@ -231,10 +231,12 @@
|
|||
#define PS_ON_PIN 12
|
||||
#endif
|
||||
|
||||
#if ENABLED(CASE_LIGHT_ENABLE) && !defined(CASE_LIGHT_PIN) && !defined(SPINDLE_LASER_ENABLE_PIN)
|
||||
#define AUX2_PINS_FREE !( BOTH(ULTRA_LCD, NEWPANEL) && ANY(PANEL_ONE, VIKI2, miniVIKI, MINIPANEL, REPRAPWORLD_KEYPAD) )
|
||||
|
||||
#if ENABLED(CASE_LIGHT_ENABLE) && !defined(CASE_LIGHT_PIN) && !defined(SPINDLE_LASER_ENA_PIN)
|
||||
#if NUM_SERVOS <= 1 // try to use servo connector first
|
||||
#define CASE_LIGHT_PIN 6 // MUST BE HARDWARE PWM
|
||||
#elif !(BOTH(ULTRA_LCD, NEWPANEL) && ANY(PANEL_ONE, VIKI2, miniVIKI, MINIPANEL, REPRAPWORLD_KEYPAD)) // try to use AUX 2
|
||||
#elif AUX2_PINS_FREE
|
||||
#define CASE_LIGHT_PIN 44 // MUST BE HARDWARE PWM
|
||||
#endif
|
||||
#endif
|
||||
|
@ -242,18 +244,20 @@
|
|||
//
|
||||
// M3/M4/M5 - Spindle/Laser Control
|
||||
//
|
||||
#if ENABLED(SPINDLE_LASER_ENABLE) && !PIN_EXISTS(SPINDLE_LASER_ENABLE)
|
||||
#if ENABLED(SPINDLE_LASER_ENABLE) && !PIN_EXISTS(SPINDLE_LASER_ENA)
|
||||
#if !defined(NUM_SERVOS) || NUM_SERVOS == 0 // try to use servo connector first
|
||||
#define SPINDLE_LASER_ENABLE_PIN 4 // Pin should have a pullup/pulldown!
|
||||
#define SPINDLE_LASER_ENA_PIN 4 // Pin should have a pullup/pulldown!
|
||||
#define SPINDLE_LASER_PWM_PIN 6 // MUST BE HARDWARE PWM
|
||||
#define SPINDLE_DIR_PIN 5
|
||||
#elif !(BOTH(ULTRA_LCD, NEWPANEL) && ANY(PANEL_ONE, VIKI2, miniVIKI, MINIPANEL, REPRAPWORLD_KEYPAD)) // try to use AUX 2
|
||||
#define SPINDLE_LASER_ENABLE_PIN 40 // Pin should have a pullup/pulldown!
|
||||
#elif AUX2_PINS_FREE
|
||||
#define SPINDLE_LASER_ENA_PIN 40 // Pin should have a pullup/pulldown!
|
||||
#define SPINDLE_LASER_PWM_PIN 44 // MUST BE HARDWARE PWM
|
||||
#define SPINDLE_DIR_PIN 65
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#undef AUX2_PINS_FREE
|
||||
|
||||
//
|
||||
// TMC software SPI
|
||||
//
|
||||
|
@ -518,6 +522,31 @@
|
|||
#define SD_DETECT_PIN 49
|
||||
#define KILL_PIN 41
|
||||
|
||||
#elif ENABLED(FYSETC_MINI_12864) // Added in Marlin 1.1.9+
|
||||
|
||||
// From https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
#define BEEPER_PIN 37
|
||||
#define LCD_RESET_PIN 23
|
||||
|
||||
#define DOGLCD_A0 16
|
||||
#define DOGLCD_CS 17
|
||||
|
||||
#define BTN_EN1 31
|
||||
#define BTN_EN2 33
|
||||
#define BTN_ENC 35
|
||||
|
||||
#define SD_DETECT_PIN 49
|
||||
|
||||
#ifndef RGB_LED_R_PIN
|
||||
#define RGB_LED_R_PIN 25
|
||||
#endif
|
||||
#ifndef RGB_LED_G_PIN
|
||||
#define RGB_LED_G_PIN 27
|
||||
#endif
|
||||
#ifndef RGB_LED_B_PIN
|
||||
#define RGB_LED_B_PIN 29
|
||||
#endif
|
||||
|
||||
#elif ENABLED(MINIPANEL)
|
||||
|
||||
#define BEEPER_PIN 42
|
||||
|
|
|
@ -198,9 +198,9 @@
|
|||
//
|
||||
// M3/M4/M5 - Spindle/Laser Control
|
||||
//
|
||||
#if ENABLED(SPINDLE_LASER_ENABLE) && !PIN_EXISTS(SPINDLE_LASER_ENABLE)
|
||||
#if ENABLED(SPINDLE_LASER_ENABLE) && !PIN_EXISTS(SPINDLE_LASER_ENA)
|
||||
#if HOTENDS < 3
|
||||
#define SPINDLE_LASER_ENABLE_PIN 45 // Use E2 ENA
|
||||
#define SPINDLE_LASER_ENA_PIN 45 // Use E2 ENA
|
||||
#define SPINDLE_LASER_PWM_PIN 12 // MUST BE HARDWARE PWM
|
||||
#define SPINDLE_DIR_PIN 47 // Use E2 DIR
|
||||
#endif
|
||||
|
|
|
@ -217,7 +217,7 @@
|
|||
#define PS_ON_PIN 12
|
||||
#endif
|
||||
|
||||
#if ENABLED(CASE_LIGHT_ENABLE) && !defined(CASE_LIGHT_PIN) && !defined(SPINDLE_LASER_ENABLE_PIN)
|
||||
#if ENABLED(CASE_LIGHT_ENABLE) && !defined(CASE_LIGHT_PIN) && !defined(SPINDLE_LASER_ENA_PIN)
|
||||
#if NUM_SERVOS <= 1 // try to use servo connector first
|
||||
#define CASE_LIGHT_PIN 6 // MUST BE HARDWARE PWM
|
||||
#elif !(BOTH(ULTRA_LCD, NEWPANEL) && ANY(PANEL_ONE, VIKI2, miniVIKI, MINIPANEL, REPRAPWORLD_KEYPAD)) // try to use AUX 2
|
||||
|
@ -228,13 +228,13 @@
|
|||
//
|
||||
// M3/M4/M5 - Spindle/Laser Control
|
||||
//
|
||||
#if ENABLED(SPINDLE_LASER_ENABLE) && !PIN_EXISTS(SPINDLE_LASER_ENABLE)
|
||||
#if ENABLED(SPINDLE_LASER_ENABLE) && !PIN_EXISTS(SPINDLE_LASER_ENA)
|
||||
#if !defined(NUM_SERVOS) || NUM_SERVOS == 0 // try to use servo connector first
|
||||
#define SPINDLE_LASER_ENABLE_PIN 4 // Pin should have a pullup/pulldown!
|
||||
#define SPINDLE_LASER_ENA_PIN 4 // Pin should have a pullup/pulldown!
|
||||
#define SPINDLE_LASER_PWM_PIN 6 // MUST BE HARDWARE PWM
|
||||
#define SPINDLE_DIR_PIN 5
|
||||
#elif !(BOTH(ULTRA_LCD, NEWPANEL) && ANY(PANEL_ONE, VIKI2, miniVIKI, MINIPANEL, REPRAPWORLD_KEYPAD)) // try to use AUX 2
|
||||
#define SPINDLE_LASER_ENABLE_PIN 40 // Pin should have a pullup/pulldown!
|
||||
#define SPINDLE_LASER_ENA_PIN 40 // Pin should have a pullup/pulldown!
|
||||
#define SPINDLE_LASER_PWM_PIN 44 // MUST BE HARDWARE PWM
|
||||
#define SPINDLE_DIR_PIN 65
|
||||
#endif
|
||||
|
|
|
@ -110,6 +110,6 @@
|
|||
//
|
||||
// M3/M4/M5 - Spindle/Laser Control
|
||||
//
|
||||
#define SPINDLE_LASER_ENABLE_PIN 41 // Pin should have a pullup/pulldown!
|
||||
#define SPINDLE_LASER_ENA_PIN 41 // Pin should have a pullup/pulldown!
|
||||
#define SPINDLE_LASER_PWM_PIN 45 // MUST BE HARDWARE PWM
|
||||
#define SPINDLE_DIR_PIN 43
|
||||
|
|
|
@ -200,7 +200,7 @@
|
|||
#define MAX6675_SS_PIN P1_28
|
||||
#endif
|
||||
|
||||
#if ENABLED(CASE_LIGHT_ENABLE) && !PIN_EXISTS(CASE_LIGHT) && !defined(SPINDLE_LASER_ENABLE_PIN)
|
||||
#if ENABLED(CASE_LIGHT_ENABLE) && !PIN_EXISTS(CASE_LIGHT) && !defined(SPINDLE_LASER_ENA_PIN)
|
||||
#if !defined(NUM_SERVOS) || NUM_SERVOS < 4 // Try to use servo connector
|
||||
#define CASE_LIGHT_PIN P1_18 // (4) MUST BE HARDWARE PWM
|
||||
#endif
|
||||
|
@ -210,11 +210,11 @@
|
|||
// M3/M4/M5 - Spindle/Laser Control
|
||||
// Use servo pins, if available
|
||||
//
|
||||
#if ENABLED(SPINDLE_LASER_ENABLE) && !PIN_EXISTS(SPINDLE_LASER_ENABLE)
|
||||
#if ENABLED(SPINDLE_LASER_ENABLE) && !PIN_EXISTS(SPINDLE_LASER_ENA)
|
||||
#if NUM_SERVOS > 1
|
||||
#error "SPINDLE_LASER_ENABLE requires 3 free servo pins."
|
||||
#endif
|
||||
#define SPINDLE_LASER_ENABLE_PIN SERVO1_PIN // (6) Pin should have a pullup/pulldown!
|
||||
#define SPINDLE_LASER_ENA_PIN SERVO1_PIN // (6) Pin should have a pullup/pulldown!
|
||||
#define SPINDLE_LASER_PWM_PIN SERVO3_PIN // (4) MUST BE HARDWARE PWM
|
||||
#define SPINDLE_DIR_PIN SERVO2_PIN // (5)
|
||||
#endif
|
||||
|
|
|
@ -157,8 +157,8 @@
|
|||
#ifndef SPINDLE_LASER_PWM_PIN
|
||||
#define SPINDLE_LASER_PWM_PIN 4 // MUST BE HARDWARE PWM. Pin 4 interrupts OC0* and OC1* always in use?
|
||||
#endif
|
||||
#ifndef SPINDLE_LASER_ENABLE_PIN
|
||||
#define SPINDLE_LASER_ENABLE_PIN 14 // Pin should have a pullup!
|
||||
#ifndef SPINDLE_LASER_ENA_PIN
|
||||
#define SPINDLE_LASER_ENA_PIN 14 // Pin should have a pullup!
|
||||
#endif
|
||||
#ifndef SPINDLE_DIR_PIN
|
||||
#define SPINDLE_DIR_PIN 15
|
||||
|
|
|
@ -161,11 +161,11 @@
|
|||
|
||||
// MKS TFT / Nextion Use internal USART-1
|
||||
#define TFT_LCD_MODULE_COM 1
|
||||
#define TFT_LCD_MODULE_BAUDRATE 115600
|
||||
#define TFT_LCD_MODULE_BAUDRATE 115200
|
||||
|
||||
// ESP WiFi Use internal USART-2
|
||||
#define ESP_WIFI_MODULE_COM 2
|
||||
#define ESP_WIFI_MODULE_BAUDRATE 115600
|
||||
#define ESP_WIFI_MODULE_BAUDRATE 115200
|
||||
#define ESP_WIFI_MODULE_RESET_PIN -1
|
||||
#define PIGGY_GPIO_PIN -1
|
||||
|
||||
|
|
|
@ -279,7 +279,7 @@
|
|||
#if ENABLED(SPINDLE_LASER_ENABLE)
|
||||
#if !MB(AZTEEG_X1) && ENABLED(SANGUINOLOLU_V_1_2) && !BOTH(ULTRA_LCD, NEWPANEL) // try to use IO Header
|
||||
|
||||
#define SPINDLE_LASER_ENABLE_PIN 10 // Pin should have a pullup/pulldown!
|
||||
#define SPINDLE_LASER_ENA_PIN 10 // Pin should have a pullup/pulldown!
|
||||
#define SPINDLE_LASER_PWM_PIN 4 // MUST BE HARDWARE PWM
|
||||
#define SPINDLE_DIR_PIN 11
|
||||
|
||||
|
@ -307,7 +307,7 @@
|
|||
* /RESET O| |O 1A
|
||||
* /SLEEP O| |O 1B
|
||||
* SPINDLE_LASER_PWM_PIN STEP O| |O VDD
|
||||
* SPINDLE_LASER_ENABLE_PIN DIR O| |O GND
|
||||
* SPINDLE_LASER_ENA_PIN DIR O| |O GND
|
||||
* -------
|
||||
*
|
||||
* Note: Socket names vary from vendor to vendor.
|
||||
|
@ -319,7 +319,7 @@
|
|||
#define X_ENABLE_PIN 14
|
||||
#define X_STEP_PIN 1
|
||||
#define SPINDLE_LASER_PWM_PIN 15 // MUST BE HARDWARE PWM
|
||||
#define SPINDLE_LASER_ENABLE_PIN 21 // Pin should have a pullup!
|
||||
#define SPINDLE_LASER_ENA_PIN 21 // Pin should have a pullup!
|
||||
#define SPINDLE_DIR_PIN -1 // No pin available on the socket for the direction pin
|
||||
#endif
|
||||
#endif // SPINDLE_LASER_ENABLE
|
||||
|
|
|
@ -176,7 +176,7 @@
|
|||
// M3/M4/M5 - Spindle/Laser Control
|
||||
//
|
||||
#define SPINDLE_LASER_PWM_PIN 24 // B4 PWM2A
|
||||
#define SPINDLE_LASER_ENABLE_PIN 39 // F1 Pin should have a pullup!
|
||||
#define SPINDLE_LASER_ENA_PIN 39 // F1 Pin should have a pullup!
|
||||
#define SPINDLE_DIR_PIN 40 // F2
|
||||
|
||||
#define CASE_LIGHT_PIN 0 // D0 PWM0B
|
||||
|
|
|
@ -108,7 +108,7 @@
|
|||
// Laser control
|
||||
#if ENABLED(SPINDLE_LASER_ENABLE)
|
||||
#define SPINDLE_LASER_PWM_PIN PB8
|
||||
#define SPINDLE_LASER_ENABLE_PIN PD5
|
||||
#define SPINDLE_LASER_ENA_PIN PD5
|
||||
#endif
|
||||
|
||||
//
|
||||
|
|
|
@ -179,6 +179,6 @@
|
|||
//
|
||||
// M3/M4/M5 - Spindle/Laser Control
|
||||
//
|
||||
#define SPINDLE_LASER_ENABLE_PIN 5 // D5 Pin should have a pullup!
|
||||
#define SPINDLE_LASER_ENA_PIN 5 // D5 Pin should have a pullup!
|
||||
#define SPINDLE_LASER_PWM_PIN 0 // D0 PWM0B MUST BE HARDWARE PWM
|
||||
#define SPINDLE_DIR_PIN 7 // D7
|
||||
|
|
|
@ -159,5 +159,5 @@
|
|||
// M3/M4/M5 - Spindle/Laser Control
|
||||
//
|
||||
#define SPINDLE_LASER_PWM_PIN 24 // B4 IO-3 PWM2A - MUST BE HARDWARE PWM
|
||||
#define SPINDLE_LASER_ENABLE_PIN 39 // F1 IO-11 - Pin should have a pullup!
|
||||
#define SPINDLE_LASER_ENA_PIN 39 // F1 IO-11 - Pin should have a pullup!
|
||||
#define SPINDLE_DIR_PIN 40 // F2 IO-9
|
||||
|
|
|
@ -131,7 +131,7 @@
|
|||
#if ENABLED(SPINDLE_LASER_ENABLE) // use the LED_PIN for spindle speed control or case light
|
||||
#undef LED_PIN
|
||||
#define SPINDLE_DIR_PIN 16
|
||||
#define SPINDLE_LASER_ENABLE_PIN 17 // Pin should have a pullup!
|
||||
#define SPINDLE_LASER_ENA_PIN 17 // Pin should have a pullup!
|
||||
#define SPINDLE_LASER_PWM_PIN 8 // MUST BE HARDWARE PWM
|
||||
#else
|
||||
#undef LED_PIN
|
||||
|
|
|
@ -160,5 +160,5 @@
|
|||
// M3/M4/M5 - Spindle/Laser Control
|
||||
//
|
||||
#define SPINDLE_LASER_PWM_PIN 9 // MUST BE HARDWARE PWM
|
||||
#define SPINDLE_LASER_ENABLE_PIN 10 // Pin should have a pullup!
|
||||
#define SPINDLE_LASER_ENA_PIN 10 // Pin should have a pullup!
|
||||
#define SPINDLE_DIR_PIN 11 // use the EXP3 PWM header
|
||||
|
|
|
@ -221,13 +221,13 @@
|
|||
|
||||
#define SPINDLE_DIR_PIN 10 // SW4
|
||||
#define SPINDLE_LASER_PWM_PIN 9 // SW5 MUST BE HARDWARE PWM
|
||||
#define SPINDLE_LASER_ENABLE_PIN 8 // SW6 Pin should have a pullup!
|
||||
#define SPINDLE_LASER_ENA_PIN 8 // SW6 Pin should have a pullup!
|
||||
|
||||
#elif ENABLED(board_rev_1_5) // use the same pins - but now they are on a different connector
|
||||
|
||||
#define SPINDLE_DIR_PIN 10 // EXP3-6 (silkscreen says 10)
|
||||
#define SPINDLE_LASER_PWM_PIN 9 // EXP3-7 (silkscreen says 9) MUST BE HARDWARE PWM
|
||||
#define SPINDLE_LASER_ENABLE_PIN 8 // EXP3-8 (silkscreen says 8) Pin should have a pullup!
|
||||
#define SPINDLE_LASER_ENA_PIN 8 // EXP3-8 (silkscreen says 8) Pin should have a pullup!
|
||||
|
||||
#elif ENABLED(board_rev_1_1_TO_1_3)
|
||||
|
||||
|
@ -251,12 +251,12 @@
|
|||
#define E0_ENABLE_PIN 48
|
||||
#define SPINDLE_DIR_PIN 43
|
||||
#define SPINDLE_LASER_PWM_PIN 45 // MUST BE HARDWARE PWM
|
||||
#define SPINDLE_LASER_ENABLE_PIN 41 // Pin should have a pullup!
|
||||
#define SPINDLE_LASER_ENA_PIN 41 // Pin should have a pullup!
|
||||
#elif TEMP_SENSOR_BED == 0 // Can't use E0 so see if HEATER_BED_PIN is available
|
||||
#undef HEATER_BED_PIN
|
||||
#define SPINDLE_DIR_PIN 38 // Probably pin 4 on 10 pin connector closest to the E0 socket
|
||||
#define SPINDLE_LASER_PWM_PIN 4 // MUST BE HARDWARE PWM - Special precautions usually needed.
|
||||
#define SPINDLE_LASER_ENABLE_PIN 40 // Pin should have a pullup! (Probably pin 6 on the 10-pin
|
||||
#define SPINDLE_LASER_ENA_PIN 40 // Pin should have a pullup! (Probably pin 6 on the 10-pin
|
||||
// connector closest to the E0 socket)
|
||||
#endif
|
||||
#endif
|
||||
|
@ -267,7 +267,7 @@
|
|||
*
|
||||
* spindle signal socket name socket name
|
||||
* -------
|
||||
* SPINDLE_LASER_ENABLE_PIN /ENABLE *| |O VMOT
|
||||
* SPINDLE_LASER_ENA_PIN /ENABLE *| |O VMOT
|
||||
* MS1 O| |O GND
|
||||
* MS2 O| |O 2B
|
||||
* MS3 O| |O 2A
|
||||
|
|
|
@ -35,7 +35,7 @@
|
|||
#else
|
||||
#define _X_MAX
|
||||
#endif
|
||||
#if PIN_EXISTS(X_CS)
|
||||
#if PIN_EXISTS(X_CS) && AXIS_HAS_SPI(X)
|
||||
#define _X_CS X_CS_PIN,
|
||||
#else
|
||||
#define _X_CS
|
||||
|
@ -68,7 +68,7 @@
|
|||
#else
|
||||
#define _Y_MAX
|
||||
#endif
|
||||
#if PIN_EXISTS(Y_CS)
|
||||
#if PIN_EXISTS(Y_CS) && AXIS_HAS_SPI(Y)
|
||||
#define _Y_CS Y_CS_PIN,
|
||||
#else
|
||||
#define _Y_CS
|
||||
|
@ -101,7 +101,7 @@
|
|||
#else
|
||||
#define _Z_MAX
|
||||
#endif
|
||||
#if PIN_EXISTS(Z_CS)
|
||||
#if PIN_EXISTS(Z_CS) && AXIS_HAS_SPI(Z)
|
||||
#define _Z_CS Z_CS_PIN,
|
||||
#else
|
||||
#define _Z_CS
|
||||
|
@ -139,7 +139,7 @@
|
|||
#define _E0_MS3
|
||||
|
||||
#if E_NEEDED(0)
|
||||
#if PIN_EXISTS(E0_CS)
|
||||
#if PIN_EXISTS(E0_CS) && AXIS_HAS_SPI(E0)
|
||||
#undef _E0_CS
|
||||
#define _E0_CS E0_CS_PIN,
|
||||
#endif
|
||||
|
@ -163,7 +163,7 @@
|
|||
#define _E1_MS3
|
||||
|
||||
#if E_NEEDED(1)
|
||||
#if PIN_EXISTS(E1_CS)
|
||||
#if PIN_EXISTS(E1_CS) && AXIS_HAS_SPI(E1)
|
||||
#undef _E1_CS
|
||||
#define _E1_CS E1_CS_PIN,
|
||||
#endif
|
||||
|
@ -187,7 +187,7 @@
|
|||
#define _E2_MS3
|
||||
|
||||
#if E_NEEDED(2)
|
||||
#if PIN_EXISTS(E2_CS)
|
||||
#if PIN_EXISTS(E2_CS) && AXIS_HAS_SPI(E2)
|
||||
#undef _E2_CS
|
||||
#define _E2_CS E2_CS_PIN,
|
||||
#endif
|
||||
|
@ -211,7 +211,7 @@
|
|||
#define _E3_MS3
|
||||
|
||||
#if E_NEEDED(3)
|
||||
#if PIN_EXISTS(E3_CS)
|
||||
#if PIN_EXISTS(E3_CS) && AXIS_HAS_SPI(E3)
|
||||
#undef _E3_CS
|
||||
#define _E3_CS E3_CS_PIN,
|
||||
#endif
|
||||
|
@ -235,7 +235,7 @@
|
|||
#define _E4_MS3
|
||||
|
||||
#if E_NEEDED(4)
|
||||
#if PIN_EXISTS(E4_CS)
|
||||
#if PIN_EXISTS(E4_CS) && AXIS_HAS_SPI(E4)
|
||||
#undef _E4_CS
|
||||
#define _E4_CS E4_CS_PIN,
|
||||
#endif
|
||||
|
@ -259,7 +259,7 @@
|
|||
#define _E5_MS3
|
||||
|
||||
#if E_NEEDED(5)
|
||||
#if PIN_EXISTS(E5_CS)
|
||||
#if PIN_EXISTS(E5_CS) && AXIS_HAS_SPI(E5)
|
||||
#undef _E5_CS
|
||||
#define _E5_CS E5_CS_PIN,
|
||||
#endif
|
||||
|
@ -368,7 +368,7 @@
|
|||
//
|
||||
|
||||
#if EITHER(DUAL_X_CARRIAGE, X_DUAL_STEPPER_DRIVERS)
|
||||
#if PIN_EXISTS(X2_CS)
|
||||
#if PIN_EXISTS(X2_CS) && AXIS_HAS_SPI(X2)
|
||||
#define _X2_CS X2_CS_PIN,
|
||||
#else
|
||||
#define _X2_CS
|
||||
|
@ -394,7 +394,7 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
||||
#if PIN_EXISTS(Y2_CS)
|
||||
#if PIN_EXISTS(Y2_CS) && AXIS_HAS_SPI(Y2)
|
||||
#define _Y2_CS Y2_CS_PIN,
|
||||
#else
|
||||
#define _Y2_CS
|
||||
|
@ -420,7 +420,7 @@
|
|||
#endif
|
||||
|
||||
#if Z_MULTI_STEPPER_DRIVERS
|
||||
#if PIN_EXISTS(Z2_CS)
|
||||
#if PIN_EXISTS(Z2_CS) && AXIS_HAS_SPI(Z2)
|
||||
#define _Z2_CS Z2_CS_PIN,
|
||||
#else
|
||||
#define _Z2_CS
|
||||
|
@ -446,7 +446,7 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(Z_TRIPLE_STEPPER_DRIVERS)
|
||||
#if PIN_EXISTS(Z3_CS)
|
||||
#if PIN_EXISTS(Z3_CS) && AXIS_HAS_SPI(Z3)
|
||||
#define _Z3_CS Z3_CS_PIN,
|
||||
#else
|
||||
#define _Z3_CS
|
||||
|
|
|
@ -813,7 +813,11 @@ void CardReader::setroot() {
|
|||
|
||||
// Init sort order.
|
||||
for (uint16_t i = 0; i < fileCnt; i++) {
|
||||
sort_order[i] = i;
|
||||
sort_order[i] = (
|
||||
#if ENABLED(SDCARD_RATHERRECENTFIRST)
|
||||
fileCnt - 1 -
|
||||
#endif
|
||||
i);
|
||||
// If using RAM then read all filenames now.
|
||||
#if ENABLED(SDSORT_USES_RAM)
|
||||
getfilename(i);
|
||||
|
|
65
buildroot/share/PlatformIO/boards/blackSTM32F407VET6.json
Normal file
65
buildroot/share/PlatformIO/boards/blackSTM32F407VET6.json
Normal file
|
@ -0,0 +1,65 @@
|
|||
{
|
||||
"build": {
|
||||
"core": "stm32",
|
||||
"cpu": "cortex-m4",
|
||||
"extra_flags": "-DSTM32F407xx",
|
||||
"f_cpu": "168000000L",
|
||||
"hwids": [
|
||||
[
|
||||
"0x1EAF",
|
||||
"0x0003"
|
||||
],
|
||||
[
|
||||
"0x0483",
|
||||
"0x3748"
|
||||
]
|
||||
],
|
||||
"ldscript": "stm32f407xe.ld",
|
||||
"mcu": "stm32f407vet6",
|
||||
"variant": "MARLIN_F407VE"
|
||||
},
|
||||
"debug": {
|
||||
"jlink_device": "STM32F407VE",
|
||||
"openocd_target": "stm32f4x",
|
||||
"svd_path": "STM32F40x.svd",
|
||||
"tools": {
|
||||
"stlink": {
|
||||
"server": {
|
||||
"arguments": [
|
||||
"-f",
|
||||
"scripts/interface/stlink.cfg",
|
||||
"-c",
|
||||
"transport select hla_swd",
|
||||
"-f",
|
||||
"scripts/target/stm32f4x.cfg",
|
||||
"-c",
|
||||
"reset_config none"
|
||||
],
|
||||
"executable": "bin/openocd",
|
||||
"package": "tool-openocd"
|
||||
}
|
||||
}
|
||||
}
|
||||
},
|
||||
"frameworks": [
|
||||
"arduino",
|
||||
"stm32cube"
|
||||
],
|
||||
"name": "STM32F407VE (192k RAM. 512k Flash)",
|
||||
"upload": {
|
||||
"disable_flushing": false,
|
||||
"maximum_ram_size": 131072,
|
||||
"maximum_size": 514288,
|
||||
"protocol": "stlink",
|
||||
"protocols": [
|
||||
"stlink",
|
||||
"dfu",
|
||||
"jlink"
|
||||
],
|
||||
"require_upload_port": true,
|
||||
"use_1200bps_touch": false,
|
||||
"wait_for_upload_port": false
|
||||
},
|
||||
"url": "http://www.st.com/en/microcontrollers/stm32f407ve.html",
|
||||
"vendor": "Generic"
|
||||
}
|
29
buildroot/share/PlatformIO/scripts/black_stm32f407vet6.py
Normal file
29
buildroot/share/PlatformIO/scripts/black_stm32f407vet6.py
Normal file
|
@ -0,0 +1,29 @@
|
|||
import os,shutil
|
||||
from SCons.Script import DefaultEnvironment
|
||||
from platformio import util
|
||||
|
||||
env = DefaultEnvironment()
|
||||
platform = env.PioPlatform()
|
||||
board = env.BoardConfig()
|
||||
|
||||
FRAMEWORK_DIR = platform.get_package_dir("framework-arduinoststm32")
|
||||
CMSIS_DIR = os.path.join(FRAMEWORK_DIR, "CMSIS", "CMSIS")
|
||||
assert os.path.isdir(FRAMEWORK_DIR)
|
||||
assert os.path.isdir(CMSIS_DIR)
|
||||
assert os.path.isdir("buildroot/share/PlatformIO/variants")
|
||||
|
||||
mcu_type = board.get("build.mcu")[:-2]
|
||||
variant = board.get("build.variant")
|
||||
series = mcu_type[:7].upper() + "xx"
|
||||
variant_dir = os.path.join(FRAMEWORK_DIR, "variants", variant)
|
||||
|
||||
source_dir = os.path.join("buildroot/share/PlatformIO/variants", variant)
|
||||
assert os.path.isdir(source_dir)
|
||||
|
||||
if not os.path.isdir(variant_dir):
|
||||
os.mkdir(variant_dir)
|
||||
|
||||
for file_name in os.listdir(source_dir):
|
||||
full_file_name = os.path.join(source_dir, file_name)
|
||||
if os.path.isfile(full_file_name):
|
||||
shutil.copy(full_file_name, variant_dir)
|
|
@ -0,0 +1,438 @@
|
|||
/*
|
||||
*******************************************************************************
|
||||
* Copyright (c) 2019, STMicroelectronics
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
* 3. Neither the name of STMicroelectronics nor the names of its contributors
|
||||
* may be used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
|
||||
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
||||
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
|
||||
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
|
||||
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
|
||||
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
|
||||
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
|
||||
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*******************************************************************************
|
||||
* Automatically generated from STM32F407Z(E-G)Tx.xml
|
||||
*/
|
||||
#include "Arduino.h"
|
||||
#include "PeripheralPins.h"
|
||||
|
||||
/* =====
|
||||
* Note: Commented lines are alternative possibilities which are not used per default.
|
||||
* If you change them, you will have to know what you do
|
||||
* =====
|
||||
*/
|
||||
|
||||
//*** ADC ***
|
||||
|
||||
#ifdef HAL_ADC_MODULE_ENABLED
|
||||
const PinMap PinMap_ADC[] = {
|
||||
{PA_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC1_IN0
|
||||
// {PA_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC2_IN0
|
||||
// {PA_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC3_IN0
|
||||
{PA_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1
|
||||
// {PA_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC2_IN1
|
||||
// {PA_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC3_IN1
|
||||
// {PA_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2
|
||||
{PA_2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC2_IN2
|
||||
// {PA_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC3_IN2
|
||||
// {PA_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_IN3
|
||||
// {PA_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC2_IN3
|
||||
{PA_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC3_IN3
|
||||
{PA_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_IN4
|
||||
// {PA_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC2_IN4
|
||||
// {PA_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC1_IN5
|
||||
{PA_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC2_IN5
|
||||
#if defined(ARDUINO_BLACK_F407ZE) || defined(ARDUINO_BLACK_F407ZG)
|
||||
// {PA_6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_IN6
|
||||
// {PA_6, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC2_IN6
|
||||
// {PA_7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_IN7
|
||||
// {PA_7, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC2_IN7
|
||||
// {PB_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8
|
||||
#endif
|
||||
{PB_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC2_IN8
|
||||
{PB_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_IN9
|
||||
// {PB_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC2_IN9
|
||||
// {PC_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_IN10
|
||||
// {PC_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC2_IN10
|
||||
{PC_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC3_IN10
|
||||
{PC_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC1_IN11
|
||||
// {PC_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC2_IN11
|
||||
// {PC_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC3_IN11
|
||||
// {PC_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC1_IN12
|
||||
{PC_2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC2_IN12
|
||||
// {PC_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC3_IN12
|
||||
// {PC_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC1_IN13
|
||||
// {PC_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC2_IN13
|
||||
{PC_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC3_IN13
|
||||
// {PC_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_IN14
|
||||
{PC_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC2_IN14
|
||||
// {PC_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15
|
||||
{PC_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC2_IN15
|
||||
#if defined(ARDUINO_BLACK_F407ZE) || defined(ARDUINO_BLACK_F407ZG)
|
||||
// {PF_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC3_IN9
|
||||
// {PF_4, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC3_IN14
|
||||
// {PF_5, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC3_IN15
|
||||
{PF_6, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC3_IN4
|
||||
{PF_7, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC3_IN5
|
||||
{PF_8, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC3_IN6
|
||||
// {PF_9, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC3_IN7
|
||||
// {PF_10, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC3_IN8
|
||||
#endif
|
||||
{NC, NP, 0}
|
||||
};
|
||||
#endif
|
||||
|
||||
//*** DAC ***
|
||||
|
||||
#ifdef HAL_DAC_MODULE_ENABLED
|
||||
const PinMap PinMap_DAC[] = {
|
||||
{PA_4, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // DAC_OUT1
|
||||
{PA_5, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // DAC_OUT2
|
||||
{NC, NP, 0}
|
||||
};
|
||||
#endif
|
||||
|
||||
//*** I2C ***
|
||||
|
||||
#ifdef HAL_I2C_MODULE_ENABLED
|
||||
const PinMap PinMap_I2C_SDA[] = {
|
||||
{PB_7, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)},
|
||||
{PB_9, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)},
|
||||
{PB_11, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)},
|
||||
{PC_9, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)},
|
||||
#if defined(ARDUINO_BLACK_F407ZE) || defined(ARDUINO_BLACK_F407ZG)
|
||||
{PF_0, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)},
|
||||
#endif
|
||||
{NC, NP, 0}
|
||||
};
|
||||
#endif
|
||||
|
||||
#ifdef HAL_I2C_MODULE_ENABLED
|
||||
const PinMap PinMap_I2C_SCL[] = {
|
||||
{PA_8, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)},
|
||||
{PB_6, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)},
|
||||
{PB_8, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)},
|
||||
{PB_10, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)},
|
||||
#if defined(ARDUINO_BLACK_F407ZE) || defined(ARDUINO_BLACK_F407ZG)
|
||||
{PF_1, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)},
|
||||
#endif
|
||||
{NC, NP, 0}
|
||||
};
|
||||
#endif
|
||||
|
||||
//*** PWM ***
|
||||
|
||||
#ifdef HAL_TIM_MODULE_ENABLED
|
||||
const PinMap PinMap_PWM[] = {
|
||||
{PA_0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1
|
||||
// {PA_0, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1
|
||||
{PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2
|
||||
// {PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2
|
||||
{PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3
|
||||
// {PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3
|
||||
// {PA_2, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1
|
||||
{PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4
|
||||
// {PA_3, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 4, 0)}, // TIM5_CH4
|
||||
// {PA_3, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2
|
||||
{PA_5, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1
|
||||
// {PA_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N
|
||||
{PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1
|
||||
// {PA_6, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1
|
||||
// {PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N
|
||||
{PA_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2
|
||||
// {PA_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N
|
||||
// {PA_7, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1
|
||||
{PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1
|
||||
{PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2
|
||||
{PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3
|
||||
{PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4
|
||||
// {PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1
|
||||
// {PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N
|
||||
{PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3
|
||||
// {PB_0, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N
|
||||
// {PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N
|
||||
{PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4
|
||||
// {PB_1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N
|
||||
// {PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2
|
||||
{PB_4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1
|
||||
{PB_5, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2
|
||||
{PB_6, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1
|
||||
{PB_7, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2
|
||||
{PB_8, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3
|
||||
{PB_8, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1
|
||||
{PB_9, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4
|
||||
{PB_9, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1
|
||||
{PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3
|
||||
{PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4
|
||||
{PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N
|
||||
{PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N
|
||||
{PB_14, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N
|
||||
{PB_14, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 1, 0)}, // TIM12_CH1
|
||||
{PB_15, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N
|
||||
{PB_15, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N
|
||||
{PB_15, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 2, 0)}, // TIM12_CH2
|
||||
{PC_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1
|
||||
{PC_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1
|
||||
{PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2
|
||||
{PC_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2
|
||||
{PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3
|
||||
{PC_8, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 0)}, // TIM8_CH3
|
||||
{PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4
|
||||
{PC_9, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 4, 0)}, // TIM8_CH4
|
||||
{PD_12, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1
|
||||
{PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2
|
||||
{PD_14, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3
|
||||
{PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4
|
||||
{PE_5, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1
|
||||
{PE_6, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2
|
||||
{PE_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N
|
||||
{PE_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1
|
||||
{PE_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N
|
||||
{PE_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2
|
||||
{PE_12, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N
|
||||
{PE_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3
|
||||
{PE_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4
|
||||
#if defined(ARDUINO_BLACK_F407ZE) || defined(ARDUINO_BLACK_F407ZG)
|
||||
{PF_6, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1
|
||||
{PF_7, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1
|
||||
{PF_8, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1
|
||||
{PF_9, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1
|
||||
#endif
|
||||
{NC, NP, 0}
|
||||
};
|
||||
#endif
|
||||
|
||||
//*** SERIAL ***
|
||||
|
||||
#ifdef HAL_UART_MODULE_ENABLED
|
||||
const PinMap PinMap_UART_TX[] = {
|
||||
{PA_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)},
|
||||
{PA_2, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
|
||||
{PA_9, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
|
||||
{PB_6, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
|
||||
{PB_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
|
||||
{PC_6, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)},
|
||||
// {PC_10, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)},
|
||||
{PC_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
|
||||
{PC_12, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)},
|
||||
{PD_5, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
|
||||
{PD_8, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
|
||||
#if defined(ARDUINO_BLACK_F407ZE) || defined(ARDUINO_BLACK_F407ZG)
|
||||
// {PG_14, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)},
|
||||
#endif
|
||||
{NC, NP, 0}
|
||||
};
|
||||
#endif
|
||||
|
||||
#ifdef HAL_UART_MODULE_ENABLED
|
||||
const PinMap PinMap_UART_RX[] = {
|
||||
{PA_1, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)},
|
||||
{PA_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
|
||||
{PA_10, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
|
||||
{PB_7, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
|
||||
{PB_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
|
||||
{PC_7, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)},
|
||||
// {PC_11, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)},
|
||||
{PC_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
|
||||
{PD_2, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)},
|
||||
{PD_6, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
|
||||
{PD_9, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
|
||||
#if defined(ARDUINO_BLACK_F407ZE) || defined(ARDUINO_BLACK_F407ZG)
|
||||
// {PG_9, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)},
|
||||
#endif
|
||||
{NC, NP, 0}
|
||||
};
|
||||
#endif
|
||||
|
||||
#ifdef HAL_UART_MODULE_ENABLED
|
||||
const PinMap PinMap_UART_RTS[] = {
|
||||
{PA_1, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
|
||||
{PA_12, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
|
||||
{PB_14, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
|
||||
{PD_4, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
|
||||
{PD_12, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
|
||||
#if defined(ARDUINO_BLACK_F407ZE) || defined(ARDUINO_BLACK_F407ZG)
|
||||
{PG_8, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)},
|
||||
{PG_12, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)},
|
||||
#endif
|
||||
{NC, NP, 0}
|
||||
};
|
||||
#endif
|
||||
|
||||
#ifdef HAL_UART_MODULE_ENABLED
|
||||
const PinMap PinMap_UART_CTS[] = {
|
||||
{PA_0, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
|
||||
{PA_11, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
|
||||
{PB_13, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
|
||||
{PD_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
|
||||
{PD_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
|
||||
#if defined(ARDUINO_BLACK_F407ZE) || defined(ARDUINO_BLACK_F407ZG)
|
||||
{PG_13, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)},
|
||||
{PG_15, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)},
|
||||
#endif
|
||||
{NC, NP, 0}
|
||||
};
|
||||
#endif
|
||||
|
||||
//*** SPI ***
|
||||
|
||||
#ifdef HAL_SPI_MODULE_ENABLED
|
||||
const PinMap PinMap_SPI_MOSI[] = {
|
||||
{PA_7, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
|
||||
{PB_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
|
||||
{PB_5, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
|
||||
{PB_15, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
|
||||
{PC_3, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
|
||||
{PC_12, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
|
||||
{NC, NP, 0}
|
||||
};
|
||||
#endif
|
||||
|
||||
#ifdef HAL_SPI_MODULE_ENABLED
|
||||
const PinMap PinMap_SPI_MISO[] = {
|
||||
{PA_6, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
|
||||
{PB_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
|
||||
{PB_4, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
|
||||
{PB_14, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
|
||||
{PC_2, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
|
||||
{PC_11, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
|
||||
{NC, NP, 0}
|
||||
};
|
||||
#endif
|
||||
|
||||
#ifdef HAL_SPI_MODULE_ENABLED
|
||||
const PinMap PinMap_SPI_SCLK[] = {
|
||||
{PA_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
|
||||
{PB_3, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
|
||||
{PB_3, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
|
||||
{PB_10, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
|
||||
{PB_13, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
|
||||
{PC_10, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
|
||||
{NC, NP, 0}
|
||||
};
|
||||
#endif
|
||||
|
||||
#ifdef HAL_SPI_MODULE_ENABLED
|
||||
const PinMap PinMap_SPI_SSEL[] = {
|
||||
{PA_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
|
||||
{PA_4, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
|
||||
{PA_15, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
|
||||
{PA_15, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
|
||||
{PB_9, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
|
||||
{PB_12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
|
||||
{NC, NP, 0}
|
||||
};
|
||||
#endif
|
||||
|
||||
//*** CAN ***
|
||||
|
||||
#ifdef HAL_CAN_MODULE_ENABLED
|
||||
const PinMap PinMap_CAN_RD[] = {
|
||||
{PA_11, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)},
|
||||
{PB_5, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)},
|
||||
{PB_8, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)},
|
||||
{PB_12, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)},
|
||||
{PD_0, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)},
|
||||
{NC, NP, 0}
|
||||
};
|
||||
#endif
|
||||
|
||||
#ifdef HAL_CAN_MODULE_ENABLED
|
||||
const PinMap PinMap_CAN_TD[] = {
|
||||
{PA_12, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)},
|
||||
{PB_6, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)},
|
||||
{PB_9, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)},
|
||||
{PB_13, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)},
|
||||
{PD_1, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)},
|
||||
{NC, NP, 0}
|
||||
};
|
||||
#endif
|
||||
|
||||
//*** ETHERNET ***
|
||||
|
||||
#ifdef HAL_ETH_MODULE_ENABLED
|
||||
const PinMap PinMap_Ethernet[] = {
|
||||
{PA_0, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_CRS
|
||||
{PA_1, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_REF_CLK|ETH_RX_CLK
|
||||
{PA_2, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_MDIO
|
||||
{PA_3, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_COL
|
||||
{PA_7, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_CRS_DV|ETH_RX_DV
|
||||
{PB_0, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD2
|
||||
{PB_1, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD3
|
||||
{PB_5, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_PPS_OUT
|
||||
{PB_8, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD3
|
||||
{PB_10, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RX_ER
|
||||
{PB_11, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TX_EN
|
||||
{PB_12, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD0
|
||||
{PB_13, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD1
|
||||
{PC_1, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_MDC
|
||||
{PC_2, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD2
|
||||
{PC_3, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TX_CLK
|
||||
{PC_4, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD0
|
||||
{PC_5, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD1
|
||||
{PE_2, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD3
|
||||
#if defined(ARDUINO_BLACK_F407ZE) || defined(ARDUINO_BLACK_F407ZG)
|
||||
{PG_8, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_PPS_OUT
|
||||
{PG_11, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TX_EN
|
||||
{PG_13, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD0
|
||||
{PG_14, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD1
|
||||
#endif
|
||||
{NC, NP, 0}
|
||||
};
|
||||
#endif
|
||||
|
||||
//*** No QUADSPI ***
|
||||
|
||||
//*** USB ***
|
||||
|
||||
#ifdef HAL_PCD_MODULE_ENABLED
|
||||
const PinMap PinMap_USB_OTG_FS[] = {
|
||||
// {PA_8, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_SOF
|
||||
// {PA_9, USB_OTG_FS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_FS_VBUS
|
||||
// {PA_10, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_ID
|
||||
{PA_11, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DM
|
||||
{PA_12, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DP
|
||||
{NC, NP, 0}
|
||||
};
|
||||
#endif
|
||||
|
||||
#ifdef HAL_PCD_MODULE_ENABLED
|
||||
const PinMap PinMap_USB_OTG_HS[] = {
|
||||
#ifdef USE_USB_HS_IN_FS
|
||||
{PA_4, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_SOF
|
||||
{PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_ID
|
||||
{PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_HS_VBUS
|
||||
{PB_14, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DM
|
||||
{PB_15, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DP
|
||||
#else
|
||||
{PA_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D0
|
||||
{PA_5, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_CK
|
||||
{PB_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D1
|
||||
{PB_1, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D2
|
||||
{PB_5, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D7
|
||||
{PB_10, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D3
|
||||
{PB_11, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D4
|
||||
{PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D5
|
||||
{PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D6
|
||||
{PC_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_STP
|
||||
{PC_2, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_DIR
|
||||
{PC_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_NXT
|
||||
#endif /* USE_USB_HS_IN_FS */
|
||||
{NC, NP, 0}
|
||||
};
|
||||
#endif
|
|
@ -0,0 +1,50 @@
|
|||
/* SYS_WKUP */
|
||||
#ifdef PWR_WAKEUP_PIN1
|
||||
SYS_WKUP1 = PA_0,
|
||||
#endif
|
||||
#ifdef PWR_WAKEUP_PIN2
|
||||
SYS_WKUP2 = NC,
|
||||
#endif
|
||||
#ifdef PWR_WAKEUP_PIN3
|
||||
SYS_WKUP3 = NC,
|
||||
#endif
|
||||
#ifdef PWR_WAKEUP_PIN4
|
||||
SYS_WKUP4 = NC,
|
||||
#endif
|
||||
#ifdef PWR_WAKEUP_PIN5
|
||||
SYS_WKUP5 = NC,
|
||||
#endif
|
||||
#ifdef PWR_WAKEUP_PIN6
|
||||
SYS_WKUP6 = NC,
|
||||
#endif
|
||||
#ifdef PWR_WAKEUP_PIN7
|
||||
SYS_WKUP7 = NC,
|
||||
#endif
|
||||
#ifdef PWR_WAKEUP_PIN8
|
||||
SYS_WKUP8 = NC,
|
||||
#endif
|
||||
/* USB */
|
||||
#ifdef USBCON
|
||||
USB_OTG_FS_SOF = PA_8,
|
||||
USB_OTG_FS_VBUS = PA_9,
|
||||
USB_OTG_FS_ID = PA_10,
|
||||
USB_OTG_FS_DM = PA_11,
|
||||
USB_OTG_FS_DP = PA_12,
|
||||
USB_OTG_HS_ULPI_D0 = PA_3,
|
||||
USB_OTG_HS_SOF = PA_4,
|
||||
USB_OTG_HS_ULPI_CK = PA_5,
|
||||
USB_OTG_HS_ULPI_D1 = PB_0,
|
||||
USB_OTG_HS_ULPI_D2 = PB_1,
|
||||
USB_OTG_HS_ULPI_D7 = PB_5,
|
||||
USB_OTG_HS_ULPI_D3 = PB_10,
|
||||
USB_OTG_HS_ULPI_D4 = PB_11,
|
||||
USB_OTG_HS_ID = PB_12,
|
||||
USB_OTG_HS_ULPI_D5 = PB_12,
|
||||
USB_OTG_HS_ULPI_D6 = PB_13,
|
||||
USB_OTG_HS_VBUS = PB_13,
|
||||
USB_OTG_HS_DM = PB_14,
|
||||
USB_OTG_HS_DP = PB_15,
|
||||
USB_OTG_HS_ULPI_STP = PC_0,
|
||||
USB_OTG_HS_ULPI_DIR = PC_2,
|
||||
USB_OTG_HS_ULPI_NXT = PC_3,
|
||||
#endif
|
184
buildroot/share/PlatformIO/variants/MARLIN_F407VE/ldscript.ld
Normal file
184
buildroot/share/PlatformIO/variants/MARLIN_F407VE/ldscript.ld
Normal file
|
@ -0,0 +1,184 @@
|
|||
/*
|
||||
*****************************************************************************
|
||||
**
|
||||
** File : LinkerScript.ld
|
||||
**
|
||||
** Abstract : Linker script for STM32F407VETx Device with
|
||||
** 512KByte FLASH, 128KByte RAM
|
||||
**
|
||||
** Set heap size, stack size and stack location according
|
||||
** to application requirements.
|
||||
**
|
||||
** Set memory bank area and size if external memory is used.
|
||||
**
|
||||
** Target : STMicroelectronics STM32
|
||||
**
|
||||
**
|
||||
** Distribution: The file is distributed as is, without any warranty
|
||||
** of any kind.
|
||||
**
|
||||
** (c)Copyright Ac6.
|
||||
** You may use this file as-is or modify it according to the needs of your
|
||||
** project. Distribution of this file (unmodified or modified) is not
|
||||
** permitted. Ac6 permit registered System Workbench for MCU users the
|
||||
** rights to distribute the assembled, compiled & linked contents of this
|
||||
** file as part of an application binary file, provided that it is built
|
||||
** using the System Workbench for MCU toolchain.
|
||||
**
|
||||
*****************************************************************************
|
||||
*/
|
||||
|
||||
/* Entry Point */
|
||||
ENTRY(Reset_Handler)
|
||||
|
||||
/* Highest address of the user mode stack */
|
||||
_estack = 0x20020000; /* end of RAM */
|
||||
/* Generate a link error if heap and stack don't fit into RAM */
|
||||
_Min_Heap_Size = 0x200; /* required amount of heap */
|
||||
_Min_Stack_Size = 0x400; /* required amount of stack */
|
||||
|
||||
/* Specify the memory areas */
|
||||
MEMORY
|
||||
{
|
||||
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K
|
||||
CCMRAM (rw) : ORIGIN = 0x10000000, LENGTH = 64K
|
||||
FLASH (rx) : ORIGIN = 0x8000000, LENGTH = 512K
|
||||
}
|
||||
|
||||
/* Define output sections */
|
||||
SECTIONS
|
||||
{
|
||||
/* The startup code goes first into FLASH */
|
||||
.isr_vector :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
KEEP(*(.isr_vector)) /* Startup code */
|
||||
. = ALIGN(4);
|
||||
} >FLASH
|
||||
|
||||
/* The program code and other data goes into FLASH */
|
||||
.text ALIGN(8):
|
||||
{
|
||||
. = ALIGN(4);
|
||||
*(.text) /* .text sections (code) */
|
||||
*(.text*) /* .text* sections (code) */
|
||||
*(.glue_7) /* glue arm to thumb code */
|
||||
*(.glue_7t) /* glue thumb to arm code */
|
||||
*(.eh_frame)
|
||||
|
||||
KEEP (*(.init))
|
||||
KEEP (*(.fini))
|
||||
|
||||
. = ALIGN(4);
|
||||
_etext = .; /* define a global symbols at end of code */
|
||||
} >FLASH
|
||||
|
||||
/* Constant data goes into FLASH */
|
||||
.rodata ALIGN(4):
|
||||
{
|
||||
. = ALIGN(4);
|
||||
*(.rodata) /* .rodata sections (constants, strings, etc.) */
|
||||
*(.rodata*) /* .rodata* sections (constants, strings, etc.) */
|
||||
. = ALIGN(4);
|
||||
} >FLASH
|
||||
|
||||
.ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
|
||||
.ARM : {
|
||||
__exidx_start = .;
|
||||
*(.ARM.exidx*)
|
||||
__exidx_end = .;
|
||||
} >FLASH
|
||||
|
||||
.preinit_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__preinit_array_start = .);
|
||||
KEEP (*(.preinit_array*))
|
||||
PROVIDE_HIDDEN (__preinit_array_end = .);
|
||||
} >FLASH
|
||||
.init_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__init_array_start = .);
|
||||
KEEP (*(SORT(.init_array.*)))
|
||||
KEEP (*(.init_array*))
|
||||
PROVIDE_HIDDEN (__init_array_end = .);
|
||||
} >FLASH
|
||||
.fini_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__fini_array_start = .);
|
||||
KEEP (*(SORT(.fini_array.*)))
|
||||
KEEP (*(.fini_array*))
|
||||
PROVIDE_HIDDEN (__fini_array_end = .);
|
||||
} >FLASH
|
||||
|
||||
/* used by the startup to initialize data */
|
||||
_sidata = LOADADDR(.data);
|
||||
|
||||
/* Initialized data sections goes into RAM, load LMA copy after code */
|
||||
.data :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_sdata = .; /* create a global symbol at data start */
|
||||
*(.data) /* .data sections */
|
||||
*(.data*) /* .data* sections */
|
||||
|
||||
. = ALIGN(4);
|
||||
_edata = .; /* define a global symbol at data end */
|
||||
} >RAM AT> FLASH
|
||||
|
||||
_siccmram = LOADADDR(.ccmram);
|
||||
|
||||
/* CCM-RAM section
|
||||
*
|
||||
* IMPORTANT NOTE!
|
||||
* If initialized variables will be placed in this section,
|
||||
* the startup code needs to be modified to copy the init-values.
|
||||
*/
|
||||
.ccmram :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_sccmram = .; /* create a global symbol at ccmram start */
|
||||
*(.ccmram)
|
||||
*(.ccmram*)
|
||||
|
||||
. = ALIGN(4);
|
||||
_eccmram = .; /* create a global symbol at ccmram end */
|
||||
} >CCMRAM AT> FLASH
|
||||
|
||||
|
||||
/* Uninitialized data section */
|
||||
. = ALIGN(4);
|
||||
.bss :
|
||||
{
|
||||
/* This is used by the startup in order to initialize the .bss secion */
|
||||
_sbss = .; /* define a global symbol at bss start */
|
||||
__bss_start__ = _sbss;
|
||||
*(.bss)
|
||||
*(.bss*)
|
||||
*(COMMON)
|
||||
|
||||
. = ALIGN(4);
|
||||
_ebss = .; /* define a global symbol at bss end */
|
||||
__bss_end__ = _ebss;
|
||||
} >RAM
|
||||
|
||||
/* User_heap_stack section, used to check that there is enough RAM left */
|
||||
._user_heap_stack :
|
||||
{
|
||||
. = ALIGN(8);
|
||||
PROVIDE ( end = . );
|
||||
PROVIDE ( _end = . );
|
||||
. = . + _Min_Heap_Size;
|
||||
. = . + _Min_Stack_Size;
|
||||
. = ALIGN(8);
|
||||
} >RAM
|
||||
|
||||
/* Remove information from the standard libraries */
|
||||
/DISCARD/ :
|
||||
{
|
||||
libc.a ( * )
|
||||
libm.a ( * )
|
||||
libgcc.a ( * )
|
||||
}
|
||||
|
||||
.ARM.attributes 0 : { *(.ARM.attributes) }
|
||||
}
|
|
@ -0,0 +1,481 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file stm32f4xx_hal_conf.h
|
||||
* @brief HAL configuration file.
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© Copyright (c) 2017 STMicroelectronics.
|
||||
* All rights reserved.</center></h2>
|
||||
*
|
||||
* This software component is licensed by ST under BSD 3-Clause license,
|
||||
* the "License"; You may not use this file except in compliance with the
|
||||
* License. You may obtain a copy of the License at:
|
||||
* opensource.org/licenses/BSD-3-Clause
|
||||
*
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef __STM32F4xx_HAL_CONF_H
|
||||
#define __STM32F4xx_HAL_CONF_H
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
|
||||
/* ########################## Module Selection ############################## */
|
||||
/**
|
||||
* @brief This is the list of modules to be used in the HAL driver
|
||||
*/
|
||||
#define HAL_MODULE_ENABLED
|
||||
#define HAL_ADC_MODULE_ENABLED
|
||||
/* #define HAL_CAN_MODULE_ENABLED */
|
||||
/* #define HAL_CAN_LEGACY_MODULE_ENABLED */
|
||||
#define HAL_CRC_MODULE_ENABLED
|
||||
/* #define HAL_CEC_MODULE_ENABLED */
|
||||
/* #define HAL_CRYP_MODULE_ENABLED */
|
||||
#define HAL_DAC_MODULE_ENABLED
|
||||
/* #define HAL_DCMI_MODULE_ENABLED */
|
||||
#define HAL_DMA_MODULE_ENABLED
|
||||
/* #define HAL_DMA2D_MODULE_ENABLED */
|
||||
/* #define HAL_ETH_MODULE_ENABLED */
|
||||
#define HAL_FLASH_MODULE_ENABLED
|
||||
/* #define HAL_NAND_MODULE_ENABLED */
|
||||
/* #define HAL_NOR_MODULE_ENABLED */
|
||||
/* #define HAL_PCCARD_MODULE_ENABLED */
|
||||
/* #define HAL_SRAM_MODULE_ENABLED */
|
||||
/* #define HAL_SDRAM_MODULE_ENABLED */
|
||||
/* #define HAL_HASH_MODULE_ENABLED */
|
||||
#define HAL_GPIO_MODULE_ENABLED
|
||||
/* #define HAL_EXTI_MODULE_ENABLED */
|
||||
#define HAL_I2C_MODULE_ENABLED
|
||||
/* #define HAL_SMBUS_MODULE_ENABLED */
|
||||
/* #define HAL_I2S_MODULE_ENABLED */
|
||||
/* #define HAL_IWDG_MODULE_ENABLED */
|
||||
/* #define HAL_LTDC_MODULE_ENABLED */
|
||||
/* #define HAL_DSI_MODULE_ENABLED */
|
||||
#define HAL_PWR_MODULE_ENABLED
|
||||
/* #define HAL_QSPI_MODULE_ENABLED */
|
||||
#define HAL_RCC_MODULE_ENABLED
|
||||
/* #define HAL_RNG_MODULE_ENABLED */
|
||||
#define HAL_RTC_MODULE_ENABLED
|
||||
/* #define HAL_SAI_MODULE_ENABLED */
|
||||
#define HAL_SD_MODULE_ENABLED
|
||||
#define HAL_SPI_MODULE_ENABLED
|
||||
#define HAL_TIM_MODULE_ENABLED
|
||||
/* #define HAL_UART_MODULE_ENABLED */
|
||||
/* #define HAL_USART_MODULE_ENABLED */
|
||||
/* #define HAL_IRDA_MODULE_ENABLED */
|
||||
/* #define HAL_SMARTCARD_MODULE_ENABLED */
|
||||
/* #define HAL_WWDG_MODULE_ENABLED */
|
||||
#define HAL_CORTEX_MODULE_ENABLED
|
||||
#define HAL_PCD_MODULE_ENABLED
|
||||
/* #define HAL_HCD_MODULE_ENABLED */
|
||||
/* #define HAL_FMPI2C_MODULE_ENABLED */
|
||||
/* #define HAL_SPDIFRX_MODULE_ENABLED */
|
||||
/* #define HAL_DFSDM_MODULE_ENABLED */
|
||||
/* #define HAL_LPTIM_MODULE_ENABLED */
|
||||
/* #define HAL_MMC_MODULE_ENABLED */
|
||||
|
||||
/* ########################## HSE/HSI Values adaptation ##################### */
|
||||
/**
|
||||
* @brief Adjust the value of External High Speed oscillator (HSE) used in your application.
|
||||
* This value is used by the RCC HAL module to compute the system frequency
|
||||
* (when HSE is used as system clock source, directly or through the PLL).
|
||||
*/
|
||||
#if !defined (HSE_VALUE)
|
||||
#define HSE_VALUE ((uint32_t)8000000U) /*!< Value of the External oscillator in Hz */
|
||||
#endif /* HSE_VALUE */
|
||||
|
||||
#if !defined (HSE_STARTUP_TIMEOUT)
|
||||
#define HSE_STARTUP_TIMEOUT ((uint32_t)100U) /*!< Time out for HSE start up, in ms */
|
||||
#endif /* HSE_STARTUP_TIMEOUT */
|
||||
|
||||
/**
|
||||
* @brief Internal High Speed oscillator (HSI) value.
|
||||
* This value is used by the RCC HAL module to compute the system frequency
|
||||
* (when HSI is used as system clock source, directly or through the PLL).
|
||||
*/
|
||||
#if !defined (HSI_VALUE)
|
||||
#define HSI_VALUE ((uint32_t)16000000U) /*!< Value of the Internal oscillator in Hz*/
|
||||
#endif /* HSI_VALUE */
|
||||
|
||||
/**
|
||||
* @brief Internal Low Speed oscillator (LSI) value.
|
||||
*/
|
||||
#if !defined (LSI_VALUE)
|
||||
#define LSI_VALUE ((uint32_t)32000U) /*!< LSI Typical Value in Hz*/
|
||||
#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz
|
||||
The real value may vary depending on the variations
|
||||
in voltage and temperature.*/
|
||||
/**
|
||||
* @brief External Low Speed oscillator (LSE) value.
|
||||
*/
|
||||
#if !defined (LSE_VALUE)
|
||||
#define LSE_VALUE ((uint32_t)32768U) /*!< Value of the External Low Speed oscillator in Hz */
|
||||
#endif /* LSE_VALUE */
|
||||
|
||||
#if !defined (LSE_STARTUP_TIMEOUT)
|
||||
#define LSE_STARTUP_TIMEOUT ((uint32_t)5000U) /*!< Time out for LSE start up, in ms */
|
||||
#endif /* LSE_STARTUP_TIMEOUT */
|
||||
|
||||
/**
|
||||
* @brief External clock source for I2S peripheral
|
||||
* This value is used by the I2S HAL module to compute the I2S clock source
|
||||
* frequency, this source is inserted directly through I2S_CKIN pad.
|
||||
*/
|
||||
#if !defined (EXTERNAL_CLOCK_VALUE)
|
||||
#define EXTERNAL_CLOCK_VALUE ((uint32_t)12288000U) /*!< Value of the External audio frequency in Hz*/
|
||||
#endif /* EXTERNAL_CLOCK_VALUE */
|
||||
|
||||
/* Tip: To avoid modifying this file each time you need to use different HSE,
|
||||
=== you can define the HSE value in your toolchain compiler preprocessor. */
|
||||
|
||||
/* ########################### System Configuration ######################### */
|
||||
/**
|
||||
* @brief This is the HAL system configuration section
|
||||
*/
|
||||
#define VDD_VALUE ((uint32_t)3300U) /*!< Value of VDD in mv */
|
||||
#define TICK_INT_PRIORITY ((uint32_t)0U) /*!< tick interrupt priority */
|
||||
#define USE_RTOS 0U
|
||||
#define PREFETCH_ENABLE 1U
|
||||
#define INSTRUCTION_CACHE_ENABLE 1U
|
||||
#define DATA_CACHE_ENABLE 1U
|
||||
|
||||
#define USE_HAL_ADC_REGISTER_CALLBACKS 0U /* ADC register callback disabled */
|
||||
#define USE_HAL_CAN_REGISTER_CALLBACKS 0U /* CAN register callback disabled */
|
||||
#define USE_HAL_CEC_REGISTER_CALLBACKS 0U /* CEC register callback disabled */
|
||||
#define USE_HAL_CRYP_REGISTER_CALLBACKS 0U /* CRYP register callback disabled */
|
||||
#define USE_HAL_DAC_REGISTER_CALLBACKS 0U /* DAC register callback disabled */
|
||||
#define USE_HAL_DCMI_REGISTER_CALLBACKS 0U /* DCMI register callback disabled */
|
||||
#define USE_HAL_DFSDM_REGISTER_CALLBACKS 0U /* DFSDM register callback disabled */
|
||||
#define USE_HAL_DMA2D_REGISTER_CALLBACKS 0U /* DMA2D register callback disabled */
|
||||
#define USE_HAL_DSI_REGISTER_CALLBACKS 0U /* DSI register callback disabled */
|
||||
#define USE_HAL_ETH_REGISTER_CALLBACKS 0U /* ETH register callback disabled */
|
||||
#define USE_HAL_HASH_REGISTER_CALLBACKS 0U /* HASH register callback disabled */
|
||||
#define USE_HAL_HCD_REGISTER_CALLBACKS 0U /* HCD register callback disabled */
|
||||
#define USE_HAL_I2C_REGISTER_CALLBACKS 0U /* I2C register callback disabled */
|
||||
#define USE_HAL_FMPI2C_REGISTER_CALLBACKS 0U /* FMPI2C register callback disabled */
|
||||
#define USE_HAL_I2S_REGISTER_CALLBACKS 0U /* I2S register callback disabled */
|
||||
#define USE_HAL_IRDA_REGISTER_CALLBACKS 0U /* IRDA register callback disabled */
|
||||
#define USE_HAL_LPTIM_REGISTER_CALLBACKS 0U /* LPTIM register callback disabled */
|
||||
#define USE_HAL_LTDC_REGISTER_CALLBACKS 0U /* LTDC register callback disabled */
|
||||
#define USE_HAL_MMC_REGISTER_CALLBACKS 0U /* MMC register callback disabled */
|
||||
#define USE_HAL_NAND_REGISTER_CALLBACKS 0U /* NAND register callback disabled */
|
||||
#define USE_HAL_NOR_REGISTER_CALLBACKS 0U /* NOR register callback disabled */
|
||||
#define USE_HAL_PCCARD_REGISTER_CALLBACKS 0U /* PCCARD register callback disabled */
|
||||
#define USE_HAL_PCD_REGISTER_CALLBACKS 0U /* PCD register callback disabled */
|
||||
#define USE_HAL_QSPI_REGISTER_CALLBACKS 0U /* QSPI register callback disabled */
|
||||
#define USE_HAL_RNG_REGISTER_CALLBACKS 0U /* RNG register callback disabled */
|
||||
#define USE_HAL_RTC_REGISTER_CALLBACKS 0U /* RTC register callback disabled */
|
||||
#define USE_HAL_SAI_REGISTER_CALLBACKS 0U /* SAI register callback disabled */
|
||||
#define USE_HAL_SD_REGISTER_CALLBACKS 0U /* SD register callback disabled */
|
||||
#define USE_HAL_SMARTCARD_REGISTER_CALLBACKS 0U /* SMARTCARD register callback disabled */
|
||||
#define USE_HAL_SDRAM_REGISTER_CALLBACKS 0U /* SDRAM register callback disabled */
|
||||
#define USE_HAL_SRAM_REGISTER_CALLBACKS 0U /* SRAM register callback disabled */
|
||||
#define USE_HAL_SPDIFRX_REGISTER_CALLBACKS 0U /* SPDIFRX register callback disabled */
|
||||
#define USE_HAL_SMBUS_REGISTER_CALLBACKS 0U /* SMBUS register callback disabled */
|
||||
#define USE_HAL_SPI_REGISTER_CALLBACKS 0U /* SPI register callback disabled */
|
||||
#define USE_HAL_TIM_REGISTER_CALLBACKS 0U /* TIM register callback disabled */
|
||||
#define USE_HAL_UART_REGISTER_CALLBACKS 0U /* UART register callback disabled */
|
||||
#define USE_HAL_USART_REGISTER_CALLBACKS 0U /* USART register callback disabled */
|
||||
#define USE_HAL_WWDG_REGISTER_CALLBACKS 0U /* WWDG register callback disabled */
|
||||
|
||||
/* ########################## Assert Selection ############################## */
|
||||
/**
|
||||
* @brief Uncomment the line below to expanse the "assert_param" macro in the
|
||||
* HAL drivers code
|
||||
*/
|
||||
/* #define USE_FULL_ASSERT 1U */
|
||||
|
||||
/* ################## Ethernet peripheral configuration ##################### */
|
||||
|
||||
/* Section 1 : Ethernet peripheral configuration */
|
||||
|
||||
/* MAC ADDRESS: MAC_ADDR0:MAC_ADDR1:MAC_ADDR2:MAC_ADDR3:MAC_ADDR4:MAC_ADDR5 */
|
||||
#define MAC_ADDR0 2U
|
||||
#define MAC_ADDR1 0U
|
||||
#define MAC_ADDR2 0U
|
||||
#define MAC_ADDR3 0U
|
||||
#define MAC_ADDR4 0U
|
||||
#define MAC_ADDR5 0U
|
||||
|
||||
/* Definition of the Ethernet driver buffers size and count */
|
||||
#define ETH_RX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for receive */
|
||||
#define ETH_TX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for transmit */
|
||||
#define ETH_RXBUFNB ((uint32_t)4U) /* 4 Rx buffers of size ETH_RX_BUF_SIZE */
|
||||
#define ETH_TXBUFNB ((uint32_t)4U) /* 4 Tx buffers of size ETH_TX_BUF_SIZE */
|
||||
|
||||
/* Section 2: PHY configuration section */
|
||||
|
||||
/* DP83848_PHY_ADDRESS Address*/
|
||||
#define DP83848_PHY_ADDRESS 0x01U
|
||||
/* PHY Reset delay these values are based on a 1 ms Systick interrupt*/
|
||||
#define PHY_RESET_DELAY ((uint32_t)0x000000FFU)
|
||||
/* PHY Configuration delay */
|
||||
#define PHY_CONFIG_DELAY ((uint32_t)0x00000FFFU)
|
||||
|
||||
#define PHY_READ_TO ((uint32_t)0x0000FFFFU)
|
||||
#define PHY_WRITE_TO ((uint32_t)0x0000FFFFU)
|
||||
|
||||
/* Section 3: Common PHY Registers */
|
||||
|
||||
#define PHY_BCR ((uint16_t)0x0000U) /*!< Transceiver Basic Control Register */
|
||||
#define PHY_BSR ((uint16_t)0x0001U) /*!< Transceiver Basic Status Register */
|
||||
|
||||
#define PHY_RESET ((uint16_t)0x8000U) /*!< PHY Reset */
|
||||
#define PHY_LOOPBACK ((uint16_t)0x4000U) /*!< Select loop-back mode */
|
||||
#define PHY_FULLDUPLEX_100M ((uint16_t)0x2100U) /*!< Set the full-duplex mode at 100 Mb/s */
|
||||
#define PHY_HALFDUPLEX_100M ((uint16_t)0x2000U) /*!< Set the half-duplex mode at 100 Mb/s */
|
||||
#define PHY_FULLDUPLEX_10M ((uint16_t)0x0100U) /*!< Set the full-duplex mode at 10 Mb/s */
|
||||
#define PHY_HALFDUPLEX_10M ((uint16_t)0x0000U) /*!< Set the half-duplex mode at 10 Mb/s */
|
||||
#define PHY_AUTONEGOTIATION ((uint16_t)0x1000U) /*!< Enable auto-negotiation function */
|
||||
#define PHY_RESTART_AUTONEGOTIATION ((uint16_t)0x0200U) /*!< Restart auto-negotiation function */
|
||||
#define PHY_POWERDOWN ((uint16_t)0x0800U) /*!< Select the power down mode */
|
||||
#define PHY_ISOLATE ((uint16_t)0x0400U) /*!< Isolate PHY from MII */
|
||||
|
||||
#define PHY_AUTONEGO_COMPLETE ((uint16_t)0x0020U) /*!< Auto-Negotiation process completed */
|
||||
#define PHY_LINKED_STATUS ((uint16_t)0x0004U) /*!< Valid link established */
|
||||
#define PHY_JABBER_DETECTION ((uint16_t)0x0002U) /*!< Jabber condition detected */
|
||||
|
||||
/* Section 4: Extended PHY Registers */
|
||||
#define PHY_SR ((uint16_t)0x10U) /*!< PHY status register Offset */
|
||||
|
||||
#define PHY_SPEED_STATUS ((uint16_t)0x0002U) /*!< PHY Speed mask */
|
||||
#define PHY_DUPLEX_STATUS ((uint16_t)0x0004U) /*!< PHY Duplex mask */
|
||||
|
||||
/* ################## SPI peripheral configuration ########################## */
|
||||
|
||||
/* CRC FEATURE: Use to activate CRC feature inside HAL SPI Driver
|
||||
* Activated: CRC code is present inside driver
|
||||
* Deactivated: CRC code cleaned from driver
|
||||
*/
|
||||
|
||||
#define USE_SPI_CRC 0U
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
/**
|
||||
* @brief Include module's header file
|
||||
*/
|
||||
|
||||
#ifdef HAL_RCC_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_rcc.h"
|
||||
#endif /* HAL_RCC_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_GPIO_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_gpio.h"
|
||||
#endif /* HAL_GPIO_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_EXTI_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_exti.h"
|
||||
#endif /* HAL_EXTI_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_DMA_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_dma.h"
|
||||
#endif /* HAL_DMA_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_CORTEX_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_cortex.h"
|
||||
#endif /* HAL_CORTEX_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_ADC_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_adc.h"
|
||||
#endif /* HAL_ADC_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_CAN_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_can.h"
|
||||
#endif /* HAL_CAN_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_CAN_LEGACY_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_can_legacy.h"
|
||||
#endif /* HAL_CAN_LEGACY_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_CRC_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_crc.h"
|
||||
#endif /* HAL_CRC_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_CRYP_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_cryp.h"
|
||||
#endif /* HAL_CRYP_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_DMA2D_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_dma2d.h"
|
||||
#endif /* HAL_DMA2D_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_DAC_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_dac.h"
|
||||
#endif /* HAL_DAC_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_DCMI_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_dcmi.h"
|
||||
#endif /* HAL_DCMI_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_ETH_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_eth.h"
|
||||
#endif /* HAL_ETH_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_FLASH_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_flash.h"
|
||||
#endif /* HAL_FLASH_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_SRAM_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_sram.h"
|
||||
#endif /* HAL_SRAM_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_NOR_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_nor.h"
|
||||
#endif /* HAL_NOR_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_NAND_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_nand.h"
|
||||
#endif /* HAL_NAND_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_PCCARD_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_pccard.h"
|
||||
#endif /* HAL_PCCARD_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_SDRAM_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_sdram.h"
|
||||
#endif /* HAL_SDRAM_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_HASH_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_hash.h"
|
||||
#endif /* HAL_HASH_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_I2C_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_i2c.h"
|
||||
#endif /* HAL_I2C_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_SMBUS_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_smbus.h"
|
||||
#endif /* HAL_SMBUS_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_I2S_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_i2s.h"
|
||||
#endif /* HAL_I2S_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_IWDG_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_iwdg.h"
|
||||
#endif /* HAL_IWDG_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_LTDC_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_ltdc.h"
|
||||
#endif /* HAL_LTDC_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_PWR_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_pwr.h"
|
||||
#endif /* HAL_PWR_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_RNG_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_rng.h"
|
||||
#endif /* HAL_RNG_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_RTC_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_rtc.h"
|
||||
#endif /* HAL_RTC_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_SAI_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_sai.h"
|
||||
#endif /* HAL_SAI_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_SD_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_sd.h"
|
||||
#endif /* HAL_SD_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_SPI_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_spi.h"
|
||||
#endif /* HAL_SPI_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_TIM_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_tim.h"
|
||||
#endif /* HAL_TIM_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_UART_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_uart.h"
|
||||
#endif /* HAL_UART_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_USART_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_usart.h"
|
||||
#endif /* HAL_USART_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_IRDA_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_irda.h"
|
||||
#endif /* HAL_IRDA_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_SMARTCARD_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_smartcard.h"
|
||||
#endif /* HAL_SMARTCARD_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_WWDG_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_wwdg.h"
|
||||
#endif /* HAL_WWDG_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_PCD_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_pcd.h"
|
||||
#endif /* HAL_PCD_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_HCD_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_hcd.h"
|
||||
#endif /* HAL_HCD_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_DSI_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_dsi.h"
|
||||
#endif /* HAL_DSI_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_QSPI_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_qspi.h"
|
||||
#endif /* HAL_QSPI_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_CEC_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_cec.h"
|
||||
#endif /* HAL_CEC_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_FMPI2C_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_fmpi2c.h"
|
||||
#endif /* HAL_FMPI2C_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_SPDIFRX_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_spdifrx.h"
|
||||
#endif /* HAL_SPDIFRX_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_DFSDM_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_dfsdm.h"
|
||||
#endif /* HAL_DFSDM_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_LPTIM_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_lptim.h"
|
||||
#endif /* HAL_LPTIM_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_MMC_MODULE_ENABLED
|
||||
#include "stm32f4xx_hal_mmc.h"
|
||||
#endif /* HAL_MMC_MODULE_ENABLED */
|
||||
|
||||
/* Exported macro ------------------------------------------------------------*/
|
||||
#ifdef USE_FULL_ASSERT
|
||||
/**
|
||||
* @brief The assert_param macro is used for function's parameters check.
|
||||
* @param expr: If expr is false, it calls assert_failed function
|
||||
* which reports the name of the source file and the source
|
||||
* line number of the call that failed.
|
||||
* If expr is true, it returns no value.
|
||||
* @retval None
|
||||
*/
|
||||
#define assert_param(expr) ((expr) ? (void)0U : assert_failed((uint8_t *)__FILE__, __LINE__))
|
||||
/* Exported functions ------------------------------------------------------- */
|
||||
void assert_failed(uint8_t *file, uint32_t line);
|
||||
#else
|
||||
#define assert_param(expr) ((void)0U)
|
||||
#endif /* USE_FULL_ASSERT */
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* __STM32F4xx_HAL_CONF_H */
|
||||
|
||||
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
165
buildroot/share/PlatformIO/variants/MARLIN_F407VE/variant.cpp
Normal file
165
buildroot/share/PlatformIO/variants/MARLIN_F407VE/variant.cpp
Normal file
|
@ -0,0 +1,165 @@
|
|||
/*
|
||||
*******************************************************************************
|
||||
* Copyright (c) 2017, STMicroelectronics
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
* 3. Neither the name of STMicroelectronics nor the names of its contributors
|
||||
* may be used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
|
||||
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
||||
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
|
||||
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
|
||||
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
|
||||
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
|
||||
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
|
||||
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*******************************************************************************
|
||||
*/
|
||||
|
||||
#include "variant.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
// Pin number
|
||||
// This array allows to wrap Arduino pin number(Dx or x)
|
||||
// to STM32 PinName (PX_n)
|
||||
const PinName digitalPin[] = {
|
||||
// Right Side
|
||||
//Int //Ext
|
||||
//3V3 //3V3
|
||||
//3V3 //3V3
|
||||
//BOOT0 //BOOT1
|
||||
//GND //GND
|
||||
//GND //GND
|
||||
PE_1, PE_0, // D0, D1
|
||||
PB_9, PB_8,
|
||||
PB_7, PB_6,
|
||||
PB_5, PB_3,
|
||||
PD_7, PD_6,
|
||||
PD_5, PD_4, // D10, D11
|
||||
PD_3, PD_2,
|
||||
PD_1, PD_0,
|
||||
PC_12, PC_11,
|
||||
PC_10, PA_15,
|
||||
PA_12, PA_11, // D20, D21 PA_11: USB_DM, PA_12: USB_DP
|
||||
PA_10, PA_9,
|
||||
PA_8, PC_9,
|
||||
PC_8, PC_7,
|
||||
PC_6, PD_15,
|
||||
PD_14, PD_13, // D30, D31
|
||||
PD_12, PD_11,
|
||||
PD_10, PD_9,
|
||||
PD_8, PB_15,
|
||||
// Left Side
|
||||
//Ext //Int
|
||||
//5V //5V
|
||||
//5V //5V
|
||||
//3V3 //3V3
|
||||
//3V3 //3V3
|
||||
//GND //GND
|
||||
PE_2, PE_3,
|
||||
PE_4, PE_5, // D40, D41 PE_4: BUT K0, PE_5: BUT K1
|
||||
PE_6, PC_13,
|
||||
PC_0, PC_1,
|
||||
PC_2, PC_3,
|
||||
//VREF- //VREF+
|
||||
PA_0, PA_1, // PA_0(WK_UP): BUT K_UP)
|
||||
PA_2, PA_3, // D50, D51
|
||||
PA_4, PA_5,
|
||||
/*PA_6, PA_7,*/ // PA_6, PA_7: Moved to allow contiguous analog pins
|
||||
PC_4, PC_5,
|
||||
PB_0, PB_1,
|
||||
PA_6, PA_7, // PA_6: LED D2, PA_7: LED D3 (active LOW)
|
||||
PE_7, PE_8, // D60, D61
|
||||
PE_9, PE_10,
|
||||
PE_11, PE_12,
|
||||
PE_13, PE_14,
|
||||
PE_15, PB_10,
|
||||
PB_11, PB_12, // D70, D71
|
||||
PB_13, PB_14,
|
||||
PB_4,
|
||||
};
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
// ----------------------------------------------------------------------------
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief System Clock Configuration
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
WEAK void SystemClock_Config(void)
|
||||
{
|
||||
|
||||
RCC_OscInitTypeDef RCC_OscInitStruct;
|
||||
RCC_ClkInitTypeDef RCC_ClkInitStruct;
|
||||
|
||||
/**Configure the main internal regulator output voltage
|
||||
*/
|
||||
__HAL_RCC_PWR_CLK_ENABLE();
|
||||
|
||||
__HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1);
|
||||
|
||||
/**Initializes the CPU, AHB and APB busses clocks
|
||||
*/
|
||||
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
|
||||
RCC_OscInitStruct.HSEState = RCC_HSE_ON;
|
||||
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
|
||||
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
|
||||
RCC_OscInitStruct.PLL.PLLM = 8;
|
||||
RCC_OscInitStruct.PLL.PLLN = 336;
|
||||
RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2;
|
||||
RCC_OscInitStruct.PLL.PLLQ = 7;
|
||||
if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) {
|
||||
_Error_Handler(__FILE__, __LINE__);
|
||||
}
|
||||
|
||||
/**Initializes the CPU, AHB and APB busses clocks
|
||||
*/
|
||||
RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_SYSCLK
|
||||
| RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2;
|
||||
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
|
||||
RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
|
||||
RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4;
|
||||
RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2;
|
||||
|
||||
if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5) != HAL_OK) {
|
||||
_Error_Handler(__FILE__, __LINE__);
|
||||
}
|
||||
|
||||
/**Configure the Systick interrupt time
|
||||
*/
|
||||
HAL_SYSTICK_Config(HAL_RCC_GetHCLKFreq() / 1000);
|
||||
|
||||
/**Configure the Systick
|
||||
*/
|
||||
HAL_SYSTICK_CLKSourceConfig(SYSTICK_CLKSOURCE_HCLK);
|
||||
|
||||
/* SysTick_IRQn interrupt configuration */
|
||||
HAL_NVIC_SetPriority(SysTick_IRQn, 0, 0);
|
||||
}
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
219
buildroot/share/PlatformIO/variants/MARLIN_F407VE/variant.h
Normal file
219
buildroot/share/PlatformIO/variants/MARLIN_F407VE/variant.h
Normal file
|
@ -0,0 +1,219 @@
|
|||
/*
|
||||
*******************************************************************************
|
||||
* Copyright (c) 2017, STMicroelectronics
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
* 3. Neither the name of STMicroelectronics nor the names of its contributors
|
||||
* may be used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
|
||||
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
||||
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
|
||||
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
|
||||
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
|
||||
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
|
||||
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
|
||||
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*******************************************************************************
|
||||
*/
|
||||
|
||||
#ifndef _VARIANT_ARDUINO_STM32_
|
||||
#define _VARIANT_ARDUINO_STM32_
|
||||
|
||||
/*----------------------------------------------------------------------------
|
||||
* Headers
|
||||
*----------------------------------------------------------------------------*/
|
||||
#include "PeripheralPins.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif // __cplusplus
|
||||
|
||||
/*----------------------------------------------------------------------------
|
||||
* Pins
|
||||
*----------------------------------------------------------------------------*/
|
||||
extern const PinName digitalPin[];
|
||||
// Right Side
|
||||
#define PE1 0
|
||||
#define PE0 1
|
||||
#define PB9 2
|
||||
#define PB8 3
|
||||
#define PB7 4
|
||||
#define PB6 5
|
||||
#define PB5 6
|
||||
#define PB3 7
|
||||
#define PD7 8
|
||||
#define PD6 9
|
||||
#define PD5 10
|
||||
#define PD4 11
|
||||
#define PD3 12
|
||||
#define PD2 13
|
||||
#define PD1 14
|
||||
#define PD0 15
|
||||
#define PC12 16
|
||||
#define PC11 17
|
||||
#define PC10 18
|
||||
#define PA15 19
|
||||
#define PA12 20 // USB_DP
|
||||
#define PA11 21 // USB_DM
|
||||
#define PA10 22
|
||||
#define PA9 23
|
||||
#define PA8 24
|
||||
#define PC9 25
|
||||
#define PC8 26
|
||||
#define PC7 27
|
||||
#define PC6 28
|
||||
#define PD15 29
|
||||
#define PD14 30
|
||||
#define PD13 31
|
||||
#define PD12 32
|
||||
#define PD11 33
|
||||
#define PD10 34
|
||||
#define PD9 35
|
||||
#define PD8 36
|
||||
#define PB15 37
|
||||
// Left Side
|
||||
#define PE2 38
|
||||
#define PE3 39
|
||||
#define PE4 40 // BUT K0
|
||||
#define PE5 41 // BUT K1
|
||||
#define PE6 42
|
||||
#define PC13 43
|
||||
#define PC0 44 // A0
|
||||
#define PC1 45 // A1
|
||||
#define PC2 46 // A2
|
||||
#define PC3 47 // A3
|
||||
#define PA0 48 // A4/WK_UP: BUT K_UP
|
||||
#define PA1 49 // A5
|
||||
#define PA2 50 // A6
|
||||
#define PA3 51 // A7
|
||||
#define PA4 52 // A8
|
||||
#define PA5 53 // A9
|
||||
#define PC4 54 // A10
|
||||
#define PC5 55 // A11
|
||||
#define PB0 56 // A12
|
||||
#define PB1 57 // A13
|
||||
#define PA6 58 // LED D2
|
||||
#define PA7 59 // LED D3 (active LOW)
|
||||
#define PE7 60
|
||||
#define PE8 61
|
||||
#define PE9 62
|
||||
#define PE10 63
|
||||
#define PE11 64
|
||||
#define PE12 65
|
||||
#define PE13 66
|
||||
#define PE14 67
|
||||
#define PE15 68
|
||||
#define PB10 69
|
||||
#define PB11 70
|
||||
#define PB12 71
|
||||
#define PB13 72
|
||||
#define PB14 73
|
||||
#define PB4 74
|
||||
|
||||
// This must be a literal
|
||||
#define NUM_DIGITAL_PINS 75
|
||||
// This must be a literal with a value less than or equal to MAX_ANALOG_INPUTS
|
||||
#define NUM_ANALOG_INPUTS 14
|
||||
#define NUM_ANALOG_FIRST 44
|
||||
|
||||
// Below ADC, DAC and PWM definitions already done in the core
|
||||
// Could be redefined here if needed
|
||||
// ADC resolution is 12bits
|
||||
//#define ADC_RESOLUTION 12
|
||||
//#define DACC_RESOLUTION 12
|
||||
|
||||
// PWM resolution
|
||||
#define PWM_RESOLUTION 8
|
||||
#define PWM_FREQUENCY 20000
|
||||
#define PWM_MAX_DUTY_CYCLE 255
|
||||
|
||||
// On-board LED pin number
|
||||
#define LED_D2 PA6
|
||||
#define LED_D3 PA7
|
||||
|
||||
// Board specific button
|
||||
#define BTN_K_UP PA0
|
||||
|
||||
#define LED_BUILTIN LED_D2
|
||||
#define LED_GREEN LED_D2
|
||||
|
||||
// On-board user button
|
||||
#define BTN_K0 PE4
|
||||
#define BTN_K1 PE3
|
||||
#define USER_BTN BTN_K0
|
||||
|
||||
// Below SPI and I2C definitions already done in the core
|
||||
// Could be redefined here if differs from the default one
|
||||
// SPI Definitions
|
||||
#define PIN_SPI_MOSI PB15
|
||||
#define PIN_SPI_MISO PB14
|
||||
#define PIN_SPI_SCK PB13
|
||||
#define PIN_SPI_SS PB12
|
||||
//#define PIN_SPI_SS1 PB0 // W25Q16 (on board flash)
|
||||
|
||||
// I2C Definitions
|
||||
#define PIN_WIRE_SDA PB7
|
||||
#define PIN_WIRE_SCL PB6
|
||||
|
||||
// Timer Definitions
|
||||
//Do not use timer used by PWM pins when possible. See PinMap_PWM in PeripheralPins.c
|
||||
#define TIMER_TONE TIM6
|
||||
|
||||
// Do not use basic timer: OC is required
|
||||
#define TIMER_SERVO TIM2 //TODO: advanced-control timers don't work
|
||||
|
||||
// UART Definitions
|
||||
// Define here Serial instance number to map on Serial generic name
|
||||
#define SERIAL_UART_INSTANCE 1 //ex: 2 for Serial2 (USART2)
|
||||
// DEBUG_UART could be redefined to print on another instance than 'Serial'
|
||||
//#define DEBUG_UART ((USART_TypeDef *) U(S)ARTX) // ex: USART3
|
||||
// DEBUG_UART baudrate, default: 9600 if not defined
|
||||
//#define DEBUG_UART_BAUDRATE x
|
||||
// DEBUG_UART Tx pin name, default: the first one found in PinMap_UART_TX for DEBUG_UART
|
||||
//#define DEBUG_PINNAME_TX PX_n // PinName used for TX
|
||||
|
||||
// Default pin used for 'Serial' instance (ex: ST-Link)
|
||||
// Mandatory for Firmata
|
||||
#define PIN_SERIAL_RX PA10
|
||||
#define PIN_SERIAL_TX PA9
|
||||
|
||||
#ifdef __cplusplus
|
||||
} // extern "C"
|
||||
#endif
|
||||
/*----------------------------------------------------------------------------
|
||||
* Arduino objects - C++ only
|
||||
*----------------------------------------------------------------------------*/
|
||||
|
||||
#ifdef __cplusplus
|
||||
// These serial port names are intended to allow libraries and architecture-neutral
|
||||
// sketches to automatically default to the correct port name for a particular type
|
||||
// of use. For example, a GPS module would normally connect to SERIAL_PORT_HARDWARE_OPEN,
|
||||
// the first hardware serial port whose RX/TX pins are not dedicated to another use.
|
||||
//
|
||||
// SERIAL_PORT_MONITOR Port which normally prints to the Arduino Serial Monitor
|
||||
//
|
||||
// SERIAL_PORT_USBVIRTUAL Port which is USB virtual serial
|
||||
//
|
||||
// SERIAL_PORT_LINUXBRIDGE Port which connects to a Linux system via Bridge library
|
||||
//
|
||||
// SERIAL_PORT_HARDWARE Hardware serial port, physical RX & TX pins.
|
||||
//
|
||||
// SERIAL_PORT_HARDWARE_OPEN Hardware serial ports which are open for use. Their RX & TX
|
||||
// pins are NOT connected to anything by default.
|
||||
#define SERIAL_PORT_MONITOR Serial
|
||||
#define SERIAL_PORT_HARDWARE Serial1
|
||||
#endif
|
||||
|
||||
#endif /* _VARIANT_ARDUINO_STM32_ */
|
|
@ -30,19 +30,19 @@ opt_set TEMP_SENSOR_BED 2
|
|||
opt_set POWER_SUPPLY 1
|
||||
opt_set GRID_MAX_POINTS_X 16
|
||||
opt_set FANMUX0_PIN 53
|
||||
opt_enable PIDTEMPBED FIX_MOUNTED_PROBE Z_SAFE_HOMING \
|
||||
SDSUPPORT EEPROM_SETTINGS REPRAP_DISCOUNT_SMART_CONTROLLER \
|
||||
BLINKM PCA9632 RGB_LED NEOPIXEL_LED AUTO_POWER_CONTROL \
|
||||
opt_enable PIDTEMPBED FIX_MOUNTED_PROBE Z_SAFE_HOMING EEPROM_SETTINGS \
|
||||
REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT SD_REPRINT_LAST_SELECTED_FILE BINARY_FILE_TRANSFER \
|
||||
NEOPIXEL_LED BLINKM PCA9632 RGB_LED RGB_LED_R_PIN RGB_LED_G_PIN RGB_LED_B_PIN \
|
||||
NOZZLE_PARK_FEATURE FILAMENT_RUNOUT_SENSOR FILAMENT_RUNOUT_DISTANCE_MM \
|
||||
AUTO_BED_LEVELING_LINEAR Z_MIN_PROBE_REPEATABILITY_TEST DEBUG_LEVELING_FEATURE \
|
||||
SKEW_CORRECTION SKEW_CORRECTION_FOR_Z SKEW_CORRECTION_GCODE \
|
||||
FWRETRACT ARC_P_CIRCLES ADVANCED_PAUSE_FEATURE CNC_WORKSPACE_PLANES CNC_COORDINATE_SYSTEMS \
|
||||
POWER_LOSS_RECOVERY POWER_LOSS_PIN POWER_LOSS_STATE BINARY_FILE_TRANSFER \
|
||||
AUTO_POWER_CONTROL POWER_LOSS_RECOVERY POWER_LOSS_PIN POWER_LOSS_STATE \
|
||||
LCD_PROGRESS_BAR LCD_PROGRESS_BAR_TEST PINS_DEBUGGING \
|
||||
MAX7219_DEBUG LED_CONTROL_MENU CASE_LIGHT_ENABLE CASE_LIGHT_USE_NEOPIXEL CODEPENDENT_XY_HOMING BACKLASH_COMPENSATION BACKLASH_GCODE
|
||||
opt_enable SLOW_PWM_HEATERS THERMAL_PROTECTION_CHAMBER
|
||||
opt_set TEMP_SENSOR_CHAMBER 3
|
||||
opt_set CHAMBER_HEATER_PIN 45
|
||||
opt_set HEATER_CHAMBER_PIN 45
|
||||
exec_test $1 $2 "RAMPS with 2 extruders, RRDFGSC, Linear ABL, LEDs, and many options"
|
||||
|
||||
#
|
||||
|
@ -69,7 +69,7 @@ exec_test $1 $2 "Azteeg X3 with 5 extruders, RRDFGSC, probeless UBL, Linear Adva
|
|||
opt_enable Z_PROBE_SLED SKEW_CORRECTION SKEW_CORRECTION_FOR_Z SKEW_CORRECTION_GCODE
|
||||
opt_set LCD_LANGUAGE jp-kana
|
||||
opt_disable SEGMENT_LEVELED_MOVES
|
||||
opt_enable BABYSTEP_ZPROBE_OFFSET DOUBLECLICK_FOR_Z_BABYSTEPPING BABYSTEP_HOTEND_Z_OFFSET
|
||||
opt_enable BABYSTEPPING BABYSTEP_XY BABYSTEP_ZPROBE_OFFSET DOUBLECLICK_FOR_Z_BABYSTEPPING BABYSTEP_HOTEND_Z_OFFSET BABYSTEP_DISPLAY_TOTAL
|
||||
exec_test $1 $2 "... Sled Z Probe, Skew, UBL Cartesian moves, Japanese, and Z probe BABYSTEPPING"
|
||||
|
||||
#
|
||||
|
@ -153,7 +153,7 @@ opt_set EXTRUDERS 2
|
|||
opt_set TEMP_SENSOR_1 -4
|
||||
opt_set SERVO_DELAY "{ 300, 300, 300 }"
|
||||
opt_enable COREYX USE_XMAX_PLUG \
|
||||
REPRAP_DISCOUNT_SMART_CONTROLLER BABYSTEPPING DAC_MOTOR_CURRENT_DEFAULT \
|
||||
REPRAP_DISCOUNT_SMART_CONTROLLER BABYSTEPPING BABYSTEP_DISPLAY_TOTAL DAC_MOTOR_CURRENT_DEFAULT \
|
||||
FILAMENT_LCD_DISPLAY FILAMENT_WIDTH_SENSOR \
|
||||
ENDSTOP_INTERRUPTS_FEATURE ENDSTOP_NOISE_THRESHOLD FAN_SOFT_PWM SDSUPPORT \
|
||||
SWITCHING_TOOLHEAD NUM_SERVOS DEBUG_LEVELING_FEATURE \
|
||||
|
|
|
@ -8,19 +8,26 @@ function activate(context) {
|
|||
|
||||
var NEXT_TERM_ID = 1;
|
||||
var pio_build = vscode.commands.registerCommand('piobuild', function () {
|
||||
const terminal = vscode.window.createTerminal(`#${NEXT_TERM_ID++}`);
|
||||
vscode.commands.executeCommand('workbench.action.files.saveAll');
|
||||
const terminal = vscode.window.createTerminal(`AB Build #${NEXT_TERM_ID++}`);
|
||||
terminal.show(true);
|
||||
terminal.sendText("python buildroot/share/atom/auto_build.py build");
|
||||
});
|
||||
var pio_clean = vscode.commands.registerCommand('pioclean', function () {
|
||||
const terminal = vscode.window.createTerminal(`#${NEXT_TERM_ID++}`);
|
||||
const terminal = vscode.window.createTerminal(`AB Clean #${NEXT_TERM_ID++}`);
|
||||
terminal.show(true);
|
||||
terminal.sendText("python buildroot/share/atom/auto_build.py clean");
|
||||
});
|
||||
var pio_upload = vscode.commands.registerCommand('pioupload', function () {
|
||||
const terminal = vscode.window.createTerminal(`#${NEXT_TERM_ID++}`);
|
||||
vscode.commands.executeCommand('workbench.action.files.saveAll');
|
||||
const terminal = vscode.window.createTerminal(`AB Upload #${NEXT_TERM_ID++}`);
|
||||
terminal.show(true);
|
||||
terminal.sendText("python buildroot/share/atom/auto_build.py upload");
|
||||
});
|
||||
var pio_traceback = vscode.commands.registerCommand('piotraceback', function () {
|
||||
const terminal = vscode.window.createTerminal(`#${NEXT_TERM_ID++}`);
|
||||
vscode.commands.executeCommand('workbench.action.files.saveAll');
|
||||
const terminal = vscode.window.createTerminal(`AB Traceback #${NEXT_TERM_ID++}`);
|
||||
terminal.show(true);
|
||||
terminal.sendText("python buildroot/share/atom/auto_build.py traceback");
|
||||
});
|
||||
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 0
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -462,7 +471,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1413,7 +1422,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1893,6 +1902,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2050,10 +2065,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -467,7 +476,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1444,7 +1453,7 @@
|
|||
#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1924,6 +1933,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G27" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 7
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 250
|
||||
#define HEATER_5_MAXTEMP 250
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -471,7 +480,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1433,7 +1442,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1913,6 +1922,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2070,10 +2085,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 4
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -462,7 +471,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1413,7 +1422,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1893,6 +1902,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2050,10 +2065,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 20
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 130
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -473,7 +482,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1424,7 +1433,7 @@
|
|||
#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1904,6 +1913,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2061,10 +2076,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G27" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 5
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -462,7 +471,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1413,7 +1422,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1895,6 +1904,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2052,10 +2067,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 5
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -462,7 +471,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1413,7 +1422,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1895,6 +1904,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2052,10 +2067,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 11
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 130
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -473,7 +482,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1565,7 +1574,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -2047,6 +2056,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2204,10 +2219,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -250,13 +250,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -378,7 +392,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 5
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -397,8 +410,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -408,7 +419,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -420,7 +430,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 130
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -469,7 +478,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1426,7 +1435,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1908,6 +1917,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2065,10 +2080,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -467,7 +476,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1423,7 +1432,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1903,6 +1912,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2060,10 +2075,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 13
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -462,7 +471,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1414,7 +1423,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1894,6 +1903,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2051,10 +2066,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -54,6 +54,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -131,8 +144,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -460,6 +473,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -777,8 +791,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -966,6 +983,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1014,6 +1037,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -462,7 +471,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1413,7 +1422,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1893,6 +1902,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2050,10 +2065,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 5
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 115
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -462,7 +471,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1413,7 +1422,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1893,6 +1902,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2050,10 +2065,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 60
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 115
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -462,7 +471,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1413,7 +1422,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1893,6 +1902,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2050,10 +2065,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 0
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 260
|
||||
#define HEATER_5_MAXTEMP 260
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -450,7 +459,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1401,7 +1410,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1881,6 +1890,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2038,10 +2053,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -770,8 +784,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -959,6 +976,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1007,6 +1030,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -257,13 +257,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -385,7 +399,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 0
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -404,8 +417,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -415,7 +426,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -427,7 +437,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 100
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -463,7 +472,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1413,7 +1422,7 @@
|
|||
#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 10 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1893,6 +1902,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2050,10 +2065,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 1
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
#define HOME_Y_BEFORE_X
|
||||
|
@ -778,8 +792,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G27" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -967,6 +984,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1015,6 +1038,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 0
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 260
|
||||
#define HEATER_5_MAXTEMP 260
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -450,7 +459,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1401,7 +1410,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1881,6 +1890,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2038,10 +2053,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -770,8 +784,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -959,6 +976,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1007,6 +1030,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -250,13 +250,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -378,7 +392,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -397,8 +410,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -408,7 +419,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -420,7 +430,6 @@
|
|||
#define HEATER_4_MAXTEMP 415
|
||||
#define HEATER_5_MAXTEMP 415
|
||||
#define BED_MAXTEMP 165
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -463,7 +472,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1412,7 +1421,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1892,6 +1901,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2049,10 +2064,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 5
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 120
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -467,7 +476,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1290,7 +1299,7 @@
|
|||
#endif
|
||||
|
||||
// Homing speeds (mm/m)
|
||||
#define HOMING_FEEDRATE_XY (50*60)
|
||||
#define HOMING_FEEDRATE_XY (20*60)
|
||||
#define HOMING_FEEDRATE_Z (4*60)
|
||||
|
||||
// Validate that endstops are triggered on homing moves
|
||||
|
@ -1423,7 +1432,7 @@
|
|||
#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1903,6 +1912,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2060,10 +2075,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G27" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 5
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 120
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -462,7 +471,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1281,7 +1290,7 @@
|
|||
#endif
|
||||
|
||||
// Homing speeds (mm/m)
|
||||
#define HOMING_FEEDRATE_XY (50*60)
|
||||
#define HOMING_FEEDRATE_XY (20*60)
|
||||
#define HOMING_FEEDRATE_Z (8*60)
|
||||
|
||||
// Validate that endstops are triggered on homing moves
|
||||
|
@ -1414,7 +1423,7 @@
|
|||
#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 3), (Y_MAX_POS - 3), 10 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1894,6 +1903,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2051,10 +2066,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G27" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 5
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 120
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -462,7 +471,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1283,7 +1292,7 @@
|
|||
#endif
|
||||
|
||||
// Homing speeds (mm/m)
|
||||
#define HOMING_FEEDRATE_XY (50*60)
|
||||
#define HOMING_FEEDRATE_XY (20*60)
|
||||
#define HOMING_FEEDRATE_Z (4*60)
|
||||
|
||||
// Validate that endstops are triggered on homing moves
|
||||
|
@ -1416,7 +1425,7 @@
|
|||
#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 20), (Y_MAX_POS - 20), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1896,6 +1905,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2053,10 +2068,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G27" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -258,13 +258,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -386,7 +400,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 5
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -405,8 +418,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -416,7 +427,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -428,7 +438,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 120
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -476,7 +485,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1299,7 +1308,7 @@
|
|||
#endif
|
||||
|
||||
// Homing speeds (mm/m)
|
||||
#define HOMING_FEEDRATE_XY (50*60)
|
||||
#define HOMING_FEEDRATE_XY (20*60)
|
||||
#define HOMING_FEEDRATE_Z (4*60)
|
||||
|
||||
// Validate that endstops are triggered on homing moves
|
||||
|
@ -1432,7 +1441,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1912,6 +1921,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2069,10 +2084,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -467,7 +476,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1290,7 +1299,7 @@
|
|||
#endif
|
||||
|
||||
// Homing speeds (mm/m)
|
||||
#define HOMING_FEEDRATE_XY (50*60)
|
||||
#define HOMING_FEEDRATE_XY (20*60)
|
||||
#define HOMING_FEEDRATE_Z (4*60)
|
||||
|
||||
// Validate that endstops are triggered on homing moves
|
||||
|
@ -1423,7 +1432,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1903,6 +1912,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2060,10 +2075,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 75
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -466,7 +475,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1284,7 +1293,7 @@
|
|||
#endif
|
||||
|
||||
// Homing speeds (mm/m)
|
||||
#define HOMING_FEEDRATE_XY (50*60)
|
||||
#define HOMING_FEEDRATE_XY (20*60)
|
||||
#define HOMING_FEEDRATE_Z (4*60)
|
||||
|
||||
// Validate that endstops are triggered on homing moves
|
||||
|
@ -1417,7 +1426,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1897,6 +1906,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2054,10 +2069,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 1
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -770,8 +784,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -959,6 +976,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1007,6 +1030,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 125
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -466,7 +475,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1417,7 +1426,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1897,6 +1906,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2054,10 +2069,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -770,8 +784,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -959,6 +976,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1007,6 +1030,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
@ -1594,7 +1619,7 @@
|
|||
* Define you own with
|
||||
* { <off_time[1..15]>, <hysteresis_end[-3..12]>, hysteresis_start[1..8] }
|
||||
*/
|
||||
#define CHOPPER_TIMING CHOPPER_DEFAULT_12V
|
||||
#define CHOPPER_TIMING CHOPPER_DEFAULT_24V
|
||||
|
||||
/**
|
||||
* Monitor Trinamic drivers for error conditions,
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -467,7 +476,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1290,7 +1299,7 @@
|
|||
#endif
|
||||
|
||||
// Homing speeds (mm/m)
|
||||
#define HOMING_FEEDRATE_XY (50*60)
|
||||
#define HOMING_FEEDRATE_XY (20*60)
|
||||
#define HOMING_FEEDRATE_Z (7*60)
|
||||
|
||||
// Validate that endstops are triggered on homing moves
|
||||
|
@ -1423,7 +1432,7 @@
|
|||
#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1903,6 +1912,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2060,10 +2075,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G27" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -379,7 +393,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 0
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -398,8 +411,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -409,7 +420,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -421,7 +431,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -470,7 +479,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1423,7 +1432,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1903,6 +1912,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2056,10 +2071,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -450,7 +459,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1395,7 +1404,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1875,6 +1884,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2032,10 +2047,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 3
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -450,7 +459,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1395,7 +1404,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1875,6 +1884,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2032,10 +2047,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -452,7 +461,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1404,7 +1413,7 @@
|
|||
#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MAX_POS - 2), (Y_MAX_POS - 2), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1884,6 +1893,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2041,10 +2056,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -769,8 +783,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G27" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -958,6 +975,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1006,6 +1029,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 245
|
||||
#define HEATER_5_MAXTEMP 245
|
||||
#define BED_MAXTEMP 115
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -467,7 +476,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1419,7 +1428,7 @@
|
|||
#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1899,6 +1908,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2056,10 +2071,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G27" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -290,13 +290,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -422,7 +436,6 @@
|
|||
#define TEMP_SENSOR_BED 1
|
||||
#endif
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -441,8 +454,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -451,7 +462,6 @@
|
|||
#define HEATER_3_MINTEMP 5
|
||||
#define HEATER_4_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -466,7 +476,6 @@
|
|||
#else
|
||||
#define BED_MAXTEMP 100
|
||||
#endif
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -514,7 +523,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1518,7 +1527,7 @@
|
|||
#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { 10, 10, 20}
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 70 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1998,6 +2007,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2155,10 +2170,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -308,7 +321,7 @@
|
|||
*/
|
||||
#define CASE_LIGHT_ENABLE
|
||||
#if ENABLED(CASE_LIGHT_ENABLE)
|
||||
#define CASE_LIGHT_PIN 5
|
||||
//#define CASE_LIGHT_PIN 4 // Override the default pin if needed
|
||||
#define INVERT_CASE_LIGHT false // Set true if Case Light is ON when pin is LOW
|
||||
#define CASE_LIGHT_DEFAULT_ON true // Set default power-up state on
|
||||
#define CASE_LIGHT_DEFAULT_BRIGHTNESS 255 // Set default power-up brightness (0-255, requires PWM pin)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G27" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -252,13 +252,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -392,7 +406,6 @@
|
|||
#endif
|
||||
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -411,8 +424,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -422,7 +433,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -434,7 +444,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -484,7 +493,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1448,7 +1457,7 @@
|
|||
#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { 50, (Y_MIN_POS + 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1928,6 +1937,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2085,10 +2100,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -460,6 +473,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -777,8 +791,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G27" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -966,6 +983,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -998,8 +1021,8 @@
|
|||
*/
|
||||
#define BABYSTEPPING
|
||||
#if ENABLED(BABYSTEPPING)
|
||||
//#define BABYSTEP_WITHOUT_HOMING
|
||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||
#define BABYSTEP_WITHOUT_HOMING
|
||||
#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||
#define BABYSTEP_MULTIPLICATOR 40 // Babysteps are very small. Increase for faster motion.
|
||||
|
||||
|
@ -1007,13 +1030,15 @@
|
|||
#if ENABLED(DOUBLECLICK_FOR_Z_BABYSTEPPING)
|
||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||
// Note: Extra time may be added to mitigate controller latency.
|
||||
//#define BABYSTEP_ALWAYS_AVAILABLE // Allow babystepping at all times (not just during movement).
|
||||
#define BABYSTEP_ALWAYS_AVAILABLE // Allow babystepping at all times (not just during movement).
|
||||
//#define MOVE_Z_WHEN_IDLE // Jump to the move Z menu on doubleclick when printer is idle.
|
||||
#if ENABLED(MOVE_Z_WHEN_IDLE)
|
||||
#define MOVE_Z_IDLE_MULTIPLICATOR 1 // Multiply 1mm by this factor for the move step size.
|
||||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -253,13 +253,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -386,7 +400,6 @@
|
|||
#endif
|
||||
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -405,8 +418,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -416,7 +427,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -428,7 +438,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -471,7 +480,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1438,7 +1447,7 @@
|
|||
#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { 100, (Y_MIN_POS + 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1921,6 +1930,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2078,10 +2093,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -460,6 +473,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -777,8 +791,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G27" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -966,6 +983,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1014,6 +1037,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -452,7 +461,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1398,7 +1407,7 @@
|
|||
#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { 3, 3, 10 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1878,6 +1887,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2035,10 +2050,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G27" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -452,7 +461,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1398,7 +1407,7 @@
|
|||
#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { 3, 3, 10 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1882,6 +1891,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2039,10 +2054,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G27" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -472,7 +481,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1428,7 +1437,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1908,6 +1917,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2065,10 +2080,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -462,7 +471,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1402,7 +1411,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1882,6 +1891,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2039,10 +2054,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -466,7 +475,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1420,7 +1429,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1900,6 +1909,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2057,10 +2072,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 125
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -472,7 +481,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1429,7 +1438,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1909,6 +1918,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2066,10 +2081,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 125
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -472,7 +481,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1428,7 +1437,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1908,6 +1917,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2065,10 +2080,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -462,7 +471,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1413,7 +1422,7 @@
|
|||
#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1893,6 +1902,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2050,10 +2065,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G27" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -462,7 +471,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1413,7 +1422,7 @@
|
|||
#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1893,6 +1902,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2050,10 +2065,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G27" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 125
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -466,7 +475,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1417,7 +1426,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1897,6 +1906,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2054,10 +2069,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 1
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -254,13 +254,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -382,7 +396,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1 // measured to be satisfactorily accurate on center of bed within +/- 1 degC.
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -401,8 +414,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -412,7 +423,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -424,7 +434,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 120
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -472,7 +481,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1425,7 +1434,7 @@
|
|||
#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1905,6 +1914,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2062,10 +2077,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 10, 10, 6 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -770,8 +784,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G27" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -959,6 +976,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1007,6 +1030,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -269,13 +269,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -397,7 +411,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -416,8 +429,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -427,7 +438,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -439,7 +449,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -482,7 +491,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1433,7 +1442,7 @@
|
|||
#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1913,6 +1922,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2070,10 +2085,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G27" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -254,13 +254,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -385,7 +399,6 @@
|
|||
// The reasons are inconclusive so I leave at 1
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -404,8 +417,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -415,7 +426,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -427,7 +437,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -470,7 +479,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1441,7 +1450,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1921,6 +1930,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2078,10 +2093,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 11
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 100
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -461,7 +470,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1412,7 +1421,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1892,6 +1901,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2049,10 +2064,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 0
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -462,7 +471,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1417,7 +1426,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1897,6 +1906,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2054,10 +2069,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 0
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -462,7 +471,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1417,7 +1426,7 @@
|
|||
#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1897,6 +1906,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2054,10 +2069,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G27" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -250,13 +250,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -378,7 +392,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -397,8 +410,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -408,7 +419,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -420,7 +430,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -463,7 +472,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1414,7 +1423,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1895,6 +1904,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2052,10 +2067,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 5
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -462,7 +471,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1413,7 +1422,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1893,6 +1902,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2050,10 +2065,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -774,8 +788,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -963,6 +980,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1011,6 +1034,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -250,13 +250,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -378,7 +392,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -397,8 +410,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -408,7 +419,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -420,7 +430,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -463,7 +472,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1421,7 +1430,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1901,6 +1910,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2058,10 +2073,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 250
|
||||
#define HEATER_5_MAXTEMP 250
|
||||
#define BED_MAXTEMP 120
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -462,7 +471,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1413,7 +1422,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1893,6 +1902,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2050,10 +2065,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1 // Sanguinololu v1.3 with 4.7kOhm pullup
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -462,7 +471,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1462,7 +1471,7 @@ Black rubber belt(MXL), 18 - tooth aluminium pulley : 87.489 step per mm (Huxley
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE DEFAULT_MAX_Z_FEEDRATE // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1942,6 +1951,12 @@ Black rubber belt(MXL), 18 - tooth aluminium pulley : 87.489 step per mm (Huxley
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2099,10 +2114,10 @@ Black rubber belt(MXL), 18 - tooth aluminium pulley : 87.489 step per mm (Huxley
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -462,7 +471,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1413,7 +1422,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1893,6 +1902,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2050,10 +2065,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -252,13 +252,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -380,7 +394,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -399,8 +412,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -410,7 +421,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -422,7 +432,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -465,7 +474,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1411,7 +1420,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1893,6 +1902,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2050,10 +2065,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -280,13 +280,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -408,7 +422,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -427,8 +440,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -438,7 +449,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -450,7 +460,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -481,7 +490,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1426,7 +1435,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1906,6 +1915,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2063,10 +2078,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 3000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 3
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -770,8 +784,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
//#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -959,6 +976,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1007,6 +1030,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
2123
config/examples/STM32/Black_STM32F407VET6/Configuration.h
Normal file
2123
config/examples/STM32/Black_STM32F407VET6/Configuration.h
Normal file
|
@ -0,0 +1,2123 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2019 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
|
||||
|
||||
/**
|
||||
* Configuration.h
|
||||
*
|
||||
* Basic settings such as:
|
||||
*
|
||||
* - Type of electronics
|
||||
* - Type of temperature sensor
|
||||
* - Printer geometry
|
||||
* - Endstop configuration
|
||||
* - LCD controller
|
||||
* - Extra features
|
||||
*
|
||||
* Advanced settings can be found in Configuration_adv.h
|
||||
*
|
||||
*/
|
||||
#define CONFIGURATION_H_VERSION 020000
|
||||
|
||||
//===========================================================================
|
||||
//============================= Getting Started =============================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
* Here are some standard links for getting your machine calibrated:
|
||||
*
|
||||
* http://reprap.org/wiki/Calibration
|
||||
* http://youtu.be/wAL9d7FgInk
|
||||
* http://calculator.josefprusa.cz
|
||||
* http://reprap.org/wiki/Triffid_Hunter%27s_Calibration_Guide
|
||||
* http://www.thingiverse.com/thing:5573
|
||||
* https://sites.google.com/site/repraplogphase/calibration-of-your-reprap
|
||||
* http://www.thingiverse.com/thing:298812
|
||||
*/
|
||||
|
||||
//===========================================================================
|
||||
//============================= DELTA Printer ===============================
|
||||
//===========================================================================
|
||||
// For a Delta printer start with one of the configuration files in the
|
||||
// config/examples/delta directory and customize for your machine.
|
||||
//
|
||||
|
||||
//===========================================================================
|
||||
//============================= SCARA Printer ===============================
|
||||
//===========================================================================
|
||||
// For a SCARA printer start with the configuration files in
|
||||
// config/examples/SCARA and customize for your machine.
|
||||
//
|
||||
|
||||
// @section info
|
||||
|
||||
// User-specified version info of this build to display in [Pronterface, etc] terminal window during
|
||||
// startup. Implementation of an idea by Prof Braino to inform user that any changes made to this
|
||||
// build by the user have been successfully uploaded into firmware.
|
||||
#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes.
|
||||
#define SHOW_BOOTSCREEN
|
||||
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
|
||||
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during bootup in line 2
|
||||
|
||||
/**
|
||||
* *** VENDORS PLEASE READ ***
|
||||
*
|
||||
* Marlin allows you to add a custom boot image for Graphical LCDs.
|
||||
* With this option Marlin will first show your custom screen followed
|
||||
* by the standard Marlin logo with version number and web URL.
|
||||
*
|
||||
* We encourage you to take advantage of this new feature and we also
|
||||
* respectfully request that you retain the unmodified Marlin boot screen.
|
||||
*/
|
||||
|
||||
// Enable to show the bitmap in Marlin/_Bootscreen.h on startup.
|
||||
//#define SHOW_CUSTOM_BOOTSCREEN
|
||||
|
||||
// Enable to show the bitmap in Marlin/_Statusscreen.h on the status screen.
|
||||
//#define CUSTOM_STATUS_SCREEN_IMAGE
|
||||
|
||||
// @section machine
|
||||
|
||||
/**
|
||||
* Select the serial port on the board to use for communication with the host.
|
||||
* This allows the connection of wireless adapters (for instance) to non-default port pins.
|
||||
* Note: The first serial port (-1 or 0) will always be used by the Arduino bootloader.
|
||||
*
|
||||
* :[-1, 0, 1, 2, 3, 4, 5, 6, 7]
|
||||
*/
|
||||
#define SERIAL_PORT -1
|
||||
|
||||
/**
|
||||
* Select a secondary serial port on the board to use for communication with the host.
|
||||
* This allows the connection of wireless adapters (for instance) to non-default port pins.
|
||||
* Serial port -1 is the USB emulated serial port, if available.
|
||||
*
|
||||
* :[-1, 0, 1, 2, 3, 4, 5, 6, 7]
|
||||
*/
|
||||
#define SERIAL_PORT_2 1
|
||||
|
||||
/**
|
||||
* This setting determines the communication speed of the printer.
|
||||
*
|
||||
* 250000 works in most cases, but you might try a lower speed if
|
||||
* you commonly experience drop-outs during host printing.
|
||||
* You may try up to 1000000 to speed up SD file transfer.
|
||||
*
|
||||
* :[2400, 9600, 19200, 38400, 57600, 115200, 250000, 500000, 1000000]
|
||||
*/
|
||||
#define BAUDRATE 250000
|
||||
|
||||
// Enable the Bluetooth serial interface on AT90USB devices
|
||||
//#define BLUETOOTH
|
||||
|
||||
// The following define selects which electronics board you have.
|
||||
// Please choose the name from boards.h that matches your setup
|
||||
#ifndef MOTHERBOARD
|
||||
#define MOTHERBOARD BOARD_BLACK_STM32F407VE
|
||||
#endif
|
||||
|
||||
// Optional custom name for your RepStrap or other custom machine
|
||||
// Displayed in the LCD "Ready" message
|
||||
//#define CUSTOM_MACHINE_NAME "3D Printer"
|
||||
|
||||
// Define this to set a unique identifier for this printer, (Used by some programs to differentiate between machines)
|
||||
// You can use an online service to generate a random UUID. (eg http://www.uuidgenerator.net/version4)
|
||||
//#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
|
||||
|
||||
// @section extruder
|
||||
|
||||
// This defines the number of extruders
|
||||
// :[1, 2, 3, 4, 5, 6]
|
||||
#define EXTRUDERS 2
|
||||
|
||||
// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
|
||||
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0
|
||||
|
||||
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
||||
//#define SINGLENOZZLE
|
||||
|
||||
/**
|
||||
* Průša MK2 Single Nozzle Multi-Material Multiplexer, and variants.
|
||||
*
|
||||
* This device allows one stepper driver on a control board to drive
|
||||
* two to eight stepper motors, one at a time, in a manner suitable
|
||||
* for extruders.
|
||||
*
|
||||
* This option only allows the multiplexer to switch on tool-change.
|
||||
* Additional options to configure custom E moves are pending.
|
||||
*/
|
||||
//#define MK2_MULTIPLEXER
|
||||
#if ENABLED(MK2_MULTIPLEXER)
|
||||
// Override the default DIO selector pins here, if needed.
|
||||
// Some pins files may provide defaults for these pins.
|
||||
//#define E_MUX0_PIN 40 // Always Required
|
||||
//#define E_MUX1_PIN 42 // Needed for 3 to 8 inputs
|
||||
//#define E_MUX2_PIN 44 // Needed for 5 to 8 inputs
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Prusa Multi-Material Unit v2
|
||||
*
|
||||
* Requires NOZZLE_PARK_FEATURE to park print head in case MMU unit fails.
|
||||
* Requires EXTRUDERS = 5
|
||||
*
|
||||
* For additional configuration see Configuration_adv.h
|
||||
*/
|
||||
//#define PRUSA_MMU2
|
||||
|
||||
// A dual extruder that uses a single stepper motor
|
||||
//#define SWITCHING_EXTRUDER
|
||||
#if ENABLED(SWITCHING_EXTRUDER)
|
||||
#define SWITCHING_EXTRUDER_SERVO_NR 0
|
||||
#define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3]
|
||||
#if EXTRUDERS > 3
|
||||
#define SWITCHING_EXTRUDER_E23_SERVO_NR 1
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// A dual-nozzle that uses a servomotor to raise/lower one (or both) of the nozzles
|
||||
//#define SWITCHING_NOZZLE
|
||||
#if ENABLED(SWITCHING_NOZZLE)
|
||||
#define SWITCHING_NOZZLE_SERVO_NR 0
|
||||
//#define SWITCHING_NOZZLE_E1_SERVO_NR 1 // If two servos are used, the index of the second
|
||||
#define SWITCHING_NOZZLE_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 (single servo) or lowered/raised (dual servo)
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Two separate X-carriages with extruders that connect to a moving part
|
||||
* via a solenoid docking mechanism. Requires SOL1_PIN and SOL2_PIN.
|
||||
*/
|
||||
//#define PARKING_EXTRUDER
|
||||
|
||||
/**
|
||||
* Two separate X-carriages with extruders that connect to a moving part
|
||||
* via a magnetic docking mechanism using movements and no solenoid
|
||||
*
|
||||
* project : https://www.thingiverse.com/thing:3080893
|
||||
* movements : https://youtu.be/0xCEiG9VS3k
|
||||
* https://youtu.be/Bqbcs0CU2FE
|
||||
*/
|
||||
//#define MAGNETIC_PARKING_EXTRUDER
|
||||
|
||||
#if EITHER(PARKING_EXTRUDER, MAGNETIC_PARKING_EXTRUDER)
|
||||
|
||||
#define PARKING_EXTRUDER_PARKING_X { -78, 184 } // X positions for parking the extruders
|
||||
#define PARKING_EXTRUDER_GRAB_DISTANCE 1 // (mm) Distance to move beyond the parking point to grab the extruder
|
||||
//#define MANUAL_SOLENOID_CONTROL // Manual control of docking solenoids with M380 S / M381
|
||||
|
||||
#if ENABLED(PARKING_EXTRUDER)
|
||||
|
||||
#define PARKING_EXTRUDER_SOLENOIDS_INVERT // If enabled, the solenoid is NOT magnetized with applied voltage
|
||||
#define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW // LOW or HIGH pin signal energizes the coil
|
||||
#define PARKING_EXTRUDER_SOLENOIDS_DELAY 250 // (ms) Delay for magnetic field. No delay if 0 or not defined.
|
||||
//#define MANUAL_SOLENOID_CONTROL // Manual control of docking solenoids with M380 S / M381
|
||||
|
||||
#elif ENABLED(MAGNETIC_PARKING_EXTRUDER)
|
||||
|
||||
#define MPE_FAST_SPEED 9000 // (mm/m) Speed for travel before last distance point
|
||||
#define MPE_SLOW_SPEED 4500 // (mm/m) Speed for last distance travel to park and couple
|
||||
#define MPE_TRAVEL_DISTANCE 10 // (mm) Last distance point
|
||||
#define MPE_COMPENSATION 0 // Offset Compensation -1 , 0 , 1 (multiplier) only for coupling
|
||||
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Switching Toolhead
|
||||
*
|
||||
* Support for swappable and dockable toolheads, such as
|
||||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
* "Mixing Extruder"
|
||||
* - Adds G-codes M163 and M164 to set and "commit" the current mix factors.
|
||||
* - Extends the stepping routines to move multiple steppers in proportion to the mix.
|
||||
* - Optional support for Repetier Firmware's 'M164 S<index>' supporting virtual tools.
|
||||
* - This implementation supports up to two mixing extruders.
|
||||
* - Enable DIRECT_MIXING_IN_G1 for M165 and mixing in G1 (from Pia Taubert's reference implementation).
|
||||
*/
|
||||
//#define MIXING_EXTRUDER
|
||||
#if ENABLED(MIXING_EXTRUDER)
|
||||
#define MIXING_STEPPERS 2 // Number of steppers in your mixing extruder
|
||||
#define MIXING_VIRTUAL_TOOLS 16 // Use the Virtual Tool method with M163 and M164
|
||||
//#define DIRECT_MIXING_IN_G1 // Allow ABCDHI mix factors in G1 movement commands
|
||||
//#define GRADIENT_MIX // Support for gradient mixing with M166 and LCD
|
||||
#if ENABLED(GRADIENT_MIX)
|
||||
//#define GRADIENT_VTOOL // Add M166 T to use a V-tool index as a Gradient alias
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// Offset of the extruders (uncomment if using more than one and relying on firmware to position when changing).
|
||||
// The offset has to be X=0, Y=0 for the extruder 0 hotend (default extruder).
|
||||
// For the other hotends it is their distance from the extruder 0 hotend.
|
||||
//#define HOTEND_OFFSET_X {0.0, 20.00} // (mm) relative X-offset for each nozzle
|
||||
//#define HOTEND_OFFSET_Y {0.0, 5.00} // (mm) relative Y-offset for each nozzle
|
||||
//#define HOTEND_OFFSET_Z {0.0, 0.00} // (mm) relative Z-offset for each nozzle
|
||||
|
||||
// @section machine
|
||||
|
||||
/**
|
||||
* Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN
|
||||
*
|
||||
* 0 = No Power Switch
|
||||
* 1 = ATX
|
||||
* 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
|
||||
*
|
||||
* :{ 0:'No power switch', 1:'ATX', 2:'X-Box 360' }
|
||||
*/
|
||||
#define POWER_SUPPLY 0
|
||||
|
||||
#if POWER_SUPPLY > 0
|
||||
// Enable this option to leave the PSU off at startup.
|
||||
// Power to steppers and heaters will need to be turned on with M80.
|
||||
//#define PS_DEFAULT_OFF
|
||||
|
||||
//#define AUTO_POWER_CONTROL // Enable automatic control of the PS_ON pin
|
||||
#if ENABLED(AUTO_POWER_CONTROL)
|
||||
#define AUTO_POWER_FANS // Turn on PSU if fans need power
|
||||
#define AUTO_POWER_E_FANS
|
||||
#define AUTO_POWER_CONTROLLERFAN
|
||||
#define POWER_TIMEOUT 30
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
// @section temperature
|
||||
|
||||
//===========================================================================
|
||||
//============================= Thermal Settings ============================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
* --NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
|
||||
*
|
||||
* Temperature sensors available:
|
||||
*
|
||||
* -4 : thermocouple with AD8495
|
||||
* -3 : thermocouple with MAX31855 (only for sensor 0)
|
||||
* -2 : thermocouple with MAX6675 (only for sensor 0)
|
||||
* -1 : thermocouple with AD595
|
||||
* 0 : not used
|
||||
* 1 : 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
|
||||
* 2 : 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
|
||||
* 3 : Mendel-parts thermistor (4.7k pullup)
|
||||
* 4 : 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
|
||||
* 5 : 100K thermistor - ATC Semitec 104GT-2/104NT-4-R025H42G (Used in ParCan & J-Head) (4.7k pullup)
|
||||
* 501 : 100K Zonestar (Tronxy X3A) Thermistor
|
||||
* 6 : 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
|
||||
* 7 : 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
|
||||
* 71 : 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
|
||||
* 8 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
|
||||
* 9 : 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
|
||||
* 10 : 100k RS thermistor 198-961 (4.7k pullup)
|
||||
* 11 : 100k beta 3950 1% thermistor (4.7k pullup)
|
||||
* 12 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
|
||||
* 13 : 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
|
||||
* 15 : 100k thermistor calibration for JGAurora A5 hotend
|
||||
* 20 : the PT100 circuit found in the Ultimainboard V2.x
|
||||
* 60 : 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
|
||||
* 61 : 100k Formbot / Vivedino 3950 350C thermistor 4.7k pullup
|
||||
* 66 : 4.7M High Temperature thermistor from Dyze Design
|
||||
* 67 : 450C thermistor from SliceEngineering
|
||||
* 70 : the 100K thermistor found in the bq Hephestos 2
|
||||
* 75 : 100k Generic Silicon Heat Pad with NTC 100K MGB18-104F39050L32 thermistor
|
||||
*
|
||||
* 1k ohm pullup tables - This is atypical, and requires changing out the 4.7k pullup for 1k.
|
||||
* (but gives greater accuracy and more stable PID)
|
||||
* 51 : 100k thermistor - EPCOS (1k pullup)
|
||||
* 52 : 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
|
||||
* 55 : 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
|
||||
*
|
||||
* 1047 : Pt1000 with 4k7 pullup
|
||||
* 1010 : Pt1000 with 1k pullup (non standard)
|
||||
* 147 : Pt100 with 4k7 pullup
|
||||
* 110 : Pt100 with 1k pullup (non standard)
|
||||
*
|
||||
* Use these for Testing or Development purposes. NEVER for production machine.
|
||||
* 998 : Dummy Table that ALWAYS reads 25°C or the temperature defined below.
|
||||
* 999 : Dummy Table that ALWAYS reads 100°C or the temperature defined below.
|
||||
*
|
||||
* :{ '0': "Not used", '1':"100k / 4.7k - EPCOS", '2':"200k / 4.7k - ATC Semitec 204GT-2", '3':"Mendel-parts / 4.7k", '4':"10k !! do not use for a hotend. Bad resolution at high temp. !!", '5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '501':"100K Zonestar (Tronxy X3A)", '6':"100k / 4.7k EPCOS - Not as accurate as Table 1", '7':"100k / 4.7k Honeywell 135-104LAG-J01", '8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10':"100k / 4.7k RS 198-961", '11':"100k / 4.7k beta 3950 1%", '12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '20':"PT100 (Ultimainboard V2.x)", '51':"100k / 1k - EPCOS", '52':"200k / 1k - ATC Semitec 204GT-2", '55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '61':"100k Formbot / Vivedino 3950 350C thermistor 4.7k pullup", '66':"Dyze Design 4.7M High Temperature thermistor", '67':"Slice Engineering 450C High Temperature thermistor", '70':"the 100K thermistor found in the bq Hephestos 2", '71':"100k / 4.7k Honeywell 135-104LAF-J01", '147':"Pt100 / 4.7k", '1047':"Pt1000 / 4.7k", '110':"Pt100 / 1k (non-standard)", '1010':"Pt1000 / 1k (non standard)", '-4':"Thermocouple + AD8495", '-3':"Thermocouple + MAX31855 (only for sensor 0)", '-2':"Thermocouple + MAX6675 (only for sensor 0)", '-1':"Thermocouple + AD595",'998':"Dummy 1", '999':"Dummy 2" }
|
||||
*/
|
||||
#define TEMP_SENSOR_0 1
|
||||
#define TEMP_SENSOR_1 1
|
||||
#define TEMP_SENSOR_2 0
|
||||
#define TEMP_SENSOR_3 0
|
||||
#define TEMP_SENSOR_4 0
|
||||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#define TEMP_SENSOR_CHAMBER 1
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
#define DUMMY_THERMISTOR_999_VALUE 100
|
||||
|
||||
// Use temp sensor 1 as a redundant sensor with sensor 0. If the readings
|
||||
// from the two sensors differ too much the print will be aborted.
|
||||
//#define TEMP_SENSOR_1_AS_REDUNDANT
|
||||
#define MAX_REDUNDANT_TEMP_SENSOR_DIFF 10
|
||||
|
||||
#define TEMP_RESIDENCY_TIME 10 // (seconds) Time to wait for hotend to "settle" in M109
|
||||
#define TEMP_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_BED_RESIDENCY_TIME 10 // (seconds) Time to wait for bed to "settle" in M190
|
||||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
#define HEATER_1_MINTEMP 5
|
||||
#define HEATER_2_MINTEMP 5
|
||||
#define HEATER_3_MINTEMP 5
|
||||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
// (Use MINTEMP for thermistor short/failure protection.)
|
||||
#define HEATER_0_MAXTEMP 275
|
||||
#define HEATER_1_MAXTEMP 275
|
||||
#define HEATER_2_MAXTEMP 275
|
||||
#define HEATER_3_MAXTEMP 275
|
||||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
//===========================================================================
|
||||
// PID Tuning Guide here: http://reprap.org/wiki/PID_Tuning
|
||||
|
||||
// Comment the following line to disable PID and enable bang-bang.
|
||||
#define PIDTEMP
|
||||
#define BANG_MAX 255 // Limits current to nozzle while in bang-bang mode; 255=full current
|
||||
#define PID_MAX BANG_MAX // Limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
|
||||
#define PID_K1 0.95 // Smoothing factor within any PID loop
|
||||
#if ENABLED(PIDTEMP)
|
||||
//#define PID_EDIT_MENU // Add PID editing to the "Advanced Settings" menu. (~700 bytes of PROGMEM)
|
||||
//#define PID_AUTOTUNE_MENU // Add PID auto-tuning to the "Advanced Settings" menu. (~250 bytes of PROGMEM)
|
||||
//#define PID_DEBUG // Sends debug data to the serial port.
|
||||
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
|
||||
//#define SLOW_PWM_HEATERS // PWM with very low frequency (roughly 0.125Hz=8s) and minimum state time of approximately 1s useful for heaters driven by a relay
|
||||
//#define PID_PARAMS_PER_HOTEND // Uses separate PID parameters for each extruder (useful for mismatched extruders)
|
||||
// Set/get with gcode: M301 E[extruder number, 0-2]
|
||||
#define PID_FUNCTIONAL_RANGE 10 // If the temperature difference between the target temperature and the actual temperature
|
||||
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
||||
|
||||
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
|
||||
|
||||
// Ultimaker
|
||||
#define DEFAULT_Kp 22.2
|
||||
#define DEFAULT_Ki 1.08
|
||||
#define DEFAULT_Kd 114
|
||||
|
||||
// MakerGear
|
||||
//#define DEFAULT_Kp 7.0
|
||||
//#define DEFAULT_Ki 0.1
|
||||
//#define DEFAULT_Kd 12
|
||||
|
||||
// Mendel Parts V9 on 12V
|
||||
//#define DEFAULT_Kp 63.0
|
||||
//#define DEFAULT_Ki 2.25
|
||||
//#define DEFAULT_Kd 440
|
||||
|
||||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
* PID Bed Heating
|
||||
*
|
||||
* If this option is enabled set PID constants below.
|
||||
* If this option is disabled, bang-bang will be used and BED_LIMIT_SWITCHING will enable hysteresis.
|
||||
*
|
||||
* The PID frequency will be the same as the extruder PWM.
|
||||
* If PID_dT is the default, and correct for the hardware/configuration, that means 7.689Hz,
|
||||
* which is fine for driving a square wave into a resistive load and does not significantly
|
||||
* impact FET heating. This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W
|
||||
* heater. If your configuration is significantly different than this and you don't understand
|
||||
* the issues involved, don't use bed PID until someone else verifies that your hardware works.
|
||||
*/
|
||||
//#define PIDTEMPBED
|
||||
|
||||
//#define BED_LIMIT_SWITCHING
|
||||
|
||||
/**
|
||||
* Max Bed Power
|
||||
* Applies to all forms of bed control (PID, bang-bang, and bang-bang with hysteresis).
|
||||
* When set to any value below 255, enables a form of PWM to the bed that acts like a divider
|
||||
* so don't use it unless you are OK with PWM on your bed. (See the comment on enabling PIDTEMPBED)
|
||||
*/
|
||||
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
||||
|
||||
#if ENABLED(PIDTEMPBED)
|
||||
|
||||
//#define PID_BED_DEBUG // Sends debug data to the serial port.
|
||||
|
||||
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
||||
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
|
||||
#define DEFAULT_bedKp 10.00
|
||||
#define DEFAULT_bedKi .023
|
||||
#define DEFAULT_bedKd 305.4
|
||||
|
||||
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
||||
//from pidautotune
|
||||
//#define DEFAULT_bedKp 97.1
|
||||
//#define DEFAULT_bedKi 1.41
|
||||
//#define DEFAULT_bedKd 1675.16
|
||||
|
||||
// FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles.
|
||||
#endif // PIDTEMPBED
|
||||
|
||||
// @section extruder
|
||||
|
||||
/**
|
||||
* Prevent extrusion if the temperature is below EXTRUDE_MINTEMP.
|
||||
* Add M302 to set the minimum extrusion temperature and/or turn
|
||||
* cold extrusion prevention on and off.
|
||||
*
|
||||
* *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
|
||||
*/
|
||||
#define PREVENT_COLD_EXTRUSION
|
||||
#define EXTRUDE_MINTEMP 170
|
||||
|
||||
/**
|
||||
* Prevent a single extrusion longer than EXTRUDE_MAXLENGTH.
|
||||
* Note: For Bowden Extruders make this large enough to allow load/unload.
|
||||
*/
|
||||
#define PREVENT_LENGTHY_EXTRUDE
|
||||
#define EXTRUDE_MAXLENGTH 200
|
||||
|
||||
//===========================================================================
|
||||
//======================== Thermal Runaway Protection =======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
* Thermal Protection provides additional protection to your printer from damage
|
||||
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||
* protect against a broken or disconnected thermistor wire.
|
||||
*
|
||||
* The issue: If a thermistor falls out, it will report the much lower
|
||||
* temperature of the air in the room, and the the firmware will keep
|
||||
* the heater on.
|
||||
*
|
||||
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||
* details can be tuned in Configuration_adv.h
|
||||
*/
|
||||
|
||||
#define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
|
||||
#define THERMAL_PROTECTION_BED // Enable thermal protection for the heated bed
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
|
||||
//===========================================================================
|
||||
//============================= Mechanical Settings =========================
|
||||
//===========================================================================
|
||||
|
||||
// @section machine
|
||||
|
||||
// Uncomment one of these options to enable CoreXY, CoreXZ, or CoreYZ kinematics
|
||||
// either in the usual order or reversed
|
||||
//#define COREXY
|
||||
//#define COREXZ
|
||||
//#define COREYZ
|
||||
//#define COREYX
|
||||
//#define COREZX
|
||||
//#define COREZY
|
||||
|
||||
//===========================================================================
|
||||
//============================== Endstop Settings ===========================
|
||||
//===========================================================================
|
||||
|
||||
// @section homing
|
||||
|
||||
// Specify here all the endstop connectors that are connected to any endstop or probe.
|
||||
// Almost all printers will be using one per axis. Probes will use one or more of the
|
||||
// extra connectors. Leave undefined any used for non-endstop and non-probe purposes.
|
||||
#define USE_XMIN_PLUG
|
||||
#define USE_YMIN_PLUG
|
||||
#define USE_ZMIN_PLUG
|
||||
//#define USE_XMAX_PLUG
|
||||
//#define USE_YMAX_PLUG
|
||||
//#define USE_ZMAX_PLUG
|
||||
|
||||
// Enable pullup for all endstops to prevent a floating state
|
||||
#define ENDSTOPPULLUPS
|
||||
#if DISABLED(ENDSTOPPULLUPS)
|
||||
// Disable ENDSTOPPULLUPS to set pullups individually
|
||||
//#define ENDSTOPPULLUP_XMAX
|
||||
//#define ENDSTOPPULLUP_YMAX
|
||||
//#define ENDSTOPPULLUP_ZMAX
|
||||
//#define ENDSTOPPULLUP_XMIN
|
||||
//#define ENDSTOPPULLUP_YMIN
|
||||
//#define ENDSTOPPULLUP_ZMIN
|
||||
//#define ENDSTOPPULLUP_ZMIN_PROBE
|
||||
#endif
|
||||
|
||||
// Enable pulldown for all endstops to prevent a floating state
|
||||
//#define ENDSTOPPULLDOWNS
|
||||
#if DISABLED(ENDSTOPPULLDOWNS)
|
||||
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
|
||||
//#define ENDSTOPPULLDOWN_XMAX
|
||||
//#define ENDSTOPPULLDOWN_YMAX
|
||||
//#define ENDSTOPPULLDOWN_ZMAX
|
||||
//#define ENDSTOPPULLDOWN_XMIN
|
||||
//#define ENDSTOPPULLDOWN_YMIN
|
||||
//#define ENDSTOPPULLDOWN_ZMIN
|
||||
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
|
||||
#endif
|
||||
|
||||
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
|
||||
#define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
|
||||
#define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
|
||||
#define Z_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
|
||||
#define X_MAX_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
|
||||
#define Y_MAX_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
|
||||
#define Z_MAX_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
|
||||
#define Z_MIN_PROBE_ENDSTOP_INVERTING false // set to true to invert the logic of the probe.
|
||||
|
||||
/**
|
||||
* Stepper Drivers
|
||||
*
|
||||
* These settings allow Marlin to tune stepper driver timing and enable advanced options for
|
||||
* stepper drivers that support them. You may also override timing options in Configuration_adv.h.
|
||||
*
|
||||
* A4988 is assumed for unspecified drivers.
|
||||
*
|
||||
* Options: A4988, A5984, DRV8825, LV8729, L6470, TB6560, TB6600, TMC2100,
|
||||
* TMC2130, TMC2130_STANDALONE, TMC2208, TMC2208_STANDALONE,
|
||||
* TMC26X, TMC26X_STANDALONE, TMC2660, TMC2660_STANDALONE,
|
||||
* TMC2160, TMC2160_STANDALONE, TMC5130, TMC5130_STANDALONE,
|
||||
* TMC5160, TMC5160_STANDALONE
|
||||
* :['A4988', 'A5984', 'DRV8825', 'LV8729', 'L6470', 'TB6560', 'TB6600', 'TMC2100', 'TMC2130', 'TMC2130_STANDALONE', 'TMC2160', 'TMC2160_STANDALONE', 'TMC2208', 'TMC2208_STANDALONE', 'TMC26X', 'TMC26X_STANDALONE', 'TMC2660', 'TMC2660_STANDALONE', 'TMC5130', 'TMC5130_STANDALONE', 'TMC5160', 'TMC5160_STANDALONE']
|
||||
*/
|
||||
//#define X_DRIVER_TYPE A4988
|
||||
//#define Y_DRIVER_TYPE A4988
|
||||
//#define Z_DRIVER_TYPE A4988
|
||||
//#define X2_DRIVER_TYPE A4988
|
||||
//#define Y2_DRIVER_TYPE A4988
|
||||
//#define Z2_DRIVER_TYPE A4988
|
||||
//#define Z3_DRIVER_TYPE A4988
|
||||
//#define E0_DRIVER_TYPE A4988
|
||||
//#define E1_DRIVER_TYPE A4988
|
||||
//#define E2_DRIVER_TYPE A4988
|
||||
//#define E3_DRIVER_TYPE A4988
|
||||
//#define E4_DRIVER_TYPE A4988
|
||||
//#define E5_DRIVER_TYPE A4988
|
||||
|
||||
// Enable this feature if all enabled endstop pins are interrupt-capable.
|
||||
// This will remove the need to poll the interrupt pins, saving many CPU cycles.
|
||||
#define ENDSTOP_INTERRUPTS_FEATURE
|
||||
|
||||
/**
|
||||
* Endstop Noise Threshold
|
||||
*
|
||||
* Enable if your probe or endstops falsely trigger due to noise.
|
||||
*
|
||||
* - Higher values may affect repeatability or accuracy of some bed probes.
|
||||
* - To fix noise install a 100nF ceramic capacitor inline with the switch.
|
||||
* - This feature is not required for common micro-switches mounted on PCBs
|
||||
* based on the Makerbot design, which already have the 100nF capacitor.
|
||||
*
|
||||
* :[2,3,4,5,6,7]
|
||||
*/
|
||||
//#define ENDSTOP_NOISE_THRESHOLD 2
|
||||
|
||||
//=============================================================================
|
||||
//============================== Movement Settings ============================
|
||||
//=============================================================================
|
||||
// @section motion
|
||||
|
||||
/**
|
||||
* Default Settings
|
||||
*
|
||||
* These settings can be reset by M502
|
||||
*
|
||||
* Note that if EEPROM is enabled, saved values will override these.
|
||||
*/
|
||||
|
||||
/**
|
||||
* With this option each E stepper can have its own factors for the
|
||||
* following movement settings. If fewer factors are given than the
|
||||
* total number of extruders, the last value applies to the rest.
|
||||
*/
|
||||
//#define DISTINCT_E_FACTORS
|
||||
|
||||
/**
|
||||
* Default Axis Steps Per Unit (steps/mm)
|
||||
* Override with M92
|
||||
* X, Y, Z, E0 [, E1[, E2[, E3[, E4[, E5]]]]]
|
||||
*/
|
||||
#define DEFAULT_AXIS_STEPS_PER_UNIT { 80, 80, 4000, 500 }
|
||||
|
||||
/**
|
||||
* Default Max Feed Rate (mm/s)
|
||||
* Override with M203
|
||||
* X, Y, Z, E0 [, E1[, E2[, E3[, E4[, E5]]]]]
|
||||
*/
|
||||
#define DEFAULT_MAX_FEEDRATE { 300, 300, 5, 25 }
|
||||
|
||||
/**
|
||||
* Default Max Acceleration (change/s) change = mm/s
|
||||
* (Maximum start speed for accelerated moves)
|
||||
* Override with M201
|
||||
* X, Y, Z, E0 [, E1[, E2[, E3[, E4[, E5]]]]]
|
||||
*/
|
||||
#define DEFAULT_MAX_ACCELERATION { 3000, 3000, 100, 10000 }
|
||||
|
||||
/**
|
||||
* Default Acceleration (change/s) change = mm/s
|
||||
* Override with M204
|
||||
*
|
||||
* M204 P Acceleration
|
||||
* M204 R Retract Acceleration
|
||||
* M204 T Travel Acceleration
|
||||
*/
|
||||
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E acceleration for printing moves
|
||||
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration for retracts
|
||||
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration for travel (non printing) moves
|
||||
|
||||
//
|
||||
// Use Junction Deviation instead of traditional Jerk Limiting
|
||||
//
|
||||
//#define JUNCTION_DEVIATION
|
||||
#if ENABLED(JUNCTION_DEVIATION)
|
||||
#define JUNCTION_DEVIATION_MM 0.02 // (mm) Distance from real junction edge
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Default Jerk (mm/s)
|
||||
* Override with M205 X Y Z E
|
||||
*
|
||||
* "Jerk" specifies the minimum speed change that requires acceleration.
|
||||
* When changing speed and direction, if the difference is less than the
|
||||
* value set here, it may happen instantaneously.
|
||||
*/
|
||||
#if DISABLED(JUNCTION_DEVIATION)
|
||||
#define DEFAULT_XJERK 10.0
|
||||
#define DEFAULT_YJERK 10.0
|
||||
#define DEFAULT_ZJERK 0.3
|
||||
#endif
|
||||
|
||||
#define DEFAULT_EJERK 5.0 // May be used by Linear Advance
|
||||
|
||||
/**
|
||||
* S-Curve Acceleration
|
||||
*
|
||||
* This option eliminates vibration during printing by fitting a Bézier
|
||||
* curve to move acceleration, producing much smoother direction changes.
|
||||
*
|
||||
* See https://github.com/synthetos/TinyG/wiki/Jerk-Controlled-Motion-Explained
|
||||
*/
|
||||
//#define S_CURVE_ACCELERATION
|
||||
|
||||
//===========================================================================
|
||||
//============================= Z Probe Options =============================
|
||||
//===========================================================================
|
||||
// @section probes
|
||||
|
||||
//
|
||||
// See http://marlinfw.org/docs/configuration/probes.html
|
||||
//
|
||||
|
||||
/**
|
||||
* Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
|
||||
*
|
||||
* Enable this option for a probe connected to the Z Min endstop pin.
|
||||
*/
|
||||
#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
|
||||
|
||||
/**
|
||||
* Z_MIN_PROBE_PIN
|
||||
*
|
||||
* Define this pin if the probe is not connected to Z_MIN_PIN.
|
||||
* If not defined the default pin for the selected MOTHERBOARD
|
||||
* will be used. Most of the time the default is what you want.
|
||||
*
|
||||
* - The simplest option is to use a free endstop connector.
|
||||
* - Use 5V for powered (usually inductive) sensors.
|
||||
*
|
||||
* - RAMPS 1.3/1.4 boards may use the 5V, GND, and Aux4->D32 pin:
|
||||
* - For simple switches connect...
|
||||
* - normally-closed switches to GND and D32.
|
||||
* - normally-open switches to 5V and D32.
|
||||
*
|
||||
*/
|
||||
//#define Z_MIN_PROBE_PIN 32 // Pin 32 is the RAMPS default
|
||||
|
||||
/**
|
||||
* Probe Type
|
||||
*
|
||||
* Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, etc.
|
||||
* Activate one of these to use Auto Bed Leveling below.
|
||||
*/
|
||||
|
||||
/**
|
||||
* The "Manual Probe" provides a means to do "Auto" Bed Leveling without a probe.
|
||||
* Use G29 repeatedly, adjusting the Z height at each point with movement commands
|
||||
* or (with LCD_BED_LEVELING) the LCD controller.
|
||||
*/
|
||||
//#define PROBE_MANUALLY
|
||||
//#define MANUAL_PROBE_START_Z 0.2
|
||||
|
||||
/**
|
||||
* A Fix-Mounted Probe either doesn't deploy or needs manual deployment.
|
||||
* (e.g., an inductive probe or a nozzle-based probe-switch.)
|
||||
*/
|
||||
//#define FIX_MOUNTED_PROBE
|
||||
|
||||
/**
|
||||
* Z Servo Probe, such as an endstop switch on a rotating arm.
|
||||
*/
|
||||
//#define Z_PROBE_SERVO_NR 0 // Defaults to SERVO 0 connector.
|
||||
//#define Z_SERVO_ANGLES {70,0} // Z Servo Deploy and Stow angles
|
||||
|
||||
/**
|
||||
* The BLTouch probe uses a Hall effect sensor and emulates a servo.
|
||||
*/
|
||||
//#define BLTOUCH
|
||||
#if ENABLED(BLTOUCH)
|
||||
//#define BLTOUCH_DELAY 375 // (ms) Enable and increase if needed
|
||||
|
||||
/**
|
||||
* BLTouch V3.0 and newer smart series
|
||||
* For genuine BLTouch 3.0 sensors. Clones may be confused by 3.0 command angles. YMMV.
|
||||
* If the pin trigger is not detected, first try swapping the black and white wires then toggle this.
|
||||
*/
|
||||
//#define BLTOUCH_V3
|
||||
#if ENABLED(BLTOUCH_V3)
|
||||
//#define BLTOUCH_FORCE_5V_MODE
|
||||
//#define BLTOUCH_FORCE_OPEN_DRAIN_MODE
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// A probe that is deployed and stowed with a solenoid pin (SOL1_PIN)
|
||||
//#define SOLENOID_PROBE
|
||||
|
||||
// A sled-mounted probe like those designed by Charles Bell.
|
||||
//#define Z_PROBE_SLED
|
||||
//#define SLED_DOCKING_OFFSET 5 // The extra distance the X axis must travel to pickup the sled. 0 should be fine but you can push it further if you'd like.
|
||||
|
||||
// A probe deployed by moving the x-axis, such as the Wilson II's rack-and-pinion probe designed by Marty Rice.
|
||||
//#define RACK_AND_PINION_PROBE
|
||||
#if ENABLED(RACK_AND_PINION_PROBE)
|
||||
#define Z_PROBE_DEPLOY_X X_MIN_POS
|
||||
#define Z_PROBE_RETRACT_X X_MAX_POS
|
||||
#endif
|
||||
|
||||
//
|
||||
// For Z_PROBE_ALLEN_KEY see the Delta example configurations.
|
||||
//
|
||||
|
||||
/**
|
||||
* Z Probe to nozzle (X,Y) offset, relative to (0, 0).
|
||||
* X and Y offsets must be integers.
|
||||
*
|
||||
* In the following example the X and Y offsets are both positive:
|
||||
* #define X_PROBE_OFFSET_FROM_EXTRUDER 10
|
||||
* #define Y_PROBE_OFFSET_FROM_EXTRUDER 10
|
||||
*
|
||||
* +-- BACK ---+
|
||||
* | |
|
||||
* L | (+) P | R <-- probe (20,20)
|
||||
* E | | I
|
||||
* F | (-) N (+) | G <-- nozzle (10,10)
|
||||
* T | | H
|
||||
* | (-) | T
|
||||
* | |
|
||||
* O-- FRONT --+
|
||||
* (0,0)
|
||||
*/
|
||||
#define X_PROBE_OFFSET_FROM_EXTRUDER 10 // X offset: -left +right [of the nozzle]
|
||||
#define Y_PROBE_OFFSET_FROM_EXTRUDER 10 // Y offset: -front +behind [the nozzle]
|
||||
#define Z_PROBE_OFFSET_FROM_EXTRUDER 0 // Z offset: -below +above [the nozzle]
|
||||
|
||||
// Certain types of probes need to stay away from edges
|
||||
#define MIN_PROBE_EDGE 10
|
||||
|
||||
// X and Y axis travel speed (mm/m) between probes
|
||||
#define XY_PROBE_SPEED 8000
|
||||
|
||||
// Feedrate (mm/m) for the first approach when double-probing (MULTIPLE_PROBING == 2)
|
||||
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
||||
|
||||
// Feedrate (mm/m) for the "accurate" probe of each point
|
||||
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
||||
|
||||
// The number of probes to perform at each point.
|
||||
// Set to 2 for a fast/slow probe, using the second probe result.
|
||||
// Set to 3 or more for slow probes, averaging the results.
|
||||
//#define MULTIPLE_PROBING 2
|
||||
|
||||
/**
|
||||
* Z probes require clearance when deploying, stowing, and moving between
|
||||
* probe points to avoid hitting the bed and other hardware.
|
||||
* Servo-mounted probes require extra space for the arm to rotate.
|
||||
* Inductive probes need space to keep from triggering early.
|
||||
*
|
||||
* Use these settings to specify the distance (mm) to raise the probe (or
|
||||
* lower the bed). The values set here apply over and above any (negative)
|
||||
* probe Z Offset set with Z_PROBE_OFFSET_FROM_EXTRUDER, M851, or the LCD.
|
||||
* Only integer values >= 1 are valid here.
|
||||
*
|
||||
* Example: `M851 Z-5` with a CLEARANCE of 4 => 9mm from bed to nozzle.
|
||||
* But: `M851 Z+1` with a CLEARANCE of 2 => 2mm from bed to nozzle.
|
||||
*/
|
||||
#define Z_CLEARANCE_DEPLOY_PROBE 10 // Z Clearance for Deploy/Stow
|
||||
#define Z_CLEARANCE_BETWEEN_PROBES 5 // Z Clearance between probe points
|
||||
#define Z_CLEARANCE_MULTI_PROBE 5 // Z Clearance between multiple probes
|
||||
//#define Z_AFTER_PROBING 5 // Z position after probing is done
|
||||
|
||||
#define Z_PROBE_LOW_POINT -2 // Farthest distance below the trigger-point to go before stopping
|
||||
|
||||
// For M851 give a range for adjusting the Z probe offset
|
||||
#define Z_PROBE_OFFSET_RANGE_MIN -20
|
||||
#define Z_PROBE_OFFSET_RANGE_MAX 20
|
||||
|
||||
// Enable the M48 repeatability test to test probe accuracy
|
||||
//#define Z_MIN_PROBE_REPEATABILITY_TEST
|
||||
|
||||
// Before deploy/stow pause for user confirmation
|
||||
//#define PAUSE_BEFORE_DEPLOY_STOW
|
||||
|
||||
/**
|
||||
* Enable one or more of the following if probing seems unreliable.
|
||||
* Heaters and/or fans can be disabled during probing to minimize electrical
|
||||
* noise. A delay can also be added to allow noise and vibration to settle.
|
||||
* These options are most useful for the BLTouch probe, but may also improve
|
||||
* readings with inductive probes and piezo sensors.
|
||||
*/
|
||||
//#define PROBING_HEATERS_OFF // Turn heaters off when probing
|
||||
#if ENABLED(PROBING_HEATERS_OFF)
|
||||
//#define WAIT_FOR_BED_HEATER // Wait for bed to heat back up between probes (to improve accuracy)
|
||||
#endif
|
||||
//#define PROBING_FANS_OFF // Turn fans off when probing
|
||||
//#define PROBING_STEPPERS_OFF // Turn steppers off (unless needed to hold position) when probing
|
||||
//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors
|
||||
|
||||
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
|
||||
// :{ 0:'Low', 1:'High' }
|
||||
#define X_ENABLE_ON 0
|
||||
#define Y_ENABLE_ON 0
|
||||
#define Z_ENABLE_ON 0
|
||||
#define E_ENABLE_ON 0 // For all extruders
|
||||
|
||||
// Disables axis stepper immediately when it's not being used.
|
||||
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
||||
#define DISABLE_X false
|
||||
#define DISABLE_Y false
|
||||
#define DISABLE_Z false
|
||||
|
||||
// Warn on display about possibly reduced accuracy
|
||||
//#define DISABLE_REDUCED_ACCURACY_WARNING
|
||||
|
||||
// @section extruder
|
||||
|
||||
#define DISABLE_E false // For all extruders
|
||||
#define DISABLE_INACTIVE_EXTRUDER // Keep only the active extruder enabled
|
||||
|
||||
// @section machine
|
||||
|
||||
// Invert the stepper direction. Change (or reverse the motor connector) if an axis goes the wrong way.
|
||||
#define INVERT_X_DIR false
|
||||
#define INVERT_Y_DIR true
|
||||
#define INVERT_Z_DIR false
|
||||
|
||||
// @section extruder
|
||||
|
||||
// For direct drive extruder v9 set to true, for geared extruder set to false.
|
||||
#define INVERT_E0_DIR false
|
||||
#define INVERT_E1_DIR false
|
||||
#define INVERT_E2_DIR false
|
||||
#define INVERT_E3_DIR false
|
||||
#define INVERT_E4_DIR false
|
||||
#define INVERT_E5_DIR false
|
||||
|
||||
// @section homing
|
||||
|
||||
//#define NO_MOTION_BEFORE_HOMING // Inhibit movement until all axes have been homed
|
||||
|
||||
//#define UNKNOWN_Z_NO_RAISE // Don't raise Z (lower the bed) if Z is "unknown." For beds that fall when Z is powered off.
|
||||
|
||||
//#define Z_HOMING_HEIGHT 4 // (mm) Minimal Z height before homing (G28) for Z clearance above the bed, clamps, ...
|
||||
// Be sure you have this distance over your Z_MAX_POS in case.
|
||||
|
||||
// Direction of endstops when homing; 1=MAX, -1=MIN
|
||||
// :[-1,1]
|
||||
#define X_HOME_DIR -1
|
||||
#define Y_HOME_DIR -1
|
||||
#define Z_HOME_DIR -1
|
||||
|
||||
// @section machine
|
||||
|
||||
// The size of the print bed
|
||||
#define X_BED_SIZE 200
|
||||
#define Y_BED_SIZE 200
|
||||
|
||||
// Travel limits (mm) after homing, corresponding to endstop positions.
|
||||
#define X_MIN_POS 0
|
||||
#define Y_MIN_POS 0
|
||||
#define Z_MIN_POS 0
|
||||
#define X_MAX_POS X_BED_SIZE
|
||||
#define Y_MAX_POS Y_BED_SIZE
|
||||
#define Z_MAX_POS 200
|
||||
|
||||
/**
|
||||
* Software Endstops
|
||||
*
|
||||
* - Prevent moves outside the set machine bounds.
|
||||
* - Individual axes can be disabled, if desired.
|
||||
* - X and Y only apply to Cartesian robots.
|
||||
* - Use 'M211' to set software endstops on/off or report current state
|
||||
*/
|
||||
|
||||
// Min software endstops constrain movement within minimum coordinate bounds
|
||||
#define MIN_SOFTWARE_ENDSTOPS
|
||||
#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
|
||||
#define MIN_SOFTWARE_ENDSTOP_X
|
||||
#define MIN_SOFTWARE_ENDSTOP_Y
|
||||
#define MIN_SOFTWARE_ENDSTOP_Z
|
||||
#endif
|
||||
|
||||
// Max software endstops constrain movement within maximum coordinate bounds
|
||||
#define MAX_SOFTWARE_ENDSTOPS
|
||||
#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
|
||||
#define MAX_SOFTWARE_ENDSTOP_X
|
||||
#define MAX_SOFTWARE_ENDSTOP_Y
|
||||
#define MAX_SOFTWARE_ENDSTOP_Z
|
||||
#endif
|
||||
|
||||
#if EITHER(MIN_SOFTWARE_ENDSTOPS, MAX_SOFTWARE_ENDSTOPS)
|
||||
//#define SOFT_ENDSTOPS_MENU_ITEM // Enable/Disable software endstops from the LCD
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Filament Runout Sensors
|
||||
* Mechanical or opto endstops are used to check for the presence of filament.
|
||||
*
|
||||
* RAMPS-based boards use SERVO3_PIN for the first runout sensor.
|
||||
* For other boards you may need to define FIL_RUNOUT_PIN, FIL_RUNOUT2_PIN, etc.
|
||||
* By default the firmware assumes HIGH=FILAMENT PRESENT.
|
||||
*/
|
||||
//#define FILAMENT_RUNOUT_SENSOR
|
||||
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
|
||||
#define NUM_RUNOUT_SENSORS 1 // Number of sensors, up to one per extruder. Define a FIL_RUNOUT#_PIN for each.
|
||||
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
|
||||
#define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
|
||||
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
|
||||
|
||||
// Set one or more commands to execute on filament runout.
|
||||
// (After 'M412 H' Marlin will ask the host to handle the process.)
|
||||
#define FILAMENT_RUNOUT_SCRIPT "M600"
|
||||
|
||||
// After a runout is detected, continue printing this length of filament
|
||||
// before executing the runout script. Useful for a sensor at the end of
|
||||
// a feed tube. Requires 4 bytes SRAM per sensor, plus 4 bytes overhead.
|
||||
//#define FILAMENT_RUNOUT_DISTANCE_MM 25
|
||||
|
||||
#ifdef FILAMENT_RUNOUT_DISTANCE_MM
|
||||
// Enable this option to use an encoder disc that toggles the runout pin
|
||||
// as the filament moves. (Be sure to set FILAMENT_RUNOUT_DISTANCE_MM
|
||||
// large enough to avoid false positives.)
|
||||
//#define FILAMENT_MOTION_SENSOR
|
||||
#endif
|
||||
#endif
|
||||
|
||||
//===========================================================================
|
||||
//=============================== Bed Leveling ==============================
|
||||
//===========================================================================
|
||||
// @section calibrate
|
||||
|
||||
/**
|
||||
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
||||
* and behavior of G29 will change depending on your selection.
|
||||
*
|
||||
* If using a Probe for Z Homing, enable Z_SAFE_HOMING also!
|
||||
*
|
||||
* - AUTO_BED_LEVELING_3POINT
|
||||
* Probe 3 arbitrary points on the bed (that aren't collinear)
|
||||
* You specify the XY coordinates of all 3 points.
|
||||
* The result is a single tilted plane. Best for a flat bed.
|
||||
*
|
||||
* - AUTO_BED_LEVELING_LINEAR
|
||||
* Probe several points in a grid.
|
||||
* You specify the rectangle and the density of sample points.
|
||||
* The result is a single tilted plane. Best for a flat bed.
|
||||
*
|
||||
* - AUTO_BED_LEVELING_BILINEAR
|
||||
* Probe several points in a grid.
|
||||
* You specify the rectangle and the density of sample points.
|
||||
* The result is a mesh, best for large or uneven beds.
|
||||
*
|
||||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||
* A comprehensive bed leveling system combining the features and benefits
|
||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||
* Validation and Mesh Editing systems.
|
||||
*
|
||||
* - MESH_BED_LEVELING
|
||||
* Probe a grid manually
|
||||
* The result is a mesh, suitable for large or uneven beds. (See BILINEAR.)
|
||||
* For machines without a probe, Mesh Bed Leveling provides a method to perform
|
||||
* leveling in steps so you can manually adjust the Z height at each grid-point.
|
||||
* With an LCD controller the process is guided step-by-step.
|
||||
*/
|
||||
//#define AUTO_BED_LEVELING_3POINT
|
||||
//#define AUTO_BED_LEVELING_LINEAR
|
||||
//#define AUTO_BED_LEVELING_BILINEAR
|
||||
//#define AUTO_BED_LEVELING_UBL
|
||||
//#define MESH_BED_LEVELING
|
||||
|
||||
/**
|
||||
* Normally G28 leaves leveling disabled on completion. Enable
|
||||
* this option to have G28 restore the prior leveling state.
|
||||
*/
|
||||
//#define RESTORE_LEVELING_AFTER_G28
|
||||
|
||||
/**
|
||||
* Enable detailed logging of G28, G29, M48, etc.
|
||||
* Turn on with the command 'M111 S32'.
|
||||
* NOTE: Requires a lot of PROGMEM!
|
||||
*/
|
||||
//#define DEBUG_LEVELING_FEATURE
|
||||
|
||||
#if ANY(MESH_BED_LEVELING, AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_UBL)
|
||||
// Gradually reduce leveling correction until a set height is reached,
|
||||
// at which point movement will be level to the machine's XY plane.
|
||||
// The height can be set with M420 Z<height>
|
||||
#define ENABLE_LEVELING_FADE_HEIGHT
|
||||
|
||||
// For Cartesian machines, instead of dividing moves on mesh boundaries,
|
||||
// split up moves into short segments like a Delta. This follows the
|
||||
// contours of the bed more closely than edge-to-edge straight moves.
|
||||
#define SEGMENT_LEVELED_MOVES
|
||||
#define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
|
||||
|
||||
/**
|
||||
* Enable the G26 Mesh Validation Pattern tool.
|
||||
*/
|
||||
//#define G26_MESH_VALIDATION
|
||||
#if ENABLED(G26_MESH_VALIDATION)
|
||||
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
|
||||
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
|
||||
#define MESH_TEST_HOTEND_TEMP 205 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
|
||||
#define MESH_TEST_BED_TEMP 60 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
|
||||
#define G26_XY_FEEDRATE 20 // (mm/s) Feedrate for XY Moves for the G26 Mesh Validation Tool.
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
#if EITHER(AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_BILINEAR)
|
||||
|
||||
// Set the number of grid points per dimension.
|
||||
#define GRID_MAX_POINTS_X 3
|
||||
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
||||
|
||||
// Set the boundaries for probing (where the probe can reach).
|
||||
//#define LEFT_PROBE_BED_POSITION MIN_PROBE_EDGE
|
||||
//#define RIGHT_PROBE_BED_POSITION (X_BED_SIZE - (MIN_PROBE_EDGE))
|
||||
//#define FRONT_PROBE_BED_POSITION MIN_PROBE_EDGE
|
||||
//#define BACK_PROBE_BED_POSITION (Y_BED_SIZE - (MIN_PROBE_EDGE))
|
||||
|
||||
// Probe along the Y axis, advancing X after each column
|
||||
//#define PROBE_Y_FIRST
|
||||
|
||||
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||
|
||||
// Beyond the probed grid, continue the implied tilt?
|
||||
// Default is to maintain the height of the nearest edge.
|
||||
//#define EXTRAPOLATE_BEYOND_GRID
|
||||
|
||||
//
|
||||
// Experimental Subdivision of the grid by Catmull-Rom method.
|
||||
// Synthesizes intermediate points to produce a more detailed mesh.
|
||||
//
|
||||
//#define ABL_BILINEAR_SUBDIVISION
|
||||
#if ENABLED(ABL_BILINEAR_SUBDIVISION)
|
||||
// Number of subdivisions between probe points
|
||||
#define BILINEAR_SUBDIVISIONS 3
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
#elif ENABLED(AUTO_BED_LEVELING_UBL)
|
||||
|
||||
//===========================================================================
|
||||
//========================= Unified Bed Leveling ============================
|
||||
//===========================================================================
|
||||
|
||||
//#define MESH_EDIT_GFX_OVERLAY // Display a graphics overlay while editing the mesh
|
||||
|
||||
#define MESH_INSET 1 // Set Mesh bounds as an inset region of the bed
|
||||
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
||||
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
||||
|
||||
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
||||
#define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500
|
||||
|
||||
//#define UBL_Z_RAISE_WHEN_OFF_MESH 2.5 // When the nozzle is off the mesh, this value is used
|
||||
// as the Z-Height correction value.
|
||||
|
||||
#elif ENABLED(MESH_BED_LEVELING)
|
||||
|
||||
//===========================================================================
|
||||
//=================================== Mesh ==================================
|
||||
//===========================================================================
|
||||
|
||||
#define MESH_INSET 10 // Set Mesh bounds as an inset region of the bed
|
||||
#define GRID_MAX_POINTS_X 3 // Don't use more than 7 points per axis, implementation limited.
|
||||
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
||||
|
||||
//#define MESH_G28_REST_ORIGIN // After homing all axes ('G28' or 'G28 XYZ') rest Z at Z_MIN_POS
|
||||
|
||||
#endif // BED_LEVELING
|
||||
|
||||
/**
|
||||
* Points to probe for all 3-point Leveling procedures.
|
||||
* Override if the automatically selected points are inadequate.
|
||||
*/
|
||||
#if EITHER(AUTO_BED_LEVELING_3POINT, AUTO_BED_LEVELING_UBL)
|
||||
//#define PROBE_PT_1_X 15
|
||||
//#define PROBE_PT_1_Y 180
|
||||
//#define PROBE_PT_2_X 15
|
||||
//#define PROBE_PT_2_Y 20
|
||||
//#define PROBE_PT_3_X 170
|
||||
//#define PROBE_PT_3_Y 20
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Add a bed leveling sub-menu for ABL or MBL.
|
||||
* Include a guided procedure if manual probing is enabled.
|
||||
*/
|
||||
//#define LCD_BED_LEVELING
|
||||
|
||||
#if ENABLED(LCD_BED_LEVELING)
|
||||
#define MESH_EDIT_Z_STEP 0.025 // (mm) Step size while manually probing Z axis.
|
||||
#define LCD_PROBE_Z_RANGE 4 // (mm) Z Range centered on Z_MIN_POS for LCD Z adjustment
|
||||
//#define MESH_EDIT_MENU // Add a menu to edit mesh points
|
||||
#endif
|
||||
|
||||
// Add a menu item to move between bed corners for manual bed adjustment
|
||||
//#define LEVEL_BED_CORNERS
|
||||
|
||||
#if ENABLED(LEVEL_BED_CORNERS)
|
||||
#define LEVEL_CORNERS_INSET 30 // (mm) An inset for corner leveling
|
||||
#define LEVEL_CORNERS_Z_HOP 4.0 // (mm) Move nozzle up before moving between corners
|
||||
#define LEVEL_CORNERS_HEIGHT 0.0 // (mm) Z height of nozzle at leveling points
|
||||
//#define LEVEL_CENTER_TOO // Move to the center after the last corner
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Commands to execute at the end of G29 probing.
|
||||
* Useful to retract or move the Z probe out of the way.
|
||||
*/
|
||||
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10"
|
||||
|
||||
|
||||
// @section homing
|
||||
|
||||
// The center of the bed is at (X=0, Y=0)
|
||||
//#define BED_CENTER_AT_0_0
|
||||
|
||||
// Manually set the home position. Leave these undefined for automatic settings.
|
||||
// For DELTA this is the top-center of the Cartesian print volume.
|
||||
//#define MANUAL_X_HOME_POS 0
|
||||
//#define MANUAL_Y_HOME_POS 0
|
||||
//#define MANUAL_Z_HOME_POS 0
|
||||
|
||||
// Use "Z Safe Homing" to avoid homing with a Z probe outside the bed area.
|
||||
//
|
||||
// With this feature enabled:
|
||||
//
|
||||
// - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
|
||||
// - If stepper drivers time out, it will need X and Y homing again before Z homing.
|
||||
// - Move the Z probe (or nozzle) to a defined XY point before Z Homing when homing all axes (G28).
|
||||
// - Prevent Z homing when the Z probe is outside bed area.
|
||||
//
|
||||
//#define Z_SAFE_HOMING
|
||||
|
||||
#if ENABLED(Z_SAFE_HOMING)
|
||||
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axes (G28).
|
||||
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axes (G28).
|
||||
#endif
|
||||
|
||||
// Homing speeds (mm/m)
|
||||
#define HOMING_FEEDRATE_XY (50*60)
|
||||
#define HOMING_FEEDRATE_Z (4*60)
|
||||
|
||||
// Validate that endstops are triggered on homing moves
|
||||
#define VALIDATE_HOMING_ENDSTOPS
|
||||
|
||||
// @section calibrate
|
||||
|
||||
/**
|
||||
* Bed Skew Compensation
|
||||
*
|
||||
* This feature corrects for misalignment in the XYZ axes.
|
||||
*
|
||||
* Take the following steps to get the bed skew in the XY plane:
|
||||
* 1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
|
||||
* 2. For XY_DIAG_AC measure the diagonal A to C
|
||||
* 3. For XY_DIAG_BD measure the diagonal B to D
|
||||
* 4. For XY_SIDE_AD measure the edge A to D
|
||||
*
|
||||
* Marlin automatically computes skew factors from these measurements.
|
||||
* Skew factors may also be computed and set manually:
|
||||
*
|
||||
* - Compute AB : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
|
||||
* - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
|
||||
*
|
||||
* If desired, follow the same procedure for XZ and YZ.
|
||||
* Use these diagrams for reference:
|
||||
*
|
||||
* Y Z Z
|
||||
* ^ B-------C ^ B-------C ^ B-------C
|
||||
* | / / | / / | / /
|
||||
* | / / | / / | / /
|
||||
* | A-------D | A-------D | A-------D
|
||||
* +-------------->X +-------------->X +-------------->Y
|
||||
* XY_SKEW_FACTOR XZ_SKEW_FACTOR YZ_SKEW_FACTOR
|
||||
*/
|
||||
//#define SKEW_CORRECTION
|
||||
|
||||
#if ENABLED(SKEW_CORRECTION)
|
||||
// Input all length measurements here:
|
||||
#define XY_DIAG_AC 282.8427124746
|
||||
#define XY_DIAG_BD 282.8427124746
|
||||
#define XY_SIDE_AD 200
|
||||
|
||||
// Or, set the default skew factors directly here
|
||||
// to override the above measurements:
|
||||
#define XY_SKEW_FACTOR 0.0
|
||||
|
||||
//#define SKEW_CORRECTION_FOR_Z
|
||||
#if ENABLED(SKEW_CORRECTION_FOR_Z)
|
||||
#define XZ_DIAG_AC 282.8427124746
|
||||
#define XZ_DIAG_BD 282.8427124746
|
||||
#define YZ_DIAG_AC 282.8427124746
|
||||
#define YZ_DIAG_BD 282.8427124746
|
||||
#define YZ_SIDE_AD 200
|
||||
#define XZ_SKEW_FACTOR 0.0
|
||||
#define YZ_SKEW_FACTOR 0.0
|
||||
#endif
|
||||
|
||||
// Enable this option for M852 to set skew at runtime
|
||||
//#define SKEW_CORRECTION_GCODE
|
||||
#endif
|
||||
|
||||
//=============================================================================
|
||||
//============================= Additional Features ===========================
|
||||
//=============================================================================
|
||||
|
||||
// @section extras
|
||||
|
||||
//
|
||||
// EEPROM
|
||||
//
|
||||
// The microcontroller can store settings in the EEPROM, e.g. max velocity...
|
||||
// M500 - stores parameters in EEPROM
|
||||
// M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily).
|
||||
// M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to.
|
||||
//
|
||||
#define EEPROM_SETTINGS // Enable for M500 and M501 commands
|
||||
//#define DISABLE_M503 // Saves ~2700 bytes of PROGMEM. Disable for release!
|
||||
#define EEPROM_CHITCHAT // Give feedback on EEPROM commands. Disable to save PROGMEM.
|
||||
|
||||
//
|
||||
// Host Keepalive
|
||||
//
|
||||
// When enabled Marlin will send a busy status message to the host
|
||||
// every couple of seconds when it can't accept commands.
|
||||
//
|
||||
#define HOST_KEEPALIVE_FEATURE // Disable this if your host doesn't like keepalive messages
|
||||
#define DEFAULT_KEEPALIVE_INTERVAL 2 // Number of seconds between "busy" messages. Set with M113.
|
||||
#define BUSY_WHILE_HEATING // Some hosts require "busy" messages even during heating
|
||||
|
||||
//
|
||||
// M100 Free Memory Watcher
|
||||
//
|
||||
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||
|
||||
//
|
||||
// G20/G21 Inch mode support
|
||||
//
|
||||
//#define INCH_MODE_SUPPORT
|
||||
|
||||
//
|
||||
// M149 Set temperature units support
|
||||
//
|
||||
//#define TEMPERATURE_UNITS_SUPPORT
|
||||
|
||||
// @section temperature
|
||||
|
||||
// Preheat Constants
|
||||
#define PREHEAT_1_LABEL "PLA"
|
||||
#define PREHEAT_1_TEMP_HOTEND 180
|
||||
#define PREHEAT_1_TEMP_BED 70
|
||||
#define PREHEAT_1_FAN_SPEED 0 // Value from 0 to 255
|
||||
|
||||
#define PREHEAT_2_LABEL "ABS"
|
||||
#define PREHEAT_2_TEMP_HOTEND 240
|
||||
#define PREHEAT_2_TEMP_BED 110
|
||||
#define PREHEAT_2_FAN_SPEED 0 // Value from 0 to 255
|
||||
|
||||
/**
|
||||
* Nozzle Park
|
||||
*
|
||||
* Park the nozzle at the given XYZ position on idle or G27.
|
||||
*
|
||||
* The "P" parameter controls the action applied to the Z axis:
|
||||
*
|
||||
* P0 (Default) If Z is below park Z raise the nozzle.
|
||||
* P1 Raise the nozzle always to Z-park height.
|
||||
* P2 Raise the nozzle by Z-park amount, limited to Z_MAX_POS.
|
||||
*/
|
||||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Clean Nozzle Feature -- EXPERIMENTAL
|
||||
*
|
||||
* Adds the G12 command to perform a nozzle cleaning process.
|
||||
*
|
||||
* Parameters:
|
||||
* P Pattern
|
||||
* S Strokes / Repetitions
|
||||
* T Triangles (P1 only)
|
||||
*
|
||||
* Patterns:
|
||||
* P0 Straight line (default). This process requires a sponge type material
|
||||
* at a fixed bed location. "S" specifies strokes (i.e. back-forth motions)
|
||||
* between the start / end points.
|
||||
*
|
||||
* P1 Zig-zag pattern between (X0, Y0) and (X1, Y1), "T" specifies the
|
||||
* number of zig-zag triangles to do. "S" defines the number of strokes.
|
||||
* Zig-zags are done in whichever is the narrower dimension.
|
||||
* For example, "G12 P1 S1 T3" will execute:
|
||||
*
|
||||
* --
|
||||
* | (X0, Y1) | /\ /\ /\ | (X1, Y1)
|
||||
* | | / \ / \ / \ |
|
||||
* A | | / \ / \ / \ |
|
||||
* | | / \ / \ / \ |
|
||||
* | (X0, Y0) | / \/ \/ \ | (X1, Y0)
|
||||
* -- +--------------------------------+
|
||||
* |________|_________|_________|
|
||||
* T1 T2 T3
|
||||
*
|
||||
* P2 Circular pattern with middle at NOZZLE_CLEAN_CIRCLE_MIDDLE.
|
||||
* "R" specifies the radius. "S" specifies the stroke count.
|
||||
* Before starting, the nozzle moves to NOZZLE_CLEAN_START_POINT.
|
||||
*
|
||||
* Caveats: The ending Z should be the same as starting Z.
|
||||
* Attention: EXPERIMENTAL. G-code arguments may change.
|
||||
*
|
||||
*/
|
||||
//#define NOZZLE_CLEAN_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_CLEAN_FEATURE)
|
||||
// Default number of pattern repetitions
|
||||
#define NOZZLE_CLEAN_STROKES 12
|
||||
|
||||
// Default number of triangles
|
||||
#define NOZZLE_CLEAN_TRIANGLES 3
|
||||
|
||||
// Specify positions as { X, Y, Z }
|
||||
#define NOZZLE_CLEAN_START_POINT { 30, 30, (Z_MIN_POS + 1)}
|
||||
#define NOZZLE_CLEAN_END_POINT {100, 60, (Z_MIN_POS + 1)}
|
||||
|
||||
// Circular pattern radius
|
||||
#define NOZZLE_CLEAN_CIRCLE_RADIUS 6.5
|
||||
// Circular pattern circle fragments number
|
||||
#define NOZZLE_CLEAN_CIRCLE_FN 10
|
||||
// Middle point of circle
|
||||
#define NOZZLE_CLEAN_CIRCLE_MIDDLE NOZZLE_CLEAN_START_POINT
|
||||
|
||||
// Moves the nozzle to the initial position
|
||||
#define NOZZLE_CLEAN_GOBACK
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Print Job Timer
|
||||
*
|
||||
* Automatically start and stop the print job timer on M104/M109/M190.
|
||||
*
|
||||
* M104 (hotend, no wait) - high temp = none, low temp = stop timer
|
||||
* M109 (hotend, wait) - high temp = start timer, low temp = stop timer
|
||||
* M190 (bed, wait) - high temp = start timer, low temp = none
|
||||
*
|
||||
* The timer can also be controlled with the following commands:
|
||||
*
|
||||
* M75 - Start the print job timer
|
||||
* M76 - Pause the print job timer
|
||||
* M77 - Stop the print job timer
|
||||
*/
|
||||
#define PRINTJOB_TIMER_AUTOSTART
|
||||
|
||||
/**
|
||||
* Print Counter
|
||||
*
|
||||
* Track statistical data such as:
|
||||
*
|
||||
* - Total print jobs
|
||||
* - Total successful print jobs
|
||||
* - Total failed print jobs
|
||||
* - Total time printing
|
||||
*
|
||||
* View the current statistics with M78.
|
||||
*/
|
||||
//#define PRINTCOUNTER
|
||||
|
||||
//=============================================================================
|
||||
//============================= LCD and SD support ============================
|
||||
//=============================================================================
|
||||
|
||||
// @section lcd
|
||||
|
||||
/**
|
||||
* LCD LANGUAGE
|
||||
*
|
||||
* Select the language to display on the LCD. These languages are available:
|
||||
*
|
||||
* en, an, bg, ca, cz, da, de, el, el-gr, es, eu, fi, fr, gl, hr, it,
|
||||
* jp-kana, ko_KR, nl, pl, pt, pt-br, ru, sk, tr, uk, zh_CN, zh_TW, test
|
||||
*
|
||||
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cz':'Czech', 'da':'Danish', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'jp-kana':'Japanese', 'ko_KR':'Korean (South Korea)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'ru':'Russian', 'sk':'Slovak', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Traditional)', 'test':'TEST' }
|
||||
*/
|
||||
#define LCD_LANGUAGE en
|
||||
|
||||
/**
|
||||
* LCD Character Set
|
||||
*
|
||||
* Note: This option is NOT applicable to Graphical Displays.
|
||||
*
|
||||
* All character-based LCDs provide ASCII plus one of these
|
||||
* language extensions:
|
||||
*
|
||||
* - JAPANESE ... the most common
|
||||
* - WESTERN ... with more accented characters
|
||||
* - CYRILLIC ... for the Russian language
|
||||
*
|
||||
* To determine the language extension installed on your controller:
|
||||
*
|
||||
* - Compile and upload with LCD_LANGUAGE set to 'test'
|
||||
* - Click the controller to view the LCD menu
|
||||
* - The LCD will display Japanese, Western, or Cyrillic text
|
||||
*
|
||||
* See http://marlinfw.org/docs/development/lcd_language.html
|
||||
*
|
||||
* :['JAPANESE', 'WESTERN', 'CYRILLIC']
|
||||
*/
|
||||
#define DISPLAY_CHARSET_HD44780 JAPANESE
|
||||
|
||||
/**
|
||||
* Info Screen Style (0:Classic, 1:Prusa)
|
||||
*
|
||||
* :[0:'Classic', 1:'Prusa']
|
||||
*/
|
||||
#define LCD_INFO_SCREEN_STYLE 0
|
||||
|
||||
/**
|
||||
* SD CARD
|
||||
*
|
||||
* SD Card support is disabled by default. If your controller has an SD slot,
|
||||
* you must uncomment the following option or it won't work.
|
||||
*
|
||||
*/
|
||||
//#define SDSUPPORT
|
||||
|
||||
/**
|
||||
* SD CARD: SPI SPEED
|
||||
*
|
||||
* Enable one of the following items for a slower SPI transfer speed.
|
||||
* This may be required to resolve "volume init" errors.
|
||||
*/
|
||||
//#define SPI_SPEED SPI_HALF_SPEED
|
||||
//#define SPI_SPEED SPI_QUARTER_SPEED
|
||||
//#define SPI_SPEED SPI_EIGHTH_SPEED
|
||||
|
||||
/**
|
||||
* SD CARD: ENABLE CRC
|
||||
*
|
||||
* Use CRC checks and retries on the SD communication.
|
||||
*/
|
||||
//#define SD_CHECK_AND_RETRY
|
||||
|
||||
/**
|
||||
* LCD Menu Items
|
||||
*
|
||||
* Disable all menus and only display the Status Screen, or
|
||||
* just remove some extraneous menu items to recover space.
|
||||
*/
|
||||
//#define NO_LCD_MENUS
|
||||
//#define SLIM_LCD_MENUS
|
||||
|
||||
//
|
||||
// ENCODER SETTINGS
|
||||
//
|
||||
// This option overrides the default number of encoder pulses needed to
|
||||
// produce one step. Should be increased for high-resolution encoders.
|
||||
//
|
||||
//#define ENCODER_PULSES_PER_STEP 4
|
||||
|
||||
//
|
||||
// Use this option to override the number of step signals required to
|
||||
// move between next/prev menu items.
|
||||
//
|
||||
//#define ENCODER_STEPS_PER_MENU_ITEM 1
|
||||
|
||||
/**
|
||||
* Encoder Direction Options
|
||||
*
|
||||
* Test your encoder's behavior first with both options disabled.
|
||||
*
|
||||
* Reversed Value Edit and Menu Nav? Enable REVERSE_ENCODER_DIRECTION.
|
||||
* Reversed Menu Navigation only? Enable REVERSE_MENU_DIRECTION.
|
||||
* Reversed Value Editing only? Enable BOTH options.
|
||||
*/
|
||||
|
||||
//
|
||||
// This option reverses the encoder direction everywhere.
|
||||
//
|
||||
// Set this option if CLOCKWISE causes values to DECREASE
|
||||
//
|
||||
//#define REVERSE_ENCODER_DIRECTION
|
||||
|
||||
//
|
||||
// This option reverses the encoder direction for navigating LCD menus.
|
||||
//
|
||||
// If CLOCKWISE normally moves DOWN this makes it go UP.
|
||||
// If CLOCKWISE normally moves UP this makes it go DOWN.
|
||||
//
|
||||
//#define REVERSE_MENU_DIRECTION
|
||||
|
||||
//
|
||||
// Individual Axis Homing
|
||||
//
|
||||
// Add individual axis homing items (Home X, Home Y, and Home Z) to the LCD menu.
|
||||
//
|
||||
//#define INDIVIDUAL_AXIS_HOMING_MENU
|
||||
|
||||
//
|
||||
// SPEAKER/BUZZER
|
||||
//
|
||||
// If you have a speaker that can produce tones, enable it here.
|
||||
// By default Marlin assumes you have a buzzer with a fixed frequency.
|
||||
//
|
||||
//#define SPEAKER
|
||||
|
||||
//
|
||||
// The duration and frequency for the UI feedback sound.
|
||||
// Set these to 0 to disable audio feedback in the LCD menus.
|
||||
//
|
||||
// Note: Test audio output with the G-Code:
|
||||
// M300 S<frequency Hz> P<duration ms>
|
||||
//
|
||||
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
|
||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
|
||||
|
||||
//=============================================================================
|
||||
//======================== LCD / Controller Selection =========================
|
||||
//======================== (Character-based LCDs) =========================
|
||||
//=============================================================================
|
||||
|
||||
//
|
||||
// RepRapDiscount Smart Controller.
|
||||
// http://reprap.org/wiki/RepRapDiscount_Smart_Controller
|
||||
//
|
||||
// Note: Usually sold with a white PCB.
|
||||
//
|
||||
//#define REPRAP_DISCOUNT_SMART_CONTROLLER
|
||||
|
||||
//
|
||||
// Original RADDS LCD Display+Encoder+SDCardReader
|
||||
// http://doku.radds.org/dokumentation/lcd-display/
|
||||
//
|
||||
//#define RADDS_DISPLAY
|
||||
|
||||
//
|
||||
// ULTIMAKER Controller.
|
||||
//
|
||||
//#define ULTIMAKERCONTROLLER
|
||||
|
||||
//
|
||||
// ULTIPANEL as seen on Thingiverse.
|
||||
//
|
||||
//#define ULTIPANEL
|
||||
|
||||
//
|
||||
// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
|
||||
// http://reprap.org/wiki/PanelOne
|
||||
//
|
||||
//#define PANEL_ONE
|
||||
|
||||
//
|
||||
// GADGETS3D G3D LCD/SD Controller
|
||||
// http://reprap.org/wiki/RAMPS_1.3/1.4_GADGETS3D_Shield_with_Panel
|
||||
//
|
||||
// Note: Usually sold with a blue PCB.
|
||||
//
|
||||
//#define G3D_PANEL
|
||||
|
||||
//
|
||||
// RigidBot Panel V1.0
|
||||
// http://www.inventapart.com/
|
||||
//
|
||||
//#define RIGIDBOT_PANEL
|
||||
|
||||
//
|
||||
// Makeboard 3D Printer Parts 3D Printer Mini Display 1602 Mini Controller
|
||||
// https://www.aliexpress.com/item/Micromake-Makeboard-3D-Printer-Parts-3D-Printer-Mini-Display-1602-Mini-Controller-Compatible-with-Ramps-1/32765887917.html
|
||||
//
|
||||
//#define MAKEBOARD_MINI_2_LINE_DISPLAY_1602
|
||||
|
||||
//
|
||||
// ANET and Tronxy 20x4 Controller
|
||||
//
|
||||
//#define ZONESTAR_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
||||
// This LCD is known to be susceptible to electrical interference
|
||||
// which scrambles the display. Pressing any button clears it up.
|
||||
// This is a LCD2004 display with 5 analog buttons.
|
||||
|
||||
//
|
||||
// Generic 16x2, 16x4, 20x2, or 20x4 character-based LCD.
|
||||
//
|
||||
//#define ULTRA_LCD
|
||||
|
||||
//=============================================================================
|
||||
//======================== LCD / Controller Selection =========================
|
||||
//===================== (I2C and Shift-Register LCDs) =====================
|
||||
//=============================================================================
|
||||
|
||||
//
|
||||
// CONTROLLER TYPE: I2C
|
||||
//
|
||||
// Note: These controllers require the installation of Arduino's LiquidCrystal_I2C
|
||||
// library. For more info: https://github.com/kiyoshigawa/LiquidCrystal_I2C
|
||||
//
|
||||
|
||||
//
|
||||
// Elefu RA Board Control Panel
|
||||
// http://www.elefu.com/index.php?route=product/product&product_id=53
|
||||
//
|
||||
//#define RA_CONTROL_PANEL
|
||||
|
||||
//
|
||||
// Sainsmart (YwRobot) LCD Displays
|
||||
//
|
||||
// These require F.Malpartida's LiquidCrystal_I2C library
|
||||
// https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/Home
|
||||
//
|
||||
//#define LCD_SAINSMART_I2C_1602
|
||||
//#define LCD_SAINSMART_I2C_2004
|
||||
|
||||
//
|
||||
// Generic LCM1602 LCD adapter
|
||||
//
|
||||
//#define LCM1602
|
||||
|
||||
//
|
||||
// PANELOLU2 LCD with status LEDs,
|
||||
// separate encoder and click inputs.
|
||||
//
|
||||
// Note: This controller requires Arduino's LiquidTWI2 library v1.2.3 or later.
|
||||
// For more info: https://github.com/lincomatic/LiquidTWI2
|
||||
//
|
||||
// Note: The PANELOLU2 encoder click input can either be directly connected to
|
||||
// a pin (if BTN_ENC defined to != -1) or read through I2C (when BTN_ENC == -1).
|
||||
//
|
||||
//#define LCD_I2C_PANELOLU2
|
||||
|
||||
//
|
||||
// Panucatt VIKI LCD with status LEDs,
|
||||
// integrated click & L/R/U/D buttons, separate encoder inputs.
|
||||
//
|
||||
//#define LCD_I2C_VIKI
|
||||
|
||||
//
|
||||
// CONTROLLER TYPE: Shift register panels
|
||||
//
|
||||
|
||||
//
|
||||
// 2-wire Non-latching LCD SR from https://goo.gl/aJJ4sH
|
||||
// LCD configuration: http://reprap.org/wiki/SAV_3D_LCD
|
||||
//
|
||||
//#define SAV_3DLCD
|
||||
|
||||
//
|
||||
// 3-wire SR LCD with strobe using 74HC4094
|
||||
// https://github.com/mikeshub/SailfishLCD
|
||||
// Uses the code directly from Sailfish
|
||||
//
|
||||
//#define FF_INTERFACEBOARD
|
||||
|
||||
//=============================================================================
|
||||
//======================= LCD / Controller Selection =======================
|
||||
//========================= (Graphical LCDs) ========================
|
||||
//=============================================================================
|
||||
|
||||
//
|
||||
// CONTROLLER TYPE: Graphical 128x64 (DOGM)
|
||||
//
|
||||
// IMPORTANT: The U8glib library is required for Graphical Display!
|
||||
// https://github.com/olikraus/U8glib_Arduino
|
||||
//
|
||||
|
||||
//
|
||||
// RepRapDiscount FULL GRAPHIC Smart Controller
|
||||
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
|
||||
//
|
||||
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
|
||||
|
||||
//
|
||||
// ReprapWorld Graphical LCD
|
||||
// https://reprapworld.com/?products_details&products_id/1218
|
||||
//
|
||||
//#define REPRAPWORLD_GRAPHICAL_LCD
|
||||
|
||||
//
|
||||
// Activate one of these if you have a Panucatt Devices
|
||||
// Viki 2.0 or mini Viki with Graphic LCD
|
||||
// http://panucatt.com
|
||||
//
|
||||
//#define VIKI2
|
||||
//#define miniVIKI
|
||||
|
||||
//
|
||||
// MakerLab Mini Panel with graphic
|
||||
// controller and SD support - http://reprap.org/wiki/Mini_panel
|
||||
//
|
||||
//#define MINIPANEL
|
||||
|
||||
//
|
||||
// MaKr3d Makr-Panel with graphic controller and SD support.
|
||||
// http://reprap.org/wiki/MaKr3d_MaKrPanel
|
||||
//
|
||||
//#define MAKRPANEL
|
||||
|
||||
//
|
||||
// Adafruit ST7565 Full Graphic Controller.
|
||||
// https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
|
||||
//
|
||||
//#define ELB_FULL_GRAPHIC_CONTROLLER
|
||||
|
||||
//
|
||||
// BQ LCD Smart Controller shipped by
|
||||
// default with the BQ Hephestos 2 and Witbox 2.
|
||||
//
|
||||
//#define BQ_LCD_SMART_CONTROLLER
|
||||
|
||||
//
|
||||
// Cartesio UI
|
||||
// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface
|
||||
//
|
||||
//#define CARTESIO_UI
|
||||
|
||||
//
|
||||
// LCD for Melzi Card with Graphical LCD
|
||||
//
|
||||
//#define LCD_FOR_MELZI
|
||||
|
||||
//
|
||||
// SSD1306 OLED full graphics generic display
|
||||
//
|
||||
//#define U8GLIB_SSD1306
|
||||
|
||||
//
|
||||
// SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules
|
||||
//
|
||||
//#define SAV_3DGLCD
|
||||
#if ENABLED(SAV_3DGLCD)
|
||||
//#define U8GLIB_SSD1306
|
||||
#define U8GLIB_SH1106
|
||||
#endif
|
||||
|
||||
//
|
||||
// Original Ulticontroller from Ultimaker 2 printer with SSD1309 I2C display and encoder
|
||||
// https://github.com/Ultimaker/Ultimaker2/tree/master/1249_Ulticontroller_Board_(x1)
|
||||
//
|
||||
//#define ULTI_CONTROLLER
|
||||
|
||||
//
|
||||
// TinyBoy2 128x64 OLED / Encoder Panel
|
||||
//
|
||||
//#define OLED_PANEL_TINYBOY2
|
||||
|
||||
//
|
||||
// MKS MINI12864 with graphic controller and SD support
|
||||
// http://reprap.org/wiki/MKS_MINI_12864
|
||||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
//
|
||||
// This is RAMPS-compatible using a single 10-pin connector.
|
||||
// (For CR-10 owners who want to replace the Melzi Creality board but retain the display)
|
||||
//
|
||||
//#define CR10_STOCKDISPLAY
|
||||
|
||||
//
|
||||
// ANET and Tronxy Graphical Controller
|
||||
//
|
||||
// Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
||||
// A clone of the RepRapDiscount full graphics display but with
|
||||
// different pins/wiring (see pins_ANET_10.h).
|
||||
//
|
||||
//#define ANET_FULL_GRAPHICS_LCD
|
||||
|
||||
//
|
||||
// MKS OLED 1.3" 128 × 64 FULL GRAPHICS CONTROLLER
|
||||
// http://reprap.org/wiki/MKS_12864OLED
|
||||
//
|
||||
// Tiny, but very sharp OLED display
|
||||
//
|
||||
//#define MKS_12864OLED // Uses the SH1106 controller (default)
|
||||
//#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller
|
||||
|
||||
//
|
||||
// AZSMZ 12864 LCD with SD
|
||||
// https://www.aliexpress.com/store/product/3D-printer-smart-controller-SMART-RAMPS-OR-RAMPS-1-4-LCD-12864-LCD-control-panel-green/2179173_32213636460.html
|
||||
//
|
||||
//#define AZSMZ_12864
|
||||
|
||||
//
|
||||
// Silvergate GLCD controller
|
||||
// http://github.com/android444/Silvergate
|
||||
//
|
||||
//#define SILVER_GATE_GLCD_CONTROLLER
|
||||
|
||||
//
|
||||
// Extensible UI
|
||||
//
|
||||
// Enable third-party or vendor customized user interfaces that aren't
|
||||
// packaged with Marlin. Source code for the user interface will need to
|
||||
// be placed in "src/lcd/extensible_ui/lib"
|
||||
//
|
||||
//#define EXTENSIBLE_UI
|
||||
|
||||
//=============================================================================
|
||||
//=============================== Graphical TFTs ==============================
|
||||
//=============================================================================
|
||||
|
||||
//
|
||||
// MKS Robin 320x240 color display
|
||||
//
|
||||
//#define MKS_ROBIN_TFT
|
||||
|
||||
//=============================================================================
|
||||
//============================ Other Controllers ============================
|
||||
//=============================================================================
|
||||
|
||||
//
|
||||
// CONTROLLER TYPE: Standalone / Serial
|
||||
//
|
||||
|
||||
//
|
||||
// LCD for Malyan M200 printers.
|
||||
//
|
||||
//#define MALYAN_LCD
|
||||
|
||||
//
|
||||
// CONTROLLER TYPE: Keypad / Add-on
|
||||
//
|
||||
|
||||
//
|
||||
// RepRapWorld REPRAPWORLD_KEYPAD v1.1
|
||||
// http://reprapworld.com/?products_details&products_id=202&cPath=1591_1626
|
||||
//
|
||||
// REPRAPWORLD_KEYPAD_MOVE_STEP sets how much should the robot move when a key
|
||||
// is pressed, a value of 10.0 means 10mm per click.
|
||||
//
|
||||
//#define REPRAPWORLD_KEYPAD
|
||||
//#define REPRAPWORLD_KEYPAD_MOVE_STEP 10.0
|
||||
|
||||
//=============================================================================
|
||||
//=============================== Extra Features ==============================
|
||||
//=============================================================================
|
||||
|
||||
// @section extras
|
||||
|
||||
// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino
|
||||
//#define FAST_PWM_FAN
|
||||
|
||||
// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
|
||||
// which is not as annoying as with the hardware PWM. On the other hand, if this frequency
|
||||
// is too low, you should also increment SOFT_PWM_SCALE.
|
||||
//#define FAN_SOFT_PWM
|
||||
|
||||
// Incrementing this by 1 will double the software PWM frequency,
|
||||
// affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
|
||||
// However, control resolution will be halved for each increment;
|
||||
// at zero value, there are 128 effective control positions.
|
||||
#define SOFT_PWM_SCALE 0
|
||||
|
||||
// If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
|
||||
// be used to mitigate the associated resolution loss. If enabled,
|
||||
// some of the PWM cycles are stretched so on average the desired
|
||||
// duty cycle is attained.
|
||||
//#define SOFT_PWM_DITHER
|
||||
|
||||
// Temperature status LEDs that display the hotend and bed temperature.
|
||||
// If all hotends, bed temperature, and target temperature are under 54C
|
||||
// then the BLUE led is on. Otherwise the RED led is on. (1C hysteresis)
|
||||
//#define TEMP_STAT_LEDS
|
||||
|
||||
// SkeinForge sends the wrong arc g-codes when using Arc Point as fillet procedure
|
||||
//#define SF_ARC_FIX
|
||||
|
||||
// Support for the BariCUDA Paste Extruder
|
||||
//#define BARICUDA
|
||||
|
||||
// Support for BlinkM/CyzRgb
|
||||
//#define BLINKM
|
||||
|
||||
// Support for PCA9632 PWM LED driver
|
||||
//#define PCA9632
|
||||
|
||||
// Support for PCA9533 PWM LED driver
|
||||
// https://github.com/mikeshub/SailfishRGB_LED
|
||||
//#define PCA9533
|
||||
|
||||
/**
|
||||
* RGB LED / LED Strip Control
|
||||
*
|
||||
* Enable support for an RGB LED connected to 5V digital pins, or
|
||||
* an RGB Strip connected to MOSFETs controlled by digital pins.
|
||||
*
|
||||
* Adds the M150 command to set the LED (or LED strip) color.
|
||||
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
||||
* luminance values can be set from 0 to 255.
|
||||
* For Neopixel LED an overall brightness parameter is also available.
|
||||
*
|
||||
* *** CAUTION ***
|
||||
* LED Strips require a MOSFET Chip between PWM lines and LEDs,
|
||||
* as the Arduino cannot handle the current the LEDs will require.
|
||||
* Failure to follow this precaution can destroy your Arduino!
|
||||
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* *** CAUTION ***
|
||||
*
|
||||
* LED Type. Enable only one of the following two options.
|
||||
*
|
||||
*/
|
||||
//#define RGB_LED
|
||||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
//#define NEOPIXEL_LED
|
||||
#if ENABLED(NEOPIXEL_LED)
|
||||
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
|
||||
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
||||
#define NEOPIXEL_PIXELS 30 // Number of LEDs in the strip
|
||||
#define NEOPIXEL_IS_SEQUENTIAL // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
|
||||
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness (0-255)
|
||||
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Printer Event LEDs
|
||||
*
|
||||
* During printing, the LEDs will reflect the printer status:
|
||||
*
|
||||
* - Gradually change from blue to violet as the heated bed gets to target temp
|
||||
* - Gradually change from violet to red as the hotend gets to temperature
|
||||
* - Change to white to illuminate work surface
|
||||
* - Change to green once print has finished
|
||||
* - Turn off after the print has finished and the user has pushed a button
|
||||
*/
|
||||
#if ANY(BLINKM, RGB_LED, RGBW_LED, PCA9632, PCA9533, NEOPIXEL_LED)
|
||||
#define PRINTER_EVENT_LEDS
|
||||
#endif
|
||||
|
||||
/**
|
||||
* R/C SERVO support
|
||||
* Sponsored by TrinityLabs, Reworked by codexmas
|
||||
*/
|
||||
|
||||
/**
|
||||
* Number of servos
|
||||
*
|
||||
* For some servo-related options NUM_SERVOS will be set automatically.
|
||||
* Set this manually if there are extra servos needing manual control.
|
||||
* Leave undefined or set to 0 to entirely disable the servo subsystem.
|
||||
*/
|
||||
#define NUM_SERVOS 2 // Servo index starts with 0 for M280 command
|
||||
|
||||
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
||||
// 300ms is a good value but you can try less delay.
|
||||
// If the servo can't reach the requested position, increase it.
|
||||
#define SERVO_DELAY { 300, 300 }
|
||||
|
||||
// Only power servos during movement, otherwise leave off to prevent jitter
|
||||
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
||||
|
||||
// Allow servo angle to be edited and saved to EEPROM
|
||||
//#define EDITABLE_SERVO_ANGLES
|
2343
config/examples/STM32/Black_STM32F407VET6/Configuration_adv.h
Normal file
2343
config/examples/STM32/Black_STM32F407VET6/Configuration_adv.h
Normal file
|
@ -0,0 +1,2343 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2019 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
|
||||
|
||||
/**
|
||||
* Configuration_adv.h
|
||||
*
|
||||
* Advanced settings.
|
||||
* Only change these if you know exactly what you're doing.
|
||||
* Some of these settings can damage your printer if improperly set!
|
||||
*
|
||||
* Basic settings can be found in Configuration.h
|
||||
*
|
||||
*/
|
||||
#define CONFIGURATION_ADV_H_VERSION 020000
|
||||
|
||||
// @section temperature
|
||||
|
||||
//===========================================================================
|
||||
//=============================Thermal Settings ============================
|
||||
//===========================================================================
|
||||
|
||||
//
|
||||
// Hephestos 2 24V heated bed upgrade kit.
|
||||
// https://store.bq.com/en/heated-bed-kit-hephestos2
|
||||
//
|
||||
//#define HEPHESTOS2_HEATED_BED_KIT
|
||||
#if ENABLED(HEPHESTOS2_HEATED_BED_KIT)
|
||||
#undef TEMP_SENSOR_BED
|
||||
#define TEMP_SENSOR_BED 70
|
||||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
#define BED_HYSTERESIS 2 // Only disable heating if T>target+BED_HYSTERESIS and enable heating if T>target-BED_HYSTERESIS
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Thermal Protection provides additional protection to your printer from damage
|
||||
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||
* protect against a broken or disconnected thermistor wire.
|
||||
*
|
||||
* The issue: If a thermistor falls out, it will report the much lower
|
||||
* temperature of the air in the room, and the the firmware will keep
|
||||
* the heater on.
|
||||
*
|
||||
* The solution: Once the temperature reaches the target, start observing.
|
||||
* If the temperature stays too far below the target (hysteresis) for too
|
||||
* long (period), the firmware will halt the machine as a safety precaution.
|
||||
*
|
||||
* If you get false positives for "Thermal Runaway", increase
|
||||
* THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
|
||||
*/
|
||||
#if ENABLED(THERMAL_PROTECTION_HOTENDS)
|
||||
#define THERMAL_PROTECTION_PERIOD 40 // Seconds
|
||||
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
|
||||
|
||||
//#define ADAPTIVE_FAN_SLOWING // Slow part cooling fan if temperature drops
|
||||
#if BOTH(ADAPTIVE_FAN_SLOWING, PIDTEMP)
|
||||
//#define NO_FAN_SLOWING_IN_PID_TUNING // Don't slow fan speed during M303
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Whenever an M104, M109, or M303 increases the target temperature, the
|
||||
* firmware will wait for the WATCH_TEMP_PERIOD to expire. If the temperature
|
||||
* hasn't increased by WATCH_TEMP_INCREASE degrees, the machine is halted and
|
||||
* requires a hard reset. This test restarts with any M104/M109/M303, but only
|
||||
* if the current temperature is far enough below the target for a reliable
|
||||
* test.
|
||||
*
|
||||
* If you get false positives for "Heating failed", increase WATCH_TEMP_PERIOD
|
||||
* and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set
|
||||
* below 2.
|
||||
*/
|
||||
#define WATCH_TEMP_PERIOD 20 // Seconds
|
||||
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Thermal Protection parameters for the bed are just as above for hotends.
|
||||
*/
|
||||
#if ENABLED(THERMAL_PROTECTION_BED)
|
||||
#define THERMAL_PROTECTION_BED_PERIOD 20 // Seconds
|
||||
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
||||
|
||||
/**
|
||||
* As described above, except for the bed (M140/M190/M303).
|
||||
*/
|
||||
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
|
||||
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Thermal Protection parameters for the heated chamber.
|
||||
*/
|
||||
#if ENABLED(THERMAL_PROTECTION_CHAMBER)
|
||||
#define THERMAL_PROTECTION_CHAMBER_PERIOD 20 // Seconds
|
||||
#define THERMAL_PROTECTION_CHAMBER_HYSTERESIS 2 // Degrees Celsius
|
||||
|
||||
/**
|
||||
* Heated chamber watch settings (M141/M191).
|
||||
*/
|
||||
#define WATCH_CHAMBER_TEMP_PERIOD 60 // Seconds
|
||||
#define WATCH_CHAMBER_TEMP_INCREASE 2 // Degrees Celsius
|
||||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
#define LPQ_MAX_LEN 50
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Automatic Temperature:
|
||||
* The hotend target temperature is calculated by all the buffered lines of gcode.
|
||||
* The maximum buffered steps/sec of the extruder motor is called "se".
|
||||
* Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
|
||||
* The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
|
||||
* mintemp and maxtemp. Turn this off by executing M109 without F*
|
||||
* Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
|
||||
* On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
|
||||
*/
|
||||
#define AUTOTEMP
|
||||
#if ENABLED(AUTOTEMP)
|
||||
#define AUTOTEMP_OLDWEIGHT 0.98
|
||||
#endif
|
||||
|
||||
// Show extra position information in M114
|
||||
//#define M114_DETAIL
|
||||
|
||||
// Show Temperature ADC value
|
||||
// Enable for M105 to include ADC values read from temperature sensors.
|
||||
//#define SHOW_TEMP_ADC_VALUES
|
||||
|
||||
/**
|
||||
* High Temperature Thermistor Support
|
||||
*
|
||||
* Thermistors able to support high temperature tend to have a hard time getting
|
||||
* good readings at room and lower temperatures. This means HEATER_X_RAW_LO_TEMP
|
||||
* will probably be caught when the heating element first turns on during the
|
||||
* preheating process, which will trigger a min_temp_error as a safety measure
|
||||
* and force stop everything.
|
||||
* To circumvent this limitation, we allow for a preheat time (during which,
|
||||
* min_temp_error won't be triggered) and add a min_temp buffer to handle
|
||||
* aberrant readings.
|
||||
*
|
||||
* If you want to enable this feature for your hotend thermistor(s)
|
||||
* uncomment and set values > 0 in the constants below
|
||||
*/
|
||||
|
||||
// The number of consecutive low temperature errors that can occur
|
||||
// before a min_temp_error is triggered. (Shouldn't be more than 10.)
|
||||
//#define MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED 0
|
||||
|
||||
// The number of milliseconds a hotend will preheat before starting to check
|
||||
// the temperature. This value should NOT be set to the time it takes the
|
||||
// hot end to reach the target temperature, but the time it takes to reach
|
||||
// the minimum temperature your thermistor can read. The lower the better/safer.
|
||||
// This shouldn't need to be more than 30 seconds (30000)
|
||||
//#define MILLISECONDS_PREHEAT_TIME 0
|
||||
|
||||
// @section extruder
|
||||
|
||||
// Extruder runout prevention.
|
||||
// If the machine is idle and the temperature over MINTEMP
|
||||
// then extrude some filament every couple of SECONDS.
|
||||
//#define EXTRUDER_RUNOUT_PREVENT
|
||||
#if ENABLED(EXTRUDER_RUNOUT_PREVENT)
|
||||
#define EXTRUDER_RUNOUT_MINTEMP 190
|
||||
#define EXTRUDER_RUNOUT_SECONDS 30
|
||||
#define EXTRUDER_RUNOUT_SPEED 1500 // (mm/m)
|
||||
#define EXTRUDER_RUNOUT_EXTRUDE 5 // (mm)
|
||||
#endif
|
||||
|
||||
// @section temperature
|
||||
|
||||
// Calibration for AD595 / AD8495 sensor to adjust temperature measurements.
|
||||
// The final temperature is calculated as (measuredTemp * GAIN) + OFFSET.
|
||||
#define TEMP_SENSOR_AD595_OFFSET 0.0
|
||||
#define TEMP_SENSOR_AD595_GAIN 1.0
|
||||
#define TEMP_SENSOR_AD8495_OFFSET 0.0
|
||||
#define TEMP_SENSOR_AD8495_GAIN 1.0
|
||||
|
||||
/**
|
||||
* Controller Fan
|
||||
* To cool down the stepper drivers and MOSFETs.
|
||||
*
|
||||
* The fan will turn on automatically whenever any stepper is enabled
|
||||
* and turn off after a set period after all steppers are turned off.
|
||||
*/
|
||||
//#define USE_CONTROLLER_FAN
|
||||
#if ENABLED(USE_CONTROLLER_FAN)
|
||||
//#define CONTROLLER_FAN_PIN -1 // Set a custom pin for the controller fan
|
||||
#define CONTROLLERFAN_SECS 60 // Duration in seconds for the fan to run after all motors are disabled
|
||||
#define CONTROLLERFAN_SPEED 255 // 255 == full speed
|
||||
#endif
|
||||
|
||||
// When first starting the main fan, run it at full speed for the
|
||||
// given number of milliseconds. This gets the fan spinning reliably
|
||||
// before setting a PWM value. (Does not work with software PWM for fan on Sanguinololu)
|
||||
//#define FAN_KICKSTART_TIME 100
|
||||
|
||||
/**
|
||||
* PWM Fan Scaling
|
||||
*
|
||||
* Define the min/max speeds for PWM fans (as set with M106).
|
||||
*
|
||||
* With these options the M106 0-255 value range is scaled to a subset
|
||||
* to ensure that the fan has enough power to spin, or to run lower
|
||||
* current fans with higher current. (e.g., 5V/12V fans with 12V/24V)
|
||||
* Value 0 always turns off the fan.
|
||||
*
|
||||
* Define one or both of these to override the default 0-255 range.
|
||||
*/
|
||||
//#define FAN_MIN_PWM 50
|
||||
//#define FAN_MAX_PWM 128
|
||||
|
||||
/**
|
||||
* FAST PWM FAN Settings
|
||||
*
|
||||
* Use to change the FAST FAN PWM frequency (if enabled in Configuration.h)
|
||||
* Combinations of PWM Modes, prescale values and TOP resolutions are used internally to produce a
|
||||
* frequency as close as possible to the desired frequency.
|
||||
*
|
||||
* FAST_PWM_FAN_FREQUENCY [undefined by default]
|
||||
* Set this to your desired frequency.
|
||||
* If left undefined this defaults to F = F_CPU/(2*255*1)
|
||||
* ie F = 31.4 Khz on 16 MHz microcontrollers or F = 39.2 KHz on 20 MHz microcontrollers
|
||||
* These defaults are the same as with the old FAST_PWM_FAN implementation - no migration is required
|
||||
* NOTE: Setting very low frequencies (< 10 Hz) may result in unexpected timer behaviour.
|
||||
*
|
||||
* USE_OCR2A_AS_TOP [undefined by default]
|
||||
* Boards that use TIMER2 for PWM have limitations resulting in only a few possible frequencies on TIMER2:
|
||||
* 16MHz MCUs: [62.5KHz, 31.4KHz (default), 7.8KHz, 3.92KHz, 1.95KHz, 977Hz, 488Hz, 244Hz, 60Hz, 122Hz, 30Hz]
|
||||
* 20MHz MCUs: [78.1KHz, 39.2KHz (default), 9.77KHz, 4.9KHz, 2.44KHz, 1.22KHz, 610Hz, 305Hz, 153Hz, 76Hz, 38Hz]
|
||||
* A greater range can be achieved by enabling USE_OCR2A_AS_TOP. But note that this option blocks the use of
|
||||
* PWM on pin OC2A. Only use this option if you don't need PWM on 0C2A. (Check your schematic.)
|
||||
* USE_OCR2A_AS_TOP sacrifices duty cycle control resolution to achieve this broader range of frequencies.
|
||||
*/
|
||||
#if ENABLED(FAST_PWM_FAN)
|
||||
//#define FAST_PWM_FAN_FREQUENCY 31400
|
||||
//#define USE_OCR2A_AS_TOP
|
||||
#endif
|
||||
|
||||
// @section extruder
|
||||
|
||||
/**
|
||||
* Extruder cooling fans
|
||||
*
|
||||
* Extruder auto fans automatically turn on when their extruders'
|
||||
* temperatures go above EXTRUDER_AUTO_FAN_TEMPERATURE.
|
||||
*
|
||||
* Your board's pins file specifies the recommended pins. Override those here
|
||||
* or set to -1 to disable completely.
|
||||
*
|
||||
* Multiple extruders can be assigned to the same pin in which case
|
||||
* the fan will turn on when any selected extruder is above the threshold.
|
||||
*/
|
||||
#define E0_AUTO_FAN_PIN FAN1_PIN
|
||||
#define E1_AUTO_FAN_PIN FAN2_PIN
|
||||
#define E2_AUTO_FAN_PIN -1
|
||||
#define E3_AUTO_FAN_PIN -1
|
||||
#define E4_AUTO_FAN_PIN -1
|
||||
#define E5_AUTO_FAN_PIN -1
|
||||
#define CHAMBER_AUTO_FAN_PIN -1
|
||||
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
|
||||
#define EXTRUDER_AUTO_FAN_SPEED 255 // 255 == full speed
|
||||
|
||||
/**
|
||||
* Part-Cooling Fan Multiplexer
|
||||
*
|
||||
* This feature allows you to digitally multiplex the fan output.
|
||||
* The multiplexer is automatically switched at tool-change.
|
||||
* Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans.
|
||||
*/
|
||||
#define FANMUX0_PIN -1
|
||||
#define FANMUX1_PIN -1
|
||||
#define FANMUX2_PIN -1
|
||||
|
||||
/**
|
||||
* M355 Case Light on-off / brightness
|
||||
*/
|
||||
//#define CASE_LIGHT_ENABLE
|
||||
#if ENABLED(CASE_LIGHT_ENABLE)
|
||||
//#define CASE_LIGHT_PIN 4 // Override the default pin if needed
|
||||
#define INVERT_CASE_LIGHT false // Set true if Case Light is ON when pin is LOW
|
||||
#define CASE_LIGHT_DEFAULT_ON true // Set default power-up state on
|
||||
#define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // Set default power-up brightness (0-255, requires PWM pin)
|
||||
//#define MENU_ITEM_CASE_LIGHT // Add a Case Light option to the LCD main menu
|
||||
//#define CASE_LIGHT_USE_NEOPIXEL // Use Neopixel LED as case light, requires NEOPIXEL_LED.
|
||||
#if ENABLED(CASE_LIGHT_USE_NEOPIXEL)
|
||||
#define CASE_LIGHT_NEOPIXEL_COLOR { 255, 255, 255, 255 } // { Red, Green, Blue, White }
|
||||
#endif
|
||||
#endif
|
||||
|
||||
//===========================================================================
|
||||
//============================ Mechanical Settings ==========================
|
||||
//===========================================================================
|
||||
|
||||
// @section homing
|
||||
|
||||
// If you want endstops to stay on (by default) even when not homing
|
||||
// enable this option. Override at any time with M120, M121.
|
||||
//#define ENDSTOPS_ALWAYS_ON_DEFAULT
|
||||
|
||||
// @section extras
|
||||
|
||||
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
||||
|
||||
// Employ an external closed loop controller. Override pins here if needed.
|
||||
//#define EXTERNAL_CLOSED_LOOP_CONTROLLER
|
||||
#if ENABLED(EXTERNAL_CLOSED_LOOP_CONTROLLER)
|
||||
//#define CLOSED_LOOP_ENABLE_PIN -1
|
||||
//#define CLOSED_LOOP_MOVE_COMPLETE_PIN -1
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Dual Steppers / Dual Endstops
|
||||
*
|
||||
* This section will allow you to use extra E drivers to drive a second motor for X, Y, or Z axes.
|
||||
*
|
||||
* For example, set X_DUAL_STEPPER_DRIVERS setting to use a second motor. If the motors need to
|
||||
* spin in opposite directions set INVERT_X2_VS_X_DIR. If the second motor needs its own endstop
|
||||
* set X_DUAL_ENDSTOPS. This can adjust for "racking." Use X2_USE_ENDSTOP to set the endstop plug
|
||||
* that should be used for the second endstop. Extra endstops will appear in the output of 'M119'.
|
||||
*
|
||||
* Use X_DUAL_ENDSTOP_ADJUSTMENT to adjust for mechanical imperfection. After homing both motors
|
||||
* this offset is applied to the X2 motor. To find the offset home the X axis, and measure the error
|
||||
* in X2. Dual endstop offsets can be set at runtime with 'M666 X<offset> Y<offset> Z<offset>'.
|
||||
*/
|
||||
|
||||
//#define X_DUAL_STEPPER_DRIVERS
|
||||
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
||||
#define INVERT_X2_VS_X_DIR true // Set 'true' if X motors should rotate in opposite directions
|
||||
//#define X_DUAL_ENDSTOPS
|
||||
#if ENABLED(X_DUAL_ENDSTOPS)
|
||||
#define X2_USE_ENDSTOP _XMAX_
|
||||
#define X_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||
#endif
|
||||
#endif
|
||||
|
||||
//#define Y_DUAL_STEPPER_DRIVERS
|
||||
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
||||
#define INVERT_Y2_VS_Y_DIR true // Set 'true' if Y motors should rotate in opposite directions
|
||||
//#define Y_DUAL_ENDSTOPS
|
||||
#if ENABLED(Y_DUAL_ENDSTOPS)
|
||||
#define Y2_USE_ENDSTOP _YMAX_
|
||||
#define Y_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||
#endif
|
||||
#endif
|
||||
|
||||
//#define Z_DUAL_STEPPER_DRIVERS
|
||||
#if ENABLED(Z_DUAL_STEPPER_DRIVERS)
|
||||
//#define Z_DUAL_ENDSTOPS
|
||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||
#define Z2_USE_ENDSTOP _XMAX_
|
||||
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||
#endif
|
||||
#endif
|
||||
|
||||
//#define Z_TRIPLE_STEPPER_DRIVERS
|
||||
#if ENABLED(Z_TRIPLE_STEPPER_DRIVERS)
|
||||
//#define Z_TRIPLE_ENDSTOPS
|
||||
#if ENABLED(Z_TRIPLE_ENDSTOPS)
|
||||
#define Z2_USE_ENDSTOP _XMAX_
|
||||
#define Z3_USE_ENDSTOP _YMAX_
|
||||
#define Z_TRIPLE_ENDSTOPS_ADJUSTMENT2 0
|
||||
#define Z_TRIPLE_ENDSTOPS_ADJUSTMENT3 0
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Dual X Carriage
|
||||
*
|
||||
* This setup has two X carriages that can move independently, each with its own hotend.
|
||||
* The carriages can be used to print an object with two colors or materials, or in
|
||||
* "duplication mode" it can print two identical or X-mirrored objects simultaneously.
|
||||
* The inactive carriage is parked automatically to prevent oozing.
|
||||
* X1 is the left carriage, X2 the right. They park and home at opposite ends of the X axis.
|
||||
* By default the X2 stepper is assigned to the first unused E plug on the board.
|
||||
*
|
||||
* The following Dual X Carriage modes can be selected with M605 S<mode>:
|
||||
*
|
||||
* 0 : (FULL_CONTROL) The slicer has full control over both X-carriages and can achieve optimal travel
|
||||
* results as long as it supports dual X-carriages. (M605 S0)
|
||||
*
|
||||
* 1 : (AUTO_PARK) The firmware automatically parks and unparks the X-carriages on tool-change so
|
||||
* that additional slicer support is not required. (M605 S1)
|
||||
*
|
||||
* 2 : (DUPLICATION) The firmware moves the second X-carriage and extruder in synchronization with
|
||||
* the first X-carriage and extruder, to print 2 copies of the same object at the same time.
|
||||
* Set the constant X-offset and temperature differential with M605 S2 X[offs] R[deg] and
|
||||
* follow with M605 S2 to initiate duplicated movement.
|
||||
*
|
||||
* 3 : (MIRRORED) Formbot/Vivedino-inspired mirrored mode in which the second extruder duplicates
|
||||
* the movement of the first except the second extruder is reversed in the X axis.
|
||||
* Set the initial X offset and temperature differential with M605 S2 X[offs] R[deg] and
|
||||
* follow with M605 S3 to initiate mirrored movement.
|
||||
*/
|
||||
//#define DUAL_X_CARRIAGE
|
||||
#if ENABLED(DUAL_X_CARRIAGE)
|
||||
#define X1_MIN_POS X_MIN_POS // Set to X_MIN_POS
|
||||
#define X1_MAX_POS X_BED_SIZE // Set a maximum so the first X-carriage can't hit the parked second X-carriage
|
||||
#define X2_MIN_POS 80 // Set a minimum to ensure the second X-carriage can't hit the parked first X-carriage
|
||||
#define X2_MAX_POS 353 // Set this to the distance between toolheads when both heads are homed
|
||||
#define X2_HOME_DIR 1 // Set to 1. The second X-carriage always homes to the maximum endstop position
|
||||
#define X2_HOME_POS X2_MAX_POS // Default X2 home position. Set to X2_MAX_POS.
|
||||
// However: In this mode the HOTEND_OFFSET_X value for the second extruder provides a software
|
||||
// override for X2_HOME_POS. This also allow recalibration of the distance between the two endstops
|
||||
// without modifying the firmware (through the "M218 T1 X???" command).
|
||||
// Remember: you should set the second extruder x-offset to 0 in your slicer.
|
||||
|
||||
// This is the default power-up mode which can be later using M605.
|
||||
#define DEFAULT_DUAL_X_CARRIAGE_MODE DXC_AUTO_PARK_MODE
|
||||
|
||||
// Default x offset in duplication mode (typically set to half print bed width)
|
||||
#define DEFAULT_DUPLICATION_X_OFFSET 100
|
||||
|
||||
#endif // DUAL_X_CARRIAGE
|
||||
|
||||
// Activate a solenoid on the active extruder with M380. Disable all with M381.
|
||||
// Define SOL0_PIN, SOL1_PIN, etc., for each extruder that has a solenoid.
|
||||
//#define EXT_SOLENOID
|
||||
|
||||
// @section homing
|
||||
|
||||
// Homing hits each endstop, retracts by these distances, then does a slower bump.
|
||||
#define X_HOME_BUMP_MM 5
|
||||
#define Y_HOME_BUMP_MM 5
|
||||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
||||
// Enable this if X or Y can't home without homing the other axis first.
|
||||
//#define CODEPENDENT_XY_HOMING
|
||||
|
||||
/**
|
||||
* Z Steppers Auto-Alignment
|
||||
* Add the G34 command to align multiple Z steppers using a bed probe.
|
||||
*/
|
||||
//#define Z_STEPPER_AUTO_ALIGN
|
||||
#if ENABLED(Z_STEPPER_AUTO_ALIGN)
|
||||
// Define probe X and Y positions for Z1, Z2 [, Z3]
|
||||
#define Z_STEPPER_ALIGN_X { 10, 150, 290 }
|
||||
#define Z_STEPPER_ALIGN_Y { 290, 10, 290 }
|
||||
// Set number of iterations to align
|
||||
#define Z_STEPPER_ALIGN_ITERATIONS 3
|
||||
// Enable to restore leveling setup after operation
|
||||
#define RESTORE_LEVELING_AFTER_G34
|
||||
// Use the amplification factor to de-/increase correction step.
|
||||
// In case the stepper (spindle) position is further out than the test point
|
||||
// Use a value > 1. NOTE: This may cause instability
|
||||
#define Z_STEPPER_ALIGN_AMP 1.0
|
||||
// Stop criterion. If the accuracy is better than this stop iterating early
|
||||
#define Z_STEPPER_ALIGN_ACC 0.02
|
||||
#endif
|
||||
|
||||
// @section machine
|
||||
|
||||
#define AXIS_RELATIVE_MODES {false, false, false, false}
|
||||
|
||||
// Add a Duplicate option for well-separated conjoined nozzles
|
||||
//#define MULTI_NOZZLE_DUPLICATION
|
||||
|
||||
// By default pololu step drivers require an active high signal. However, some high power drivers require an active low signal as step.
|
||||
#define INVERT_X_STEP_PIN false
|
||||
#define INVERT_Y_STEP_PIN false
|
||||
#define INVERT_Z_STEP_PIN false
|
||||
#define INVERT_E_STEP_PIN false
|
||||
|
||||
// Default stepper release if idle. Set to 0 to deactivate.
|
||||
// Steppers will shut down DEFAULT_STEPPER_DEACTIVE_TIME seconds after the last move when DISABLE_INACTIVE_? is true.
|
||||
// Time can be set by M18 and M84.
|
||||
#define DEFAULT_STEPPER_DEACTIVE_TIME 120
|
||||
#define DISABLE_INACTIVE_X true
|
||||
#define DISABLE_INACTIVE_Y true
|
||||
#define DISABLE_INACTIVE_Z true // set to false if the nozzle will fall down on your printed part when print has finished.
|
||||
#define DISABLE_INACTIVE_E true
|
||||
|
||||
#define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate
|
||||
#define DEFAULT_MINTRAVELFEEDRATE 0.0
|
||||
|
||||
//#define HOME_AFTER_DEACTIVATE // Require rehoming after steppers are deactivated
|
||||
|
||||
// @section lcd
|
||||
|
||||
#if ENABLED(ULTIPANEL)
|
||||
#define MANUAL_FEEDRATE {50*60, 50*60, 4*60, 60} // Feedrates for manual moves along X, Y, Z, E from panel
|
||||
#define MANUAL_E_MOVES_RELATIVE // Show LCD extruder moves as relative rather than absolute positions
|
||||
#define ULTIPANEL_FEEDMULTIPLY // Comment to disable setting feedrate multiplier via encoder
|
||||
#endif
|
||||
|
||||
// @section extras
|
||||
|
||||
// minimum time in microseconds that a movement needs to take if the buffer is emptied.
|
||||
#define DEFAULT_MINSEGMENTTIME 20000
|
||||
|
||||
// If defined the movements slow down when the look ahead buffer is only half full
|
||||
#define SLOWDOWN
|
||||
|
||||
// Frequency limit
|
||||
// See nophead's blog for more info
|
||||
// Not working O
|
||||
//#define XY_FREQUENCY_LIMIT 15
|
||||
|
||||
// Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end
|
||||
// of the buffer and all stops. This should not be much greater than zero and should only be changed
|
||||
// if unwanted behavior is observed on a user's machine when running at very slow speeds.
|
||||
#define MINIMUM_PLANNER_SPEED 0.05 // (mm/s)
|
||||
|
||||
//
|
||||
// Backlash Compensation
|
||||
// Adds extra movement to axes on direction-changes to account for backlash.
|
||||
//
|
||||
//#define BACKLASH_COMPENSATION
|
||||
#if ENABLED(BACKLASH_COMPENSATION)
|
||||
// Define values for backlash distance and correction.
|
||||
// If BACKLASH_GCODE is enabled these values are the defaults.
|
||||
#define BACKLASH_DISTANCE_MM { 0, 0, 0 } // (mm)
|
||||
#define BACKLASH_CORRECTION 0.0 // 0.0 = no correction; 1.0 = full correction
|
||||
|
||||
// Set BACKLASH_SMOOTHING_MM to spread backlash correction over multiple segments
|
||||
// to reduce print artifacts. (Enabling this is costly in memory and computation!)
|
||||
//#define BACKLASH_SMOOTHING_MM 3 // (mm)
|
||||
|
||||
// Add runtime configuration and tuning of backlash values (M425)
|
||||
//#define BACKLASH_GCODE
|
||||
|
||||
#if ENABLED(BACKLASH_GCODE)
|
||||
// Measure the Z backlash when probing (G29) and set with "M425 Z"
|
||||
#define MEASURE_BACKLASH_WHEN_PROBING
|
||||
|
||||
#if ENABLED(MEASURE_BACKLASH_WHEN_PROBING)
|
||||
// When measuring, the probe will move up to BACKLASH_MEASUREMENT_LIMIT
|
||||
// mm away from point of contact in BACKLASH_MEASUREMENT_RESOLUTION
|
||||
// increments while checking for the contact to be broken.
|
||||
#define BACKLASH_MEASUREMENT_LIMIT 0.5 // (mm)
|
||||
#define BACKLASH_MEASUREMENT_RESOLUTION 0.005 // (mm)
|
||||
#define BACKLASH_MEASUREMENT_FEEDRATE Z_PROBE_SPEED_SLOW // (mm/m)
|
||||
#endif
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Automatic backlash, position and hotend offset calibration
|
||||
*
|
||||
* Enable G425 to run automatic calibration using an electrically-
|
||||
* conductive cube, bolt, or washer mounted on the bed.
|
||||
*
|
||||
* G425 uses the probe to touch the top and sides of the calibration object
|
||||
* on the bed and measures and/or correct positional offsets, axis backlash
|
||||
* and hotend offsets.
|
||||
*
|
||||
* Note: HOTEND_OFFSET and CALIBRATION_OBJECT_CENTER must be set to within
|
||||
* ±5mm of true values for G425 to succeed.
|
||||
*/
|
||||
//#define CALIBRATION_GCODE
|
||||
#if ENABLED(CALIBRATION_GCODE)
|
||||
|
||||
#define CALIBRATION_MEASUREMENT_RESOLUTION 0.01 // mm
|
||||
|
||||
#define CALIBRATION_FEEDRATE_SLOW 60 // mm/m
|
||||
#define CALIBRATION_FEEDRATE_FAST 1200 // mm/m
|
||||
#define CALIBRATION_FEEDRATE_TRAVEL 3000 // mm/m
|
||||
|
||||
// The following parameters refer to the conical section of the nozzle tip.
|
||||
#define CALIBRATION_NOZZLE_TIP_HEIGHT 1.0 // mm
|
||||
#define CALIBRATION_NOZZLE_OUTER_DIAMETER 2.0 // mm
|
||||
|
||||
// Uncomment to enable reporting (required for "G425 V", but consumes PROGMEM).
|
||||
//#define CALIBRATION_REPORTING
|
||||
|
||||
// The true location and dimension the cube/bolt/washer on the bed.
|
||||
#define CALIBRATION_OBJECT_CENTER { 264.0, -22.0, -2.0} // mm
|
||||
#define CALIBRATION_OBJECT_DIMENSIONS { 10.0, 10.0, 10.0} // mm
|
||||
|
||||
// Comment out any sides which are unreachable by the probe. For best
|
||||
// auto-calibration results, all sides must be reachable.
|
||||
#define CALIBRATION_MEASURE_RIGHT
|
||||
#define CALIBRATION_MEASURE_FRONT
|
||||
#define CALIBRATION_MEASURE_LEFT
|
||||
#define CALIBRATION_MEASURE_BACK
|
||||
|
||||
// Probing at the exact top center only works if the center is flat. If
|
||||
// probing on a screwhead or hollow washer, probe near the edges.
|
||||
//#define CALIBRATION_MEASURE_AT_TOP_EDGES
|
||||
|
||||
// Define pin which is read during calibration
|
||||
#ifndef CALIBRATION_PIN
|
||||
#define CALIBRATION_PIN -1 // Override in pins.h or set to -1 to use your Z endstop
|
||||
#define CALIBRATION_PIN_INVERTING false // set to true to invert the pin
|
||||
//#define CALIBRATION_PIN_PULLDOWN
|
||||
#define CALIBRATION_PIN_PULLUP
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Adaptive Step Smoothing increases the resolution of multi-axis moves, particularly at step frequencies
|
||||
* below 1kHz (for AVR) or 10kHz (for ARM), where aliasing between axes in multi-axis moves causes audible
|
||||
* vibration and surface artifacts. The algorithm adapts to provide the best possible step smoothing at the
|
||||
* lowest stepping frequencies.
|
||||
*/
|
||||
//#define ADAPTIVE_STEP_SMOOTHING
|
||||
|
||||
/**
|
||||
* Custom Microstepping
|
||||
* Override as-needed for your setup. Up to 3 MS pins are supported.
|
||||
*/
|
||||
//#define MICROSTEP1 LOW,LOW,LOW
|
||||
//#define MICROSTEP2 HIGH,LOW,LOW
|
||||
//#define MICROSTEP4 LOW,HIGH,LOW
|
||||
//#define MICROSTEP8 HIGH,HIGH,LOW
|
||||
//#define MICROSTEP16 LOW,LOW,HIGH
|
||||
//#define MICROSTEP32 HIGH,LOW,HIGH
|
||||
|
||||
// Microstep setting (Only functional when stepper driver microstep pins are connected to MCU.
|
||||
#define MICROSTEP_MODES { 16, 16, 16, 16, 16, 16 } // [1,2,4,8,16]
|
||||
|
||||
/**
|
||||
* @section stepper motor current
|
||||
*
|
||||
* Some boards have a means of setting the stepper motor current via firmware.
|
||||
*
|
||||
* The power on motor currents are set by:
|
||||
* PWM_MOTOR_CURRENT - used by MINIRAMBO & ULTIMAIN_2
|
||||
* known compatible chips: A4982
|
||||
* DIGIPOT_MOTOR_CURRENT - used by BQ_ZUM_MEGA_3D, RAMBO & SCOOVO_X9H
|
||||
* known compatible chips: AD5206
|
||||
* DAC_MOTOR_CURRENT_DEFAULT - used by PRINTRBOARD_REVF & RIGIDBOARD_V2
|
||||
* known compatible chips: MCP4728
|
||||
* DIGIPOT_I2C_MOTOR_CURRENTS - used by 5DPRINT, AZTEEG_X3_PRO, AZTEEG_X5_MINI_WIFI, MIGHTYBOARD_REVE
|
||||
* known compatible chips: MCP4451, MCP4018
|
||||
*
|
||||
* Motor currents can also be set by M907 - M910 and by the LCD.
|
||||
* M907 - applies to all.
|
||||
* M908 - BQ_ZUM_MEGA_3D, RAMBO, PRINTRBOARD_REVF, RIGIDBOARD_V2 & SCOOVO_X9H
|
||||
* M909, M910 & LCD - only PRINTRBOARD_REVF & RIGIDBOARD_V2
|
||||
*/
|
||||
//#define PWM_MOTOR_CURRENT { 1300, 1300, 1250 } // Values in milliamps
|
||||
//#define DIGIPOT_MOTOR_CURRENT { 135,135,135,135,135 } // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
|
||||
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
||||
|
||||
// Use an I2C based DIGIPOT (e.g., Azteeg X3 Pro)
|
||||
//#define DIGIPOT_I2C
|
||||
#if ENABLED(DIGIPOT_I2C) && !defined(DIGIPOT_I2C_ADDRESS_A)
|
||||
/**
|
||||
* Common slave addresses:
|
||||
*
|
||||
* A (A shifted) B (B shifted) IC
|
||||
* Smoothie 0x2C (0x58) 0x2D (0x5A) MCP4451
|
||||
* AZTEEG_X3_PRO 0x2C (0x58) 0x2E (0x5C) MCP4451
|
||||
* AZTEEG_X5_MINI_WIFI 0x58 0x5C MCP4451
|
||||
* MIGHTYBOARD_REVE 0x2F (0x5E) MCP4018
|
||||
*/
|
||||
#define DIGIPOT_I2C_ADDRESS_A 0x2C // unshifted slave address for first DIGIPOT
|
||||
#define DIGIPOT_I2C_ADDRESS_B 0x2D // unshifted slave address for second DIGIPOT
|
||||
#endif
|
||||
|
||||
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
||||
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8 MKS SBASE: 5
|
||||
// Actual motor currents in Amps. The number of entries must match DIGIPOT_I2C_NUM_CHANNELS.
|
||||
// These correspond to the physical drivers, so be mindful if the order is changed.
|
||||
#define DIGIPOT_I2C_MOTOR_CURRENTS { 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0 } // AZTEEG_X3_PRO
|
||||
|
||||
//===========================================================================
|
||||
//=============================Additional Features===========================
|
||||
//===========================================================================
|
||||
|
||||
// @section lcd
|
||||
|
||||
// Change values more rapidly when the encoder is rotated faster
|
||||
#define ENCODER_RATE_MULTIPLIER
|
||||
#if ENABLED(ENCODER_RATE_MULTIPLIER)
|
||||
#define ENCODER_10X_STEPS_PER_SEC 30 // (steps/s) Encoder rate for 10x speed
|
||||
#define ENCODER_100X_STEPS_PER_SEC 80 // (steps/s) Encoder rate for 100x speed
|
||||
#endif
|
||||
|
||||
// Play a beep when the feedrate is changed from the Status Screen
|
||||
//#define BEEP_ON_FEEDRATE_CHANGE
|
||||
#if ENABLED(BEEP_ON_FEEDRATE_CHANGE)
|
||||
#define FEEDRATE_CHANGE_BEEP_DURATION 10
|
||||
#define FEEDRATE_CHANGE_BEEP_FREQUENCY 440
|
||||
#endif
|
||||
|
||||
// Include a page of printer information in the LCD Main Menu
|
||||
//#define LCD_INFO_MENU
|
||||
|
||||
// Scroll a longer status message into view
|
||||
//#define STATUS_MESSAGE_SCROLLING
|
||||
|
||||
// On the Info Screen, display XY with one decimal place when possible
|
||||
//#define LCD_DECIMAL_SMALL_XY
|
||||
|
||||
// The timeout (in ms) to return to the status screen from sub-menus
|
||||
//#define LCD_TIMEOUT_TO_STATUS 15000
|
||||
|
||||
// Add an 'M73' G-code to set the current percentage
|
||||
//#define LCD_SET_PROGRESS_MANUALLY
|
||||
|
||||
#if HAS_CHARACTER_LCD && HAS_PRINT_PROGRESS
|
||||
//#define LCD_PROGRESS_BAR // Show a progress bar on HD44780 LCDs for SD printing
|
||||
#if ENABLED(LCD_PROGRESS_BAR)
|
||||
#define PROGRESS_BAR_BAR_TIME 2000 // (ms) Amount of time to show the bar
|
||||
#define PROGRESS_BAR_MSG_TIME 3000 // (ms) Amount of time to show the status message
|
||||
#define PROGRESS_MSG_EXPIRE 0 // (ms) Amount of time to retain the status message (0=forever)
|
||||
//#define PROGRESS_MSG_ONCE // Show the message for MSG_TIME then clear it
|
||||
//#define LCD_PROGRESS_BAR_TEST // Add a menu item to test the progress bar
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
* LED Control Menu
|
||||
* Enable this feature to add LED Control to the LCD menu
|
||||
*/
|
||||
//#define LED_CONTROL_MENU
|
||||
#if ENABLED(LED_CONTROL_MENU)
|
||||
#define LED_COLOR_PRESETS // Enable the Preset Color menu option
|
||||
#if ENABLED(LED_COLOR_PRESETS)
|
||||
#define LED_USER_PRESET_RED 255 // User defined RED value
|
||||
#define LED_USER_PRESET_GREEN 128 // User defined GREEN value
|
||||
#define LED_USER_PRESET_BLUE 0 // User defined BLUE value
|
||||
#define LED_USER_PRESET_WHITE 255 // User defined WHITE value
|
||||
#define LED_USER_PRESET_BRIGHTNESS 255 // User defined intensity
|
||||
//#define LED_USER_PRESET_STARTUP // Have the printer display the user preset color on startup
|
||||
#endif
|
||||
#endif // LED_CONTROL_MENU
|
||||
|
||||
#if ENABLED(SDSUPPORT)
|
||||
|
||||
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
||||
// around this by connecting a push button or single throw switch to the pin defined
|
||||
// as SD_DETECT_PIN in your board's pins definitions.
|
||||
// This setting should be disabled unless you are using a push button, pulling the pin to ground.
|
||||
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
||||
#define SD_DETECT_INVERTED
|
||||
|
||||
#define SD_FINISHED_STEPPERRELEASE true // Disable steppers when SD Print is finished
|
||||
#define SD_FINISHED_RELEASECOMMAND "M84 X Y Z E" // You might want to keep the Z enabled so your bed stays in place.
|
||||
|
||||
// Reverse SD sort to show "more recent" files first, according to the card's FAT.
|
||||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
*
|
||||
* Store the current state to the SD Card at the start of each layer
|
||||
* during SD printing. If the recovery file is found at boot time, present
|
||||
* an option on the LCD screen to continue the print from the last-known
|
||||
* point in the file.
|
||||
*/
|
||||
//#define POWER_LOSS_RECOVERY
|
||||
#if ENABLED(POWER_LOSS_RECOVERY)
|
||||
//#define POWER_LOSS_PIN 44 // Pin to detect power loss
|
||||
//#define POWER_LOSS_STATE HIGH // State of pin indicating power loss
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Sort SD file listings in alphabetical order.
|
||||
*
|
||||
* With this option enabled, items on SD cards will be sorted
|
||||
* by name for easier navigation.
|
||||
*
|
||||
* By default...
|
||||
*
|
||||
* - Use the slowest -but safest- method for sorting.
|
||||
* - Folders are sorted to the top.
|
||||
* - The sort key is statically allocated.
|
||||
* - No added G-code (M34) support.
|
||||
* - 40 item sorting limit. (Items after the first 40 are unsorted.)
|
||||
*
|
||||
* SD sorting uses static allocation (as set by SDSORT_LIMIT), allowing the
|
||||
* compiler to calculate the worst-case usage and throw an error if the SRAM
|
||||
* limit is exceeded.
|
||||
*
|
||||
* - SDSORT_USES_RAM provides faster sorting via a static directory buffer.
|
||||
* - SDSORT_USES_STACK does the same, but uses a local stack-based buffer.
|
||||
* - SDSORT_CACHE_NAMES will retain the sorted file listing in RAM. (Expensive!)
|
||||
* - SDSORT_DYNAMIC_RAM only uses RAM when the SD menu is visible. (Use with caution!)
|
||||
*/
|
||||
//#define SDCARD_SORT_ALPHA
|
||||
|
||||
// SD Card Sorting options
|
||||
#if ENABLED(SDCARD_SORT_ALPHA)
|
||||
#define SDSORT_LIMIT 40 // Maximum number of sorted items (10-256). Costs 27 bytes each.
|
||||
#define FOLDER_SORTING -1 // -1=above 0=none 1=below
|
||||
#define SDSORT_GCODE false // Allow turning sorting on/off with LCD and M34 g-code.
|
||||
#define SDSORT_USES_RAM false // Pre-allocate a static array for faster pre-sorting.
|
||||
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
||||
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
||||
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
||||
#define SDSORT_CACHE_VFATS 2 // Maximum number of 13-byte VFAT entries to use for sorting.
|
||||
// Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
|
||||
#endif
|
||||
|
||||
// This allows hosts to request long names for files and folders with M33
|
||||
//#define LONG_FILENAME_HOST_SUPPORT
|
||||
|
||||
// Enable this option to scroll long filenames in the SD card menu
|
||||
//#define SCROLL_LONG_FILENAMES
|
||||
|
||||
/**
|
||||
* This option allows you to abort SD printing when any endstop is triggered.
|
||||
* This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
* To have any effect, endstops must be enabled during SD printing.
|
||||
*/
|
||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||
|
||||
/**
|
||||
* This option makes it easier to print the same SD Card file again.
|
||||
* On print completion the LCD Menu will open with the file selected.
|
||||
* You can just click to start the print, or navigate elsewhere.
|
||||
*/
|
||||
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||
|
||||
/**
|
||||
* Auto-report SdCard status with M27 S<seconds>
|
||||
*/
|
||||
//#define AUTO_REPORT_SD_STATUS
|
||||
|
||||
/**
|
||||
* Support for USB thumb drives using an Arduino USB Host Shield or
|
||||
* equivalent MAX3421E breakout board. The USB thumb drive will appear
|
||||
* to Marlin as an SD card.
|
||||
*
|
||||
* The MAX3421E must be assigned the same pins as the SD card reader, with
|
||||
* the following pin mapping:
|
||||
*
|
||||
* SCLK, MOSI, MISO --> SCLK, MOSI, MISO
|
||||
* INT --> SD_DETECT_PIN
|
||||
* SS --> SDSS
|
||||
*/
|
||||
//#define USB_FLASH_DRIVE_SUPPORT
|
||||
#if ENABLED(USB_FLASH_DRIVE_SUPPORT)
|
||||
#define USB_CS_PIN SDSS
|
||||
#define USB_INTR_PIN SD_DETECT_PIN
|
||||
#endif
|
||||
|
||||
/**
|
||||
* When using a bootloader that supports SD-Firmware-Flashing,
|
||||
* add a menu item to activate SD-FW-Update on the next reboot.
|
||||
*
|
||||
* Requires ATMEGA2560 (Arduino Mega)
|
||||
*
|
||||
* Tested with this bootloader:
|
||||
* https://github.com/FleetProbe/MicroBridge-Arduino-ATMega2560
|
||||
*/
|
||||
//#define SD_FIRMWARE_UPDATE
|
||||
#if ENABLED(SD_FIRMWARE_UPDATE)
|
||||
#define SD_FIRMWARE_UPDATE_EEPROM_ADDR 0x1FF
|
||||
#define SD_FIRMWARE_UPDATE_ACTIVE_VALUE 0xF0
|
||||
#define SD_FIRMWARE_UPDATE_INACTIVE_VALUE 0xFF
|
||||
#endif
|
||||
|
||||
// Add an optimized binary file transfer mode, initiated with 'M28 B1'
|
||||
//#define BINARY_FILE_TRANSFER
|
||||
|
||||
#endif // SDSUPPORT
|
||||
|
||||
/**
|
||||
* Additional options for Graphical Displays
|
||||
*
|
||||
* Use the optimizations here to improve printing performance,
|
||||
* which can be adversely affected by graphical display drawing,
|
||||
* especially when doing several short moves, and when printing
|
||||
* on DELTA and SCARA machines.
|
||||
*
|
||||
* Some of these options may result in the display lagging behind
|
||||
* controller events, as there is a trade-off between reliable
|
||||
* printing performance versus fast display updates.
|
||||
*/
|
||||
#if HAS_GRAPHICAL_LCD
|
||||
// Show SD percentage next to the progress bar
|
||||
//#define DOGM_SD_PERCENT
|
||||
|
||||
// Enable to save many cycles by drawing a hollow frame on the Info Screen
|
||||
#define XYZ_HOLLOW_FRAME
|
||||
|
||||
// Enable to save many cycles by drawing a hollow frame on Menu Screens
|
||||
#define MENU_HOLLOW_FRAME
|
||||
|
||||
// A bigger font is available for edit items. Costs 3120 bytes of PROGMEM.
|
||||
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
|
||||
//#define USE_BIG_EDIT_FONT
|
||||
|
||||
// A smaller font may be used on the Info Screen. Costs 2300 bytes of PROGMEM.
|
||||
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
|
||||
//#define USE_SMALL_INFOFONT
|
||||
|
||||
// Enable this option and reduce the value to optimize screen updates.
|
||||
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
||||
//#define DOGM_SPI_DELAY_US 5
|
||||
|
||||
// Swap the CW/CCW indicators in the graphics overlay
|
||||
//#define OVERLAY_GFX_REVERSE
|
||||
|
||||
/**
|
||||
* ST7920-based LCDs can emulate a 16 x 4 character display using
|
||||
* the ST7920 character-generator for very fast screen updates.
|
||||
* Enable LIGHTWEIGHT_UI to use this special display mode.
|
||||
*
|
||||
* Since LIGHTWEIGHT_UI has limited space, the position and status
|
||||
* message occupy the same line. Set STATUS_EXPIRE_SECONDS to the
|
||||
* length of time to display the status message before clearing.
|
||||
*
|
||||
* Set STATUS_EXPIRE_SECONDS to zero to never clear the status.
|
||||
* This will prevent position updates from being displayed.
|
||||
*/
|
||||
#if ENABLED(U8GLIB_ST7920)
|
||||
//#define LIGHTWEIGHT_UI
|
||||
#if ENABLED(LIGHTWEIGHT_UI)
|
||||
#define STATUS_EXPIRE_SECONDS 20
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Status (Info) Screen customizations
|
||||
* These options may affect code size and screen render time.
|
||||
* Custom status screens can forcibly override these settings.
|
||||
*/
|
||||
//#define STATUS_COMBINE_HEATERS // Use combined heater images instead of separate ones
|
||||
//#define STATUS_HOTEND_NUMBERLESS // Use plain hotend icons instead of numbered ones (with 2+ hotends)
|
||||
#define STATUS_HOTEND_INVERTED // Show solid nozzle bitmaps when heating (Requires STATUS_HOTEND_ANIM)
|
||||
#define STATUS_HOTEND_ANIM // Use a second bitmap to indicate hotend heating
|
||||
#define STATUS_BED_ANIM // Use a second bitmap to indicate bed heating
|
||||
//#define STATUS_ALT_BED_BITMAP // Use the alternative bed bitmap
|
||||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
#endif // HAS_GRAPHICAL_LCD
|
||||
|
||||
// @section safety
|
||||
|
||||
// The hardware watchdog should reset the microcontroller disabling all outputs,
|
||||
// in case the firmware gets stuck and doesn't do temperature regulation.
|
||||
#define USE_WATCHDOG
|
||||
|
||||
#if ENABLED(USE_WATCHDOG)
|
||||
// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
|
||||
// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
|
||||
// However, THIS FEATURE IS UNSAFE!, as it will only work if interrupts are disabled. And the code could hang in an interrupt routine with interrupts disabled.
|
||||
//#define WATCHDOG_RESET_MANUAL
|
||||
#endif
|
||||
|
||||
// @section lcd
|
||||
|
||||
/**
|
||||
* Babystepping enables movement of the axes by tiny increments without changing
|
||||
* the current position values. This feature is used primarily to adjust the Z
|
||||
* axis in the first layer of a print in real-time.
|
||||
*
|
||||
* Warning: Does not respect endstops!
|
||||
*/
|
||||
//#define BABYSTEPPING
|
||||
#if ENABLED(BABYSTEPPING)
|
||||
//#define BABYSTEP_WITHOUT_HOMING
|
||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||
|
||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||
#if ENABLED(DOUBLECLICK_FOR_Z_BABYSTEPPING)
|
||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||
// Note: Extra time may be added to mitigate controller latency.
|
||||
//#define BABYSTEP_ALWAYS_AVAILABLE // Allow babystepping at all times (not just during movement).
|
||||
//#define MOVE_Z_WHEN_IDLE // Jump to the move Z menu on doubleclick when printer is idle.
|
||||
#if ENABLED(MOVE_Z_WHEN_IDLE)
|
||||
#define MOVE_Z_IDLE_MULTIPLICATOR 1 // Multiply 1mm by this factor for the move step size.
|
||||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// @section extruder
|
||||
|
||||
/**
|
||||
* Linear Pressure Control v1.5
|
||||
*
|
||||
* Assumption: advance [steps] = k * (delta velocity [steps/s])
|
||||
* K=0 means advance disabled.
|
||||
*
|
||||
* NOTE: K values for LIN_ADVANCE 1.5 differ from earlier versions!
|
||||
*
|
||||
* Set K around 0.22 for 3mm PLA Direct Drive with ~6.5cm between the drive gear and heatbreak.
|
||||
* Larger K values will be needed for flexible filament and greater distances.
|
||||
* If this algorithm produces a higher speed offset than the extruder can handle (compared to E jerk)
|
||||
* print acceleration will be reduced during the affected moves to keep within the limit.
|
||||
*
|
||||
* See http://marlinfw.org/docs/features/lin_advance.html for full instructions.
|
||||
* Mention @Sebastianv650 on GitHub to alert the author of any issues.
|
||||
*/
|
||||
//#define LIN_ADVANCE
|
||||
#if ENABLED(LIN_ADVANCE)
|
||||
//#define EXTRA_LIN_ADVANCE_K // Enable for second linear advance constants
|
||||
#define LIN_ADVANCE_K 0.22 // Unit: mm compression per 1mm/s extruder speed
|
||||
//#define LA_DEBUG // If enabled, this will generate debug information output over USB.
|
||||
#endif
|
||||
|
||||
// @section leveling
|
||||
|
||||
#if EITHER(MESH_BED_LEVELING, AUTO_BED_LEVELING_UBL)
|
||||
// Override the mesh area if the automatic (max) area is too large
|
||||
//#define MESH_MIN_X MESH_INSET
|
||||
//#define MESH_MIN_Y MESH_INSET
|
||||
//#define MESH_MAX_X X_BED_SIZE - (MESH_INSET)
|
||||
//#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET)
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Repeatedly attempt G29 leveling until it succeeds.
|
||||
* Stop after G29_MAX_RETRIES attempts.
|
||||
*/
|
||||
//#define G29_RETRY_AND_RECOVER
|
||||
#if ENABLED(G29_RETRY_AND_RECOVER)
|
||||
#define G29_MAX_RETRIES 3
|
||||
#define G29_HALT_ON_FAILURE
|
||||
/**
|
||||
* Specify the GCODE commands that will be executed when leveling succeeds,
|
||||
* between attempts, and after the maximum number of retries have been tried.
|
||||
*/
|
||||
#define G29_SUCCESS_COMMANDS "M117 Bed leveling done."
|
||||
#define G29_RECOVER_COMMANDS "M117 Probe failed. Rewiping.\nG28\nG12 P0 S12 T0"
|
||||
#define G29_FAILURE_COMMANDS "M117 Bed leveling failed.\nG0 Z10\nM300 P25 S880\nM300 P50 S0\nM300 P25 S880\nM300 P50 S0\nM300 P25 S880\nM300 P50 S0\nG4 S1"
|
||||
|
||||
#endif
|
||||
|
||||
// @section extras
|
||||
|
||||
//
|
||||
// G2/G3 Arc Support
|
||||
//
|
||||
#define ARC_SUPPORT // Disable this feature to save ~3226 bytes
|
||||
#if ENABLED(ARC_SUPPORT)
|
||||
#define MM_PER_ARC_SEGMENT 1 // Length of each arc segment
|
||||
#define MIN_ARC_SEGMENTS 24 // Minimum number of segments in a complete circle
|
||||
#define N_ARC_CORRECTION 25 // Number of interpolated segments between corrections
|
||||
//#define ARC_P_CIRCLES // Enable the 'P' parameter to specify complete circles
|
||||
//#define CNC_WORKSPACE_PLANES // Allow G2/G3 to operate in XY, ZX, or YZ planes
|
||||
#endif
|
||||
|
||||
// Support for G5 with XYZE destination and IJPQ offsets. Requires ~2666 bytes.
|
||||
//#define BEZIER_CURVE_SUPPORT
|
||||
|
||||
/**
|
||||
* G38 Probe Target
|
||||
*
|
||||
* This option adds G38.2 and G38.3 (probe towards target)
|
||||
* and optionally G38.4 and G38.5 (probe away from target).
|
||||
* Set MULTIPLE_PROBING for G38 to probe more than once.
|
||||
*/
|
||||
//#define G38_PROBE_TARGET
|
||||
#if ENABLED(G38_PROBE_TARGET)
|
||||
//#define G38_PROBE_AWAY // Include G38.4 and G38.5 to probe away from target
|
||||
#define G38_MINIMUM_MOVE 0.0275 // (mm) Minimum distance that will produce a move.
|
||||
#endif
|
||||
|
||||
// Moves (or segments) with fewer steps than this will be joined with the next move
|
||||
#define MIN_STEPS_PER_SEGMENT 6
|
||||
|
||||
/**
|
||||
* Minimum delay after setting the stepper DIR (in ns)
|
||||
* 0 : No delay (Expect at least 10µS since one Stepper ISR must transpire)
|
||||
* 20 : Minimum for TMC2xxx drivers
|
||||
* 200 : Minimum for A4988 drivers
|
||||
* 400 : Minimum for A5984 drivers
|
||||
* 500 : Minimum for LV8729 drivers (guess, no info in datasheet)
|
||||
* 650 : Minimum for DRV8825 drivers
|
||||
* 1500 : Minimum for TB6600 drivers (guess, no info in datasheet)
|
||||
* 15000 : Minimum for TB6560 drivers (guess, no info in datasheet)
|
||||
*
|
||||
* Override the default value based on the driver type set in Configuration.h.
|
||||
*/
|
||||
//#define MINIMUM_STEPPER_DIR_DELAY 650
|
||||
|
||||
/**
|
||||
* Minimum stepper driver pulse width (in µs)
|
||||
* 0 : Smallest possible width the MCU can produce, compatible with TMC2xxx drivers
|
||||
* 1 : Minimum for A4988, A5984, and LV8729 stepper drivers
|
||||
* 2 : Minimum for DRV8825 stepper drivers
|
||||
* 3 : Minimum for TB6600 stepper drivers
|
||||
* 30 : Minimum for TB6560 stepper drivers
|
||||
*
|
||||
* Override the default value based on the driver type set in Configuration.h.
|
||||
*/
|
||||
//#define MINIMUM_STEPPER_PULSE 2
|
||||
|
||||
/**
|
||||
* Maximum stepping rate (in Hz) the stepper driver allows
|
||||
* If undefined, defaults to 1MHz / (2 * MINIMUM_STEPPER_PULSE)
|
||||
* 500000 : Maximum for A4988 stepper driver
|
||||
* 400000 : Maximum for TMC2xxx stepper drivers
|
||||
* 250000 : Maximum for DRV8825 stepper driver
|
||||
* 150000 : Maximum for TB6600 stepper driver
|
||||
* 130000 : Maximum for LV8729 stepper driver
|
||||
* 15000 : Maximum for TB6560 stepper driver
|
||||
*
|
||||
* Override the default value based on the driver type set in Configuration.h.
|
||||
*/
|
||||
//#define MAXIMUM_STEPPER_RATE 250000
|
||||
|
||||
// @section temperature
|
||||
|
||||
// Control heater 0 and heater 1 in parallel.
|
||||
//#define HEATERS_PARALLEL
|
||||
|
||||
//===========================================================================
|
||||
//================================= Buffers =================================
|
||||
//===========================================================================
|
||||
|
||||
// @section hidden
|
||||
|
||||
// The number of linear motions that can be in the plan at any give time.
|
||||
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering.
|
||||
#if ENABLED(SDSUPPORT)
|
||||
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
|
||||
#else
|
||||
#define BLOCK_BUFFER_SIZE 16 // maximize block buffer
|
||||
#endif
|
||||
|
||||
// @section serial
|
||||
|
||||
// The ASCII buffer for serial input
|
||||
#define MAX_CMD_SIZE 96
|
||||
#define BUFSIZE 4
|
||||
|
||||
// Transmission to Host Buffer Size
|
||||
// To save 386 bytes of PROGMEM (and TX_BUFFER_SIZE+3 bytes of RAM) set to 0.
|
||||
// To buffer a simple "ok" you need 4 bytes.
|
||||
// For ADVANCED_OK (M105) you need 32 bytes.
|
||||
// For debug-echo: 128 bytes for the optimal speed.
|
||||
// Other output doesn't need to be that speedy.
|
||||
// :[0, 2, 4, 8, 16, 32, 64, 128, 256]
|
||||
#define TX_BUFFER_SIZE 0
|
||||
|
||||
// Host Receive Buffer Size
|
||||
// Without XON/XOFF flow control (see SERIAL_XON_XOFF below) 32 bytes should be enough.
|
||||
// To use flow control, set this buffer size to at least 1024 bytes.
|
||||
// :[0, 2, 4, 8, 16, 32, 64, 128, 256, 512, 1024, 2048]
|
||||
//#define RX_BUFFER_SIZE 1024
|
||||
|
||||
#if RX_BUFFER_SIZE >= 1024
|
||||
// Enable to have the controller send XON/XOFF control characters to
|
||||
// the host to signal the RX buffer is becoming full.
|
||||
//#define SERIAL_XON_XOFF
|
||||
#endif
|
||||
|
||||
#if ENABLED(SDSUPPORT)
|
||||
// Enable this option to collect and display the maximum
|
||||
// RX queue usage after transferring a file to SD.
|
||||
//#define SERIAL_STATS_MAX_RX_QUEUED
|
||||
|
||||
// Enable this option to collect and display the number
|
||||
// of dropped bytes after a file transfer to SD.
|
||||
//#define SERIAL_STATS_DROPPED_RX
|
||||
#endif
|
||||
|
||||
// Enable an emergency-command parser to intercept certain commands as they
|
||||
// enter the serial receive buffer, so they cannot be blocked.
|
||||
// Currently handles M108, M112, M410
|
||||
// Does not work on boards using AT90USB (USBCON) processors!
|
||||
//#define EMERGENCY_PARSER
|
||||
|
||||
// Bad Serial-connections can miss a received command by sending an 'ok'
|
||||
// Therefore some clients abort after 30 seconds in a timeout.
|
||||
// Some other clients start sending commands while receiving a 'wait'.
|
||||
// This "wait" is only sent when the buffer is empty. 1 second is a good value here.
|
||||
//#define NO_TIMEOUTS 1000 // Milliseconds
|
||||
|
||||
// Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary.
|
||||
//#define ADVANCED_OK
|
||||
|
||||
// Printrun may have trouble receiving long strings all at once.
|
||||
// This option inserts short delays between lines of serial output.
|
||||
#define SERIAL_OVERRUN_PROTECTION
|
||||
|
||||
// @section extras
|
||||
|
||||
/**
|
||||
* Extra Fan Speed
|
||||
* Adds a secondary fan speed for each print-cooling fan.
|
||||
* 'M106 P<fan> T3-255' : Set a secondary speed for <fan>
|
||||
* 'M106 P<fan> T2' : Use the set secondary speed
|
||||
* 'M106 P<fan> T1' : Restore the previous fan speed
|
||||
*/
|
||||
//#define EXTRA_FAN_SPEED
|
||||
|
||||
/**
|
||||
* Firmware-based and LCD-controlled retract
|
||||
*
|
||||
* Add G10 / G11 commands for automatic firmware-based retract / recover.
|
||||
* Use M207 and M208 to define parameters for retract / recover.
|
||||
*
|
||||
* Use M209 to enable or disable auto-retract.
|
||||
* With auto-retract enabled, all G1 E moves within the set range
|
||||
* will be converted to firmware-based retract/recover moves.
|
||||
*
|
||||
* Be sure to turn off auto-retract during filament change.
|
||||
*
|
||||
* Note that M207 / M208 / M209 settings are saved to EEPROM.
|
||||
*
|
||||
*/
|
||||
//#define FWRETRACT
|
||||
#if ENABLED(FWRETRACT)
|
||||
#define FWRETRACT_AUTORETRACT // costs ~500 bytes of PROGMEM
|
||||
#if ENABLED(FWRETRACT_AUTORETRACT)
|
||||
#define MIN_AUTORETRACT 0.1 // When auto-retract is on, convert E moves of this length and over
|
||||
#define MAX_AUTORETRACT 10.0 // Upper limit for auto-retract conversion
|
||||
#endif
|
||||
#define RETRACT_LENGTH 3 // Default retract length (positive mm)
|
||||
#define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change
|
||||
#define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s)
|
||||
#define RETRACT_ZRAISE 0 // Default retract Z-raise (mm)
|
||||
#define RETRACT_RECOVER_LENGTH 0 // Default additional recover length (mm, added to retract length when recovering)
|
||||
#define RETRACT_RECOVER_LENGTH_SWAP 0 // Default additional swap recover length (mm, added to retract length when recovering from extruder change)
|
||||
#define RETRACT_RECOVER_FEEDRATE 8 // Default feedrate for recovering from retraction (mm/s)
|
||||
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
||||
#if ENABLED(MIXING_EXTRUDER)
|
||||
//#define RETRACT_SYNC_MIXING // Retract and restore all mixing steppers simultaneously
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Universal tool change settings.
|
||||
* Applies to all types of extruders except where explicitly noted.
|
||||
*/
|
||||
#if EXTRUDERS > 1
|
||||
// Z raise distance for tool-change, as needed for some extruders
|
||||
#define TOOLCHANGE_ZRAISE 2 // (mm)
|
||||
|
||||
// Retract and prime filament on tool-change
|
||||
//#define TOOLCHANGE_FILAMENT_SWAP
|
||||
#if ENABLED(TOOLCHANGE_FILAMENT_SWAP)
|
||||
#define TOOLCHANGE_FIL_SWAP_LENGTH 12 // (mm)
|
||||
#define TOOLCHANGE_FIL_EXTRA_PRIME 2 // (mm)
|
||||
#define TOOLCHANGE_FIL_SWAP_RETRACT_SPEED 3600 // (mm/m)
|
||||
#define TOOLCHANGE_FIL_SWAP_PRIME_SPEED 3600 // (mm/m)
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Position to park head during tool change.
|
||||
* Doesn't apply to SWITCHING_TOOLHEAD, DUAL_X_CARRIAGE, or PARKING_EXTRUDER
|
||||
*/
|
||||
//#define TOOLCHANGE_PARK
|
||||
#if ENABLED(TOOLCHANGE_PARK)
|
||||
#define TOOLCHANGE_PARK_XY { X_MIN_POS + 10, Y_MIN_POS + 10 }
|
||||
#define TOOLCHANGE_PARK_XY_FEEDRATE 6000 // (mm/m)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Advanced Pause
|
||||
* Experimental feature for filament change support and for parking the nozzle when paused.
|
||||
* Adds the GCode M600 for initiating filament change.
|
||||
* If PARK_HEAD_ON_PAUSE enabled, adds the GCode M125 to pause printing and park the nozzle.
|
||||
*
|
||||
* Requires an LCD display.
|
||||
* Requires NOZZLE_PARK_FEATURE.
|
||||
* This feature is required for the default FILAMENT_RUNOUT_SCRIPT.
|
||||
*/
|
||||
//#define ADVANCED_PAUSE_FEATURE
|
||||
#if ENABLED(ADVANCED_PAUSE_FEATURE)
|
||||
#define PAUSE_PARK_RETRACT_FEEDRATE 60 // (mm/s) Initial retract feedrate.
|
||||
#define PAUSE_PARK_RETRACT_LENGTH 2 // (mm) Initial retract.
|
||||
// This short retract is done immediately, before parking the nozzle.
|
||||
#define FILAMENT_CHANGE_UNLOAD_FEEDRATE 10 // (mm/s) Unload filament feedrate. This can be pretty fast.
|
||||
#define FILAMENT_CHANGE_UNLOAD_ACCEL 25 // (mm/s^2) Lower acceleration may allow a faster feedrate.
|
||||
#define FILAMENT_CHANGE_UNLOAD_LENGTH 100 // (mm) The length of filament for a complete unload.
|
||||
// For Bowden, the full length of the tube and nozzle.
|
||||
// For direct drive, the full length of the nozzle.
|
||||
// Set to 0 for manual unloading.
|
||||
#define FILAMENT_CHANGE_SLOW_LOAD_FEEDRATE 6 // (mm/s) Slow move when starting load.
|
||||
#define FILAMENT_CHANGE_SLOW_LOAD_LENGTH 0 // (mm) Slow length, to allow time to insert material.
|
||||
// 0 to disable start loading and skip to fast load only
|
||||
#define FILAMENT_CHANGE_FAST_LOAD_FEEDRATE 6 // (mm/s) Load filament feedrate. This can be pretty fast.
|
||||
#define FILAMENT_CHANGE_FAST_LOAD_ACCEL 25 // (mm/s^2) Lower acceleration may allow a faster feedrate.
|
||||
#define FILAMENT_CHANGE_FAST_LOAD_LENGTH 0 // (mm) Load length of filament, from extruder gear to nozzle.
|
||||
// For Bowden, the full length of the tube and nozzle.
|
||||
// For direct drive, the full length of the nozzle.
|
||||
//#define ADVANCED_PAUSE_CONTINUOUS_PURGE // Purge continuously up to the purge length until interrupted.
|
||||
#define ADVANCED_PAUSE_PURGE_FEEDRATE 3 // (mm/s) Extrude feedrate (after loading). Should be slower than load feedrate.
|
||||
#define ADVANCED_PAUSE_PURGE_LENGTH 50 // (mm) Length to extrude after loading.
|
||||
// Set to 0 for manual extrusion.
|
||||
// Filament can be extruded repeatedly from the Filament Change menu
|
||||
// until extrusion is consistent, and to purge old filament.
|
||||
#define ADVANCED_PAUSE_RESUME_PRIME 0 // (mm) Extra distance to prime nozzle after returning from park.
|
||||
|
||||
// Filament Unload does a Retract, Delay, and Purge first:
|
||||
#define FILAMENT_UNLOAD_RETRACT_LENGTH 13 // (mm) Unload initial retract length.
|
||||
#define FILAMENT_UNLOAD_DELAY 5000 // (ms) Delay for the filament to cool after retract.
|
||||
#define FILAMENT_UNLOAD_PURGE_LENGTH 8 // (mm) An unretract is done, then this length is purged.
|
||||
|
||||
#define PAUSE_PARK_NOZZLE_TIMEOUT 45 // (seconds) Time limit before the nozzle is turned off for safety.
|
||||
#define FILAMENT_CHANGE_ALERT_BEEPS 10 // Number of alert beeps to play when a response is needed.
|
||||
#define PAUSE_PARK_NO_STEPPER_TIMEOUT // Enable for XYZ steppers to stay powered on during filament change.
|
||||
|
||||
//#define PARK_HEAD_ON_PAUSE // Park the nozzle during pause and filament change.
|
||||
//#define HOME_BEFORE_FILAMENT_CHANGE // Ensure homing has been completed prior to parking for filament change
|
||||
|
||||
//#define FILAMENT_LOAD_UNLOAD_GCODES // Add M701/M702 Load/Unload G-codes, plus Load/Unload in the LCD Prepare menu.
|
||||
//#define FILAMENT_UNLOAD_ALL_EXTRUDERS // Allow M702 to unload all extruders above a minimum target temp (as set by M302)
|
||||
#endif
|
||||
|
||||
// @section tmc
|
||||
|
||||
/**
|
||||
* TMC26X Stepper Driver options
|
||||
*
|
||||
* The TMC26XStepper library is required for this stepper driver.
|
||||
* https://github.com/trinamic/TMC26XStepper
|
||||
*/
|
||||
#if HAS_DRIVER(TMC26X)
|
||||
|
||||
#if AXIS_DRIVER_TYPE_X(TMC26X)
|
||||
#define X_MAX_CURRENT 1000 // (mA)
|
||||
#define X_SENSE_RESISTOR 91 // (mOhms)
|
||||
#define X_MICROSTEPS 16 // Number of microsteps
|
||||
#endif
|
||||
|
||||
#if AXIS_DRIVER_TYPE_X2(TMC26X)
|
||||
#define X2_MAX_CURRENT 1000
|
||||
#define X2_SENSE_RESISTOR 91
|
||||
#define X2_MICROSTEPS 16
|
||||
#endif
|
||||
|
||||
#if AXIS_DRIVER_TYPE_Y(TMC26X)
|
||||
#define Y_MAX_CURRENT 1000
|
||||
#define Y_SENSE_RESISTOR 91
|
||||
#define Y_MICROSTEPS 16
|
||||
#endif
|
||||
|
||||
#if AXIS_DRIVER_TYPE_Y2(TMC26X)
|
||||
#define Y2_MAX_CURRENT 1000
|
||||
#define Y2_SENSE_RESISTOR 91
|
||||
#define Y2_MICROSTEPS 16
|
||||
#endif
|
||||
|
||||
#if AXIS_DRIVER_TYPE_Z(TMC26X)
|
||||
#define Z_MAX_CURRENT 1000
|
||||
#define Z_SENSE_RESISTOR 91
|
||||
#define Z_MICROSTEPS 16
|
||||
#endif
|
||||
|
||||
#if AXIS_DRIVER_TYPE_Z2(TMC26X)
|
||||
#define Z2_MAX_CURRENT 1000
|
||||
#define Z2_SENSE_RESISTOR 91
|
||||
#define Z2_MICROSTEPS 16
|
||||
#endif
|
||||
|
||||
#if AXIS_DRIVER_TYPE_Z3(TMC26X)
|
||||
#define Z3_MAX_CURRENT 1000
|
||||
#define Z3_SENSE_RESISTOR 91
|
||||
#define Z3_MICROSTEPS 16
|
||||
#endif
|
||||
|
||||
#if AXIS_DRIVER_TYPE_E0(TMC26X)
|
||||
#define E0_MAX_CURRENT 1000
|
||||
#define E0_SENSE_RESISTOR 91
|
||||
#define E0_MICROSTEPS 16
|
||||
#endif
|
||||
|
||||
#if AXIS_DRIVER_TYPE_E1(TMC26X)
|
||||
#define E1_MAX_CURRENT 1000
|
||||
#define E1_SENSE_RESISTOR 91
|
||||
#define E1_MICROSTEPS 16
|
||||
#endif
|
||||
|
||||
#if AXIS_DRIVER_TYPE_E2(TMC26X)
|
||||
#define E2_MAX_CURRENT 1000
|
||||
#define E2_SENSE_RESISTOR 91
|
||||
#define E2_MICROSTEPS 16
|
||||
#endif
|
||||
|
||||
#if AXIS_DRIVER_TYPE_E3(TMC26X)
|
||||
#define E3_MAX_CURRENT 1000
|
||||
#define E3_SENSE_RESISTOR 91
|
||||
#define E3_MICROSTEPS 16
|
||||
#endif
|
||||
|
||||
#if AXIS_DRIVER_TYPE_E4(TMC26X)
|
||||
#define E4_MAX_CURRENT 1000
|
||||
#define E4_SENSE_RESISTOR 91
|
||||
#define E4_MICROSTEPS 16
|
||||
#endif
|
||||
|
||||
#if AXIS_DRIVER_TYPE_E5(TMC26X)
|
||||
#define E5_MAX_CURRENT 1000
|
||||
#define E5_SENSE_RESISTOR 91
|
||||
#define E5_MICROSTEPS 16
|
||||
#endif
|
||||
|
||||
#endif // TMC26X
|
||||
|
||||
// @section tmc_smart
|
||||
|
||||
/**
|
||||
* To use TMC2130, TMC2160, TMC2660, TMC5130, TMC5160 stepper drivers in SPI mode
|
||||
* connect your SPI pins to the hardware SPI interface on your board and define
|
||||
* the required CS pins in your `pins_MYBOARD.h` file. (e.g., RAMPS 1.4 uses AUX3
|
||||
* pins `X_CS_PIN 53`, `Y_CS_PIN 49`, etc.).
|
||||
* You may also use software SPI if you wish to use general purpose IO pins.
|
||||
*
|
||||
* To use TMC2208 stepper UART-configurable stepper drivers connect #_SERIAL_TX_PIN
|
||||
* to the driver side PDN_UART pin with a 1K resistor.
|
||||
* To use the reading capabilities, also connect #_SERIAL_RX_PIN to PDN_UART without
|
||||
* a resistor.
|
||||
* The drivers can also be used with hardware serial.
|
||||
*
|
||||
* TMCStepper library is required to use TMC stepper drivers.
|
||||
* https://github.com/teemuatlut/TMCStepper
|
||||
*/
|
||||
#if HAS_TRINAMIC
|
||||
|
||||
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
||||
#define INTERPOLATE true // Interpolate X/Y/Z_MICROSTEPS to 256
|
||||
|
||||
#if AXIS_IS_TMC(X)
|
||||
#define X_CURRENT 800 // (mA) RMS current. Multiply by 1.414 for peak current.
|
||||
#define X_MICROSTEPS 16 // 0..256
|
||||
#define X_RSENSE 0.11
|
||||
#endif
|
||||
|
||||
#if AXIS_IS_TMC(X2)
|
||||
#define X2_CURRENT 800
|
||||
#define X2_MICROSTEPS 16
|
||||
#define X2_RSENSE 0.11
|
||||
#endif
|
||||
|
||||
#if AXIS_IS_TMC(Y)
|
||||
#define Y_CURRENT 800
|
||||
#define Y_MICROSTEPS 16
|
||||
#define Y_RSENSE 0.11
|
||||
#endif
|
||||
|
||||
#if AXIS_IS_TMC(Y2)
|
||||
#define Y2_CURRENT 800
|
||||
#define Y2_MICROSTEPS 16
|
||||
#define Y2_RSENSE 0.11
|
||||
#endif
|
||||
|
||||
#if AXIS_IS_TMC(Z)
|
||||
#define Z_CURRENT 800
|
||||
#define Z_MICROSTEPS 16
|
||||
#define Z_RSENSE 0.11
|
||||
#endif
|
||||
|
||||
#if AXIS_IS_TMC(Z2)
|
||||
#define Z2_CURRENT 800
|
||||
#define Z2_MICROSTEPS 16
|
||||
#define Z2_RSENSE 0.11
|
||||
#endif
|
||||
|
||||
#if AXIS_IS_TMC(Z3)
|
||||
#define Z3_CURRENT 800
|
||||
#define Z3_MICROSTEPS 16
|
||||
#define Z3_RSENSE 0.11
|
||||
#endif
|
||||
|
||||
#if AXIS_IS_TMC(E0)
|
||||
#define E0_CURRENT 800
|
||||
#define E0_MICROSTEPS 16
|
||||
#define E0_RSENSE 0.11
|
||||
#endif
|
||||
|
||||
#if AXIS_IS_TMC(E1)
|
||||
#define E1_CURRENT 800
|
||||
#define E1_MICROSTEPS 16
|
||||
#define E1_RSENSE 0.11
|
||||
#endif
|
||||
|
||||
#if AXIS_IS_TMC(E2)
|
||||
#define E2_CURRENT 800
|
||||
#define E2_MICROSTEPS 16
|
||||
#define E2_RSENSE 0.11
|
||||
#endif
|
||||
|
||||
#if AXIS_IS_TMC(E3)
|
||||
#define E3_CURRENT 800
|
||||
#define E3_MICROSTEPS 16
|
||||
#define E3_RSENSE 0.11
|
||||
#endif
|
||||
|
||||
#if AXIS_IS_TMC(E4)
|
||||
#define E4_CURRENT 800
|
||||
#define E4_MICROSTEPS 16
|
||||
#define E4_RSENSE 0.11
|
||||
#endif
|
||||
|
||||
#if AXIS_IS_TMC(E5)
|
||||
#define E5_CURRENT 800
|
||||
#define E5_MICROSTEPS 16
|
||||
#define E5_RSENSE 0.11
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Override default SPI pins for TMC2130, TMC2160, TMC2660, TMC5130 and TMC5160 drivers here.
|
||||
* The default pins can be found in your board's pins file.
|
||||
*/
|
||||
//#define X_CS_PIN -1
|
||||
//#define Y_CS_PIN -1
|
||||
//#define Z_CS_PIN -1
|
||||
//#define X2_CS_PIN -1
|
||||
//#define Y2_CS_PIN -1
|
||||
//#define Z2_CS_PIN -1
|
||||
//#define Z3_CS_PIN -1
|
||||
//#define E0_CS_PIN -1
|
||||
//#define E1_CS_PIN -1
|
||||
//#define E2_CS_PIN -1
|
||||
//#define E3_CS_PIN -1
|
||||
//#define E4_CS_PIN -1
|
||||
//#define E5_CS_PIN -1
|
||||
|
||||
/**
|
||||
* Use software SPI for TMC2130.
|
||||
* Software option for SPI driven drivers (TMC2130, TMC2160, TMC2660, TMC5130 and TMC5160).
|
||||
* The default SW SPI pins are defined the respective pins files,
|
||||
* but you can override or define them here.
|
||||
*/
|
||||
//#define TMC_USE_SW_SPI
|
||||
//#define TMC_SW_MOSI -1
|
||||
//#define TMC_SW_MISO -1
|
||||
//#define TMC_SW_SCK -1
|
||||
|
||||
/**
|
||||
* Software enable
|
||||
*
|
||||
* Use for drivers that do not use a dedicated enable pin, but rather handle the same
|
||||
* function through a communication line such as SPI or UART.
|
||||
*/
|
||||
//#define SOFTWARE_DRIVER_ENABLE
|
||||
|
||||
/**
|
||||
* TMC2130, TMC2160, TMC2208, TMC5130 and TMC5160 only
|
||||
* Use Trinamic's ultra quiet stepping mode.
|
||||
* When disabled, Marlin will use spreadCycle stepping mode.
|
||||
*/
|
||||
#define STEALTHCHOP_XY
|
||||
#define STEALTHCHOP_Z
|
||||
#define STEALTHCHOP_E
|
||||
|
||||
/**
|
||||
* Optimize spreadCycle chopper parameters by using predefined parameter sets
|
||||
* or with the help of an example included in the library.
|
||||
* Provided parameter sets are
|
||||
* CHOPPER_DEFAULT_12V
|
||||
* CHOPPER_DEFAULT_19V
|
||||
* CHOPPER_DEFAULT_24V
|
||||
* CHOPPER_DEFAULT_36V
|
||||
* CHOPPER_PRUSAMK3_24V // Imported parameters from the official Prusa firmware for MK3 (24V)
|
||||
* CHOPPER_MARLIN_119 // Old defaults from Marlin v1.1.9
|
||||
*
|
||||
* Define you own with
|
||||
* { <off_time[1..15]>, <hysteresis_end[-3..12]>, hysteresis_start[1..8] }
|
||||
*/
|
||||
#define CHOPPER_TIMING CHOPPER_DEFAULT_12V
|
||||
|
||||
/**
|
||||
* Monitor Trinamic drivers for error conditions,
|
||||
* like overtemperature and short to ground. TMC2208 requires hardware serial.
|
||||
* In the case of overtemperature Marlin can decrease the driver current until error condition clears.
|
||||
* Other detected conditions can be used to stop the current print.
|
||||
* Relevant g-codes:
|
||||
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
||||
* M911 - Report stepper driver overtemperature pre-warn condition.
|
||||
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
||||
* M122 - Report driver parameters (Requires TMC_DEBUG)
|
||||
*/
|
||||
//#define MONITOR_DRIVER_STATUS
|
||||
|
||||
#if ENABLED(MONITOR_DRIVER_STATUS)
|
||||
#define CURRENT_STEP_DOWN 50 // [mA]
|
||||
#define REPORT_CURRENT_CHANGE
|
||||
#define STOP_ON_ERROR
|
||||
#endif
|
||||
|
||||
/**
|
||||
* TMC2130, TMC2160, TMC2208, TMC5130 and TMC5160 only
|
||||
* The driver will switch to spreadCycle when stepper speed is over HYBRID_THRESHOLD.
|
||||
* This mode allows for faster movements at the expense of higher noise levels.
|
||||
* STEALTHCHOP_(XY|Z|E) must be enabled to use HYBRID_THRESHOLD.
|
||||
* M913 X/Y/Z/E to live tune the setting
|
||||
*/
|
||||
//#define HYBRID_THRESHOLD
|
||||
|
||||
#define X_HYBRID_THRESHOLD 100 // [mm/s]
|
||||
#define X2_HYBRID_THRESHOLD 100
|
||||
#define Y_HYBRID_THRESHOLD 100
|
||||
#define Y2_HYBRID_THRESHOLD 100
|
||||
#define Z_HYBRID_THRESHOLD 3
|
||||
#define Z2_HYBRID_THRESHOLD 3
|
||||
#define Z3_HYBRID_THRESHOLD 3
|
||||
#define E0_HYBRID_THRESHOLD 30
|
||||
#define E1_HYBRID_THRESHOLD 30
|
||||
#define E2_HYBRID_THRESHOLD 30
|
||||
#define E3_HYBRID_THRESHOLD 30
|
||||
#define E4_HYBRID_THRESHOLD 30
|
||||
#define E5_HYBRID_THRESHOLD 30
|
||||
|
||||
/**
|
||||
* TMC2130, TMC2160, TMC2660, TMC5130, and TMC5160 only
|
||||
* Use StallGuard2 to sense an obstacle and trigger an endstop.
|
||||
* Connect the stepper driver's DIAG1 pin to the X/Y endstop pin.
|
||||
* X, Y, and Z homing will always be done in spreadCycle mode.
|
||||
*
|
||||
* X/Y/Z_STALL_SENSITIVITY is used for tuning the trigger sensitivity.
|
||||
* Higher values make the system LESS sensitive.
|
||||
* Lower value make the system MORE sensitive.
|
||||
* Too low values can lead to false positives, while too high values will collide the axis without triggering.
|
||||
* It is advised to set X/Y/Z_HOME_BUMP_MM to 0.
|
||||
* M914 X/Y/Z to live tune the setting
|
||||
*/
|
||||
//#define SENSORLESS_HOMING // TMC2130 only
|
||||
|
||||
/**
|
||||
* Use StallGuard2 to probe the bed with the nozzle.
|
||||
*
|
||||
* CAUTION: This could cause damage to machines that use a lead screw or threaded rod
|
||||
* to move the Z axis. Take extreme care when attempting to enable this feature.
|
||||
*/
|
||||
//#define SENSORLESS_PROBING // TMC2130 only
|
||||
|
||||
#if EITHER(SENSORLESS_HOMING, SENSORLESS_PROBING)
|
||||
#define X_STALL_SENSITIVITY 8
|
||||
#define Y_STALL_SENSITIVITY 8
|
||||
//#define Z_STALL_SENSITIVITY 8
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Enable M122 debugging command for TMC stepper drivers.
|
||||
* M122 S0/1 will enable continous reporting.
|
||||
*/
|
||||
//#define TMC_DEBUG
|
||||
|
||||
/**
|
||||
* You can set your own advanced settings by filling in predefined functions.
|
||||
* A list of available functions can be found on the library github page
|
||||
* https://github.com/teemuatlut/TMCStepper
|
||||
*
|
||||
* Example:
|
||||
* #define TMC_ADV() { \
|
||||
* stepperX.diag0_temp_prewarn(1); \
|
||||
* stepperY.interpolate(0); \
|
||||
* }
|
||||
*/
|
||||
#define TMC_ADV() { }
|
||||
|
||||
#endif // HAS_TRINAMIC
|
||||
|
||||
// @section L6470
|
||||
|
||||
/**
|
||||
* L6470 Stepper Driver options
|
||||
*
|
||||
* Arduino-L6470 library (0.7.0 or higher) is required for this stepper driver.
|
||||
* https://github.com/ameyer/Arduino-L6470
|
||||
*
|
||||
* Requires the following to be defined in your pins_YOUR_BOARD file
|
||||
* L6470_CHAIN_SCK_PIN
|
||||
* L6470_CHAIN_MISO_PIN
|
||||
* L6470_CHAIN_MOSI_PIN
|
||||
* L6470_CHAIN_SS_PIN
|
||||
* L6470_RESET_CHAIN_PIN (optional)
|
||||
*/
|
||||
#if HAS_DRIVER(L6470)
|
||||
|
||||
//#define L6470_CHITCHAT // Display additional status info
|
||||
|
||||
#if AXIS_DRIVER_TYPE_X(L6470)
|
||||
#define X_MICROSTEPS 128 // Number of microsteps (VALID: 1, 2, 4, 8, 16, 32, 128)
|
||||
#define X_OVERCURRENT 2000 // (mA) Current where the driver detects an over current (VALID: 375 x (1 - 16) - 6A max - rounds down)
|
||||
#define X_STALLCURRENT 1500 // (mA) Current where the driver detects a stall (VALID: 31.25 * (1-128) - 4A max - rounds down)
|
||||
#define X_MAX_VOLTAGE 127 // 0-255, Maximum effective voltage seen by stepper
|
||||
#define X_CHAIN_POS 0 // Position in SPI chain, 0=Not in chain, 1=Nearest MOSI
|
||||
#endif
|
||||
|
||||
#if AXIS_DRIVER_TYPE_X2(L6470)
|
||||
#define X2_MICROSTEPS 128
|
||||
#define X2_OVERCURRENT 2000
|
||||
#define X2_STALLCURRENT 1500
|
||||
#define X2_MAX_VOLTAGE 127
|
||||
#define X2_CHAIN_POS 0
|
||||
#endif
|
||||
|
||||
#if AXIS_DRIVER_TYPE_Y(L6470)
|
||||
#define Y_MICROSTEPS 128
|
||||
#define Y_OVERCURRENT 2000
|
||||
#define Y_STALLCURRENT 1500
|
||||
#define Y_MAX_VOLTAGE 127
|
||||
#define Y_CHAIN_POS 0
|
||||
#endif
|
||||
|
||||
#if AXIS_DRIVER_TYPE_Y2(L6470)
|
||||
#define Y2_MICROSTEPS 128
|
||||
#define Y2_OVERCURRENT 2000
|
||||
#define Y2_STALLCURRENT 1500
|
||||
#define Y2_MAX_VOLTAGE 127
|
||||
#define Y2_CHAIN_POS 0
|
||||
#endif
|
||||
|
||||
#if AXIS_DRIVER_TYPE_Z(L6470)
|
||||
#define Z_MICROSTEPS 128
|
||||
#define Z_OVERCURRENT 2000
|
||||
#define Z_STALLCURRENT 1500
|
||||
#define Z_MAX_VOLTAGE 127
|
||||
#define Z_CHAIN_POS 0
|
||||
#endif
|
||||
|
||||
#if AXIS_DRIVER_TYPE_Z2(L6470)
|
||||
#define Z2_MICROSTEPS 128
|
||||
#define Z2_OVERCURRENT 2000
|
||||
#define Z2_STALLCURRENT 1500
|
||||
#define Z2_MAX_VOLTAGE 127
|
||||
#define Z2_CHAIN_POS 0
|
||||
#endif
|
||||
|
||||
#if AXIS_DRIVER_TYPE_Z3(L6470)
|
||||
#define Z3_MICROSTEPS 128
|
||||
#define Z3_OVERCURRENT 2000
|
||||
#define Z3_STALLCURRENT 1500
|
||||
#define Z3_MAX_VOLTAGE 127
|
||||
#define Z3_CHAIN_POS 0
|
||||
#endif
|
||||
|
||||
#if AXIS_DRIVER_TYPE_E0(L6470)
|
||||
#define E0_MICROSTEPS 128
|
||||
#define E0_OVERCURRENT 2000
|
||||
#define E0_STALLCURRENT 1500
|
||||
#define E0_MAX_VOLTAGE 127
|
||||
#define E0_CHAIN_POS 0
|
||||
#endif
|
||||
|
||||
#if AXIS_DRIVER_TYPE_E1(L6470)
|
||||
#define E1_MICROSTEPS 128
|
||||
#define E1_OVERCURRENT 2000
|
||||
#define E1_STALLCURRENT 1500
|
||||
#define E1_MAX_VOLTAGE 127
|
||||
#define E1_CHAIN_POS 0
|
||||
#endif
|
||||
|
||||
#if AXIS_DRIVER_TYPE_E2(L6470)
|
||||
#define E2_MICROSTEPS 128
|
||||
#define E2_OVERCURRENT 2000
|
||||
#define E2_STALLCURRENT 1500
|
||||
#define E2_MAX_VOLTAGE 127
|
||||
#define E2_CHAIN_POS 0
|
||||
#endif
|
||||
|
||||
#if AXIS_DRIVER_TYPE_E3(L6470)
|
||||
#define E3_MICROSTEPS 128
|
||||
#define E3_OVERCURRENT 2000
|
||||
#define E3_STALLCURRENT 1500
|
||||
#define E3_MAX_VOLTAGE 127
|
||||
#define E3_CHAIN_POS 0
|
||||
#endif
|
||||
|
||||
#if AXIS_DRIVER_TYPE_E4(L6470)
|
||||
#define E4_MICROSTEPS 128
|
||||
#define E4_OVERCURRENT 2000
|
||||
#define E4_STALLCURRENT 1500
|
||||
#define E4_MAX_VOLTAGE 127
|
||||
#define E4_CHAIN_POS 0
|
||||
#endif
|
||||
|
||||
#if AXIS_DRIVER_TYPE_E5(L6470)
|
||||
#define E5_MICROSTEPS 128
|
||||
#define E5_OVERCURRENT 2000
|
||||
#define E5_STALLCURRENT 1500
|
||||
#define E5_MAX_VOLTAGE 127
|
||||
#define E5_CHAIN_POS 0
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Monitor L6470 drivers for error conditions like over temperature and over current.
|
||||
* In the case of over temperature Marlin can decrease the drive until the error condition clears.
|
||||
* Other detected conditions can be used to stop the current print.
|
||||
* Relevant g-codes:
|
||||
* M906 - I1/2/3/4/5 Set or get motor drive level using axis codes X, Y, Z, E. Report values if no axis codes given.
|
||||
* I not present or I0 or I1 - X, Y, Z or E0
|
||||
* I2 - X2, Y2, Z2 or E1
|
||||
* I3 - Z3 or E3
|
||||
* I4 - E4
|
||||
* I5 - E5
|
||||
* M916 - Increase drive level until get thermal warning
|
||||
* M917 - Find minimum current thresholds
|
||||
* M918 - Increase speed until max or error
|
||||
* M122 S0/1 - Report driver parameters
|
||||
*/
|
||||
//#define MONITOR_L6470_DRIVER_STATUS
|
||||
|
||||
#if ENABLED(MONITOR_L6470_DRIVER_STATUS)
|
||||
#define KVAL_HOLD_STEP_DOWN 1
|
||||
//#define L6470_STOP_ON_ERROR
|
||||
#endif
|
||||
|
||||
#endif // L6470
|
||||
|
||||
/**
|
||||
* TWI/I2C BUS
|
||||
*
|
||||
* This feature is an EXPERIMENTAL feature so it shall not be used on production
|
||||
* machines. Enabling this will allow you to send and receive I2C data from slave
|
||||
* devices on the bus.
|
||||
*
|
||||
* ; Example #1
|
||||
* ; This macro send the string "Marlin" to the slave device with address 0x63 (99)
|
||||
* ; It uses multiple M260 commands with one B<base 10> arg
|
||||
* M260 A99 ; Target slave address
|
||||
* M260 B77 ; M
|
||||
* M260 B97 ; a
|
||||
* M260 B114 ; r
|
||||
* M260 B108 ; l
|
||||
* M260 B105 ; i
|
||||
* M260 B110 ; n
|
||||
* M260 S1 ; Send the current buffer
|
||||
*
|
||||
* ; Example #2
|
||||
* ; Request 6 bytes from slave device with address 0x63 (99)
|
||||
* M261 A99 B5
|
||||
*
|
||||
* ; Example #3
|
||||
* ; Example serial output of a M261 request
|
||||
* echo:i2c-reply: from:99 bytes:5 data:hello
|
||||
*/
|
||||
|
||||
// @section i2cbus
|
||||
|
||||
//#define EXPERIMENTAL_I2CBUS
|
||||
#define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave
|
||||
|
||||
// @section extras
|
||||
|
||||
/**
|
||||
* Photo G-code
|
||||
* Add the M240 G-code to take a photo.
|
||||
* The photo can be triggered by a digital pin or a physical movement.
|
||||
*/
|
||||
//#define PHOTO_GCODE
|
||||
#if ENABLED(PHOTO_GCODE)
|
||||
// A position to move to (and raise Z) before taking the photo
|
||||
//#define PHOTO_POSITION { X_MAX_POS - 5, Y_MAX_POS, 0 } // { xpos, ypos, zraise } (M240 X Y Z)
|
||||
//#define PHOTO_DELAY_MS 100 // (ms) Duration to pause before moving back (M240 P)
|
||||
//#define PHOTO_RETRACT_MM 6.5 // (mm) E retract/recover for the photo move (M240 R S)
|
||||
|
||||
// Canon RC-1 or homebrew digital camera trigger
|
||||
// Data from: http://www.doc-diy.net/photo/rc-1_hacked/
|
||||
//#define PHOTOGRAPH_PIN 23
|
||||
|
||||
// Canon Hack Development Kit
|
||||
// http://captain-slow.dk/2014/03/09/3d-printing-timelapses/
|
||||
//#define CHDK_PIN 4
|
||||
|
||||
// Optional second move with delay to trigger the camera shutter
|
||||
//#define PHOTO_SWITCH_POSITION { X_MAX_POS, Y_MAX_POS } // { xpos, ypos } (M240 I J)
|
||||
|
||||
// Duration to hold the switch or keep CHDK_PIN high
|
||||
//#define PHOTO_SWITCH_MS 50 // (ms) (M240 D)
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Spindle & Laser control
|
||||
*
|
||||
* Add the M3, M4, and M5 commands to turn the spindle/laser on and off, and
|
||||
* to set spindle speed, spindle direction, and laser power.
|
||||
*
|
||||
* SuperPid is a router/spindle speed controller used in the CNC milling community.
|
||||
* Marlin can be used to turn the spindle on and off. It can also be used to set
|
||||
* the spindle speed from 5,000 to 30,000 RPM.
|
||||
*
|
||||
* You'll need to select a pin for the ON/OFF function and optionally choose a 0-5V
|
||||
* hardware PWM pin for the speed control and a pin for the rotation direction.
|
||||
*
|
||||
* See http://marlinfw.org/docs/configuration/laser_spindle.html for more config details.
|
||||
*/
|
||||
//#define SPINDLE_LASER_ENABLE
|
||||
#if ENABLED(SPINDLE_LASER_ENABLE)
|
||||
|
||||
#define SPINDLE_LASER_ENABLE_INVERT false // set to "true" if the on/off function is reversed
|
||||
#define SPINDLE_LASER_PWM true // set to true if your controller supports setting the speed/power
|
||||
#define SPINDLE_LASER_PWM_INVERT true // set to "true" if the speed/power goes up when you want it to go slower
|
||||
#define SPINDLE_LASER_POWERUP_DELAY 5000 // delay in milliseconds to allow the spindle/laser to come up to speed/power
|
||||
#define SPINDLE_LASER_POWERDOWN_DELAY 5000 // delay in milliseconds to allow the spindle to stop
|
||||
#define SPINDLE_DIR_CHANGE true // set to true if your spindle controller supports changing spindle direction
|
||||
#define SPINDLE_INVERT_DIR false
|
||||
#define SPINDLE_STOP_ON_DIR_CHANGE true // set to true if Marlin should stop the spindle before changing rotation direction
|
||||
|
||||
/**
|
||||
* The M3 & M4 commands use the following equation to convert PWM duty cycle to speed/power
|
||||
*
|
||||
* SPEED/POWER = PWM duty cycle * SPEED_POWER_SLOPE + SPEED_POWER_INTERCEPT
|
||||
* where PWM duty cycle varies from 0 to 255
|
||||
*
|
||||
* set the following for your controller (ALL MUST BE SET)
|
||||
*/
|
||||
|
||||
#define SPEED_POWER_SLOPE 118.4
|
||||
#define SPEED_POWER_INTERCEPT 0
|
||||
#define SPEED_POWER_MIN 5000
|
||||
#define SPEED_POWER_MAX 30000 // SuperPID router controller 0 - 30,000 RPM
|
||||
|
||||
//#define SPEED_POWER_SLOPE 0.3922
|
||||
//#define SPEED_POWER_INTERCEPT 0
|
||||
//#define SPEED_POWER_MIN 10
|
||||
//#define SPEED_POWER_MAX 100 // 0-100%
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Filament Width Sensor
|
||||
*
|
||||
* Measures the filament width in real-time and adjusts
|
||||
* flow rate to compensate for any irregularities.
|
||||
*
|
||||
* Also allows the measured filament diameter to set the
|
||||
* extrusion rate, so the slicer only has to specify the
|
||||
* volume.
|
||||
*
|
||||
* Only a single extruder is supported at this time.
|
||||
*
|
||||
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
||||
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
||||
* 301 RAMBO : Analog input 3
|
||||
*
|
||||
* Note: May require analog pins to be defined for other boards.
|
||||
*/
|
||||
//#define FILAMENT_WIDTH_SENSOR
|
||||
|
||||
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor. :[0,1,2,3,4]
|
||||
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
||||
|
||||
#define FILWIDTH_ERROR_MARGIN 1.0 // (mm) If a measurement differs too much from nominal width ignore it
|
||||
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
||||
|
||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
||||
|
||||
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
||||
//#define FILAMENT_LCD_DISPLAY
|
||||
#endif
|
||||
|
||||
/**
|
||||
* CNC Coordinate Systems
|
||||
*
|
||||
* Enables G53 and G54-G59.3 commands to select coordinate systems
|
||||
* and G92.1 to reset the workspace to native machine space.
|
||||
*/
|
||||
//#define CNC_COORDINATE_SYSTEMS
|
||||
|
||||
/**
|
||||
* Auto-report temperatures with M155 S<seconds>
|
||||
*/
|
||||
#define AUTO_REPORT_TEMPERATURES
|
||||
|
||||
/**
|
||||
* Include capabilities in M115 output
|
||||
*/
|
||||
#define EXTENDED_CAPABILITIES_REPORT
|
||||
|
||||
/**
|
||||
* Disable all Volumetric extrusion options
|
||||
*/
|
||||
//#define NO_VOLUMETRICS
|
||||
|
||||
#if DISABLED(NO_VOLUMETRICS)
|
||||
/**
|
||||
* Volumetric extrusion default state
|
||||
* Activate to make volumetric extrusion the default method,
|
||||
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
||||
*
|
||||
* M200 D0 to disable, M200 Dn to set a new diameter.
|
||||
*/
|
||||
//#define VOLUMETRIC_DEFAULT_ON
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Enable this option for a leaner build of Marlin that removes all
|
||||
* workspace offsets, simplifying coordinate transformations, leveling, etc.
|
||||
*
|
||||
* - M206 and M428 are disabled.
|
||||
* - G92 will revert to its behavior from Marlin 1.0.
|
||||
*/
|
||||
//#define NO_WORKSPACE_OFFSETS
|
||||
|
||||
/**
|
||||
* Set the number of proportional font spaces required to fill up a typical character space.
|
||||
* This can help to better align the output of commands like `G29 O` Mesh Output.
|
||||
*
|
||||
* For clients that use a fixed-width font (like OctoPrint), leave this set to 1.0.
|
||||
* Otherwise, adjust according to your client and font.
|
||||
*/
|
||||
#define PROPORTIONAL_FONT_RATIO 1.0
|
||||
|
||||
/**
|
||||
* Spend 28 bytes of SRAM to optimize the GCode parser
|
||||
*/
|
||||
#define FASTER_GCODE_PARSER
|
||||
|
||||
/**
|
||||
* CNC G-code options
|
||||
* Support CNC-style G-code dialects used by laser cutters, drawing machine cams, etc.
|
||||
* Note that G0 feedrates should be used with care for 3D printing (if used at all).
|
||||
* High feedrates may cause ringing and harm print quality.
|
||||
*/
|
||||
//#define PAREN_COMMENTS // Support for parentheses-delimited comments
|
||||
//#define GCODE_MOTION_MODES // Remember the motion mode (G0 G1 G2 G3 G5 G38.X) and apply for X Y Z E F, etc.
|
||||
|
||||
// Enable and set a (default) feedrate for all G0 moves
|
||||
//#define G0_FEEDRATE 3000 // (mm/m)
|
||||
#ifdef G0_FEEDRATE
|
||||
//#define VARIABLE_G0_FEEDRATE // The G0 feedrate is set by F in G0 motion mode
|
||||
#endif
|
||||
|
||||
/**
|
||||
* G-code Macros
|
||||
*
|
||||
* Add G-codes M810-M819 to define and run G-code macros.
|
||||
* Macros are not saved to EEPROM.
|
||||
*/
|
||||
//#define GCODE_MACROS
|
||||
#if ENABLED(GCODE_MACROS)
|
||||
#define GCODE_MACROS_SLOTS 5 // Up to 10 may be used
|
||||
#define GCODE_MACROS_SLOT_SIZE 50 // Maximum length of a single macro
|
||||
#endif
|
||||
|
||||
/**
|
||||
* User-defined menu items that execute custom GCode
|
||||
*/
|
||||
//#define CUSTOM_USER_MENUS
|
||||
#if ENABLED(CUSTOM_USER_MENUS)
|
||||
//#define CUSTOM_USER_MENU_TITLE "Custom Commands"
|
||||
#define USER_SCRIPT_DONE "M117 User Script Done"
|
||||
#define USER_SCRIPT_AUDIBLE_FEEDBACK
|
||||
//#define USER_SCRIPT_RETURN // Return to status screen after a script
|
||||
|
||||
#define USER_DESC_1 "Home & UBL Info"
|
||||
#define USER_GCODE_1 "G28\nG29 W"
|
||||
|
||||
#define USER_DESC_2 "Preheat for " PREHEAT_1_LABEL
|
||||
#define USER_GCODE_2 "M140 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND)
|
||||
|
||||
#define USER_DESC_3 "Preheat for " PREHEAT_2_LABEL
|
||||
#define USER_GCODE_3 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND)
|
||||
|
||||
#define USER_DESC_4 "Heat Bed/Home/Level"
|
||||
#define USER_GCODE_4 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nG28\nG29"
|
||||
|
||||
#define USER_DESC_5 "Home & Info"
|
||||
#define USER_GCODE_5 "G28\nM503"
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Host Action Commands
|
||||
*
|
||||
* Define host streamer action commands in compliance with the standard.
|
||||
*
|
||||
* See https://reprap.org/wiki/G-code#Action_commands
|
||||
* Common commands ........ poweroff, pause, paused, resume, resumed, cancel
|
||||
* G29_RETRY_AND_RECOVER .. probe_rewipe, probe_failed
|
||||
*
|
||||
* Some features add reason codes to extend these commands.
|
||||
*
|
||||
* Host Prompt Support enables Marlin to use the host for user prompts so
|
||||
* filament runout and other processes can be managed from the host side.
|
||||
*/
|
||||
//#define HOST_ACTION_COMMANDS
|
||||
#if ENABLED(HOST_ACTION_COMMANDS)
|
||||
//#define HOST_PROMPT_SUPPORT
|
||||
#endif
|
||||
|
||||
//===========================================================================
|
||||
//====================== I2C Position Encoder Settings ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
* I2C position encoders for closed loop control.
|
||||
* Developed by Chris Barr at Aus3D.
|
||||
*
|
||||
* Wiki: http://wiki.aus3d.com.au/Magnetic_Encoder
|
||||
* Github: https://github.com/Aus3D/MagneticEncoder
|
||||
*
|
||||
* Supplier: http://aus3d.com.au/magnetic-encoder-module
|
||||
* Alternative Supplier: http://reliabuild3d.com/
|
||||
*
|
||||
* Reliabuild encoders have been modified to improve reliability.
|
||||
*/
|
||||
|
||||
//#define I2C_POSITION_ENCODERS
|
||||
#if ENABLED(I2C_POSITION_ENCODERS)
|
||||
|
||||
#define I2CPE_ENCODER_CNT 1 // The number of encoders installed; max of 5
|
||||
// encoders supported currently.
|
||||
|
||||
#define I2CPE_ENC_1_ADDR I2CPE_PRESET_ADDR_X // I2C address of the encoder. 30-200.
|
||||
#define I2CPE_ENC_1_AXIS X_AXIS // Axis the encoder module is installed on. <X|Y|Z|E>_AXIS.
|
||||
#define I2CPE_ENC_1_TYPE I2CPE_ENC_TYPE_LINEAR // Type of encoder: I2CPE_ENC_TYPE_LINEAR -or-
|
||||
// I2CPE_ENC_TYPE_ROTARY.
|
||||
#define I2CPE_ENC_1_TICKS_UNIT 2048 // 1024 for magnetic strips with 2mm poles; 2048 for
|
||||
// 1mm poles. For linear encoders this is ticks / mm,
|
||||
// for rotary encoders this is ticks / revolution.
|
||||
//#define I2CPE_ENC_1_TICKS_REV (16 * 200) // Only needed for rotary encoders; number of stepper
|
||||
// steps per full revolution (motor steps/rev * microstepping)
|
||||
//#define I2CPE_ENC_1_INVERT // Invert the direction of axis travel.
|
||||
#define I2CPE_ENC_1_EC_METHOD I2CPE_ECM_MICROSTEP // Type of error error correction.
|
||||
#define I2CPE_ENC_1_EC_THRESH 0.10 // Threshold size for error (in mm) above which the
|
||||
// printer will attempt to correct the error; errors
|
||||
// smaller than this are ignored to minimize effects of
|
||||
// measurement noise / latency (filter).
|
||||
|
||||
#define I2CPE_ENC_2_ADDR I2CPE_PRESET_ADDR_Y // Same as above, but for encoder 2.
|
||||
#define I2CPE_ENC_2_AXIS Y_AXIS
|
||||
#define I2CPE_ENC_2_TYPE I2CPE_ENC_TYPE_LINEAR
|
||||
#define I2CPE_ENC_2_TICKS_UNIT 2048
|
||||
//#define I2CPE_ENC_2_TICKS_REV (16 * 200)
|
||||
//#define I2CPE_ENC_2_INVERT
|
||||
#define I2CPE_ENC_2_EC_METHOD I2CPE_ECM_MICROSTEP
|
||||
#define I2CPE_ENC_2_EC_THRESH 0.10
|
||||
|
||||
#define I2CPE_ENC_3_ADDR I2CPE_PRESET_ADDR_Z // Encoder 3. Add additional configuration options
|
||||
#define I2CPE_ENC_3_AXIS Z_AXIS // as above, or use defaults below.
|
||||
|
||||
#define I2CPE_ENC_4_ADDR I2CPE_PRESET_ADDR_E // Encoder 4.
|
||||
#define I2CPE_ENC_4_AXIS E_AXIS
|
||||
|
||||
#define I2CPE_ENC_5_ADDR 34 // Encoder 5.
|
||||
#define I2CPE_ENC_5_AXIS E_AXIS
|
||||
|
||||
// Default settings for encoders which are enabled, but without settings configured above.
|
||||
#define I2CPE_DEF_TYPE I2CPE_ENC_TYPE_LINEAR
|
||||
#define I2CPE_DEF_ENC_TICKS_UNIT 2048
|
||||
#define I2CPE_DEF_TICKS_REV (16 * 200)
|
||||
#define I2CPE_DEF_EC_METHOD I2CPE_ECM_NONE
|
||||
#define I2CPE_DEF_EC_THRESH 0.1
|
||||
|
||||
//#define I2CPE_ERR_THRESH_ABORT 100.0 // Threshold size for error (in mm) error on any given
|
||||
// axis after which the printer will abort. Comment out to
|
||||
// disable abort behaviour.
|
||||
|
||||
#define I2CPE_TIME_TRUSTED 10000 // After an encoder fault, there must be no further fault
|
||||
// for this amount of time (in ms) before the encoder
|
||||
// is trusted again.
|
||||
|
||||
/**
|
||||
* Position is checked every time a new command is executed from the buffer but during long moves,
|
||||
* this setting determines the minimum update time between checks. A value of 100 works well with
|
||||
* error rolling average when attempting to correct only for skips and not for vibration.
|
||||
*/
|
||||
#define I2CPE_MIN_UPD_TIME_MS 4 // (ms) Minimum time between encoder checks.
|
||||
|
||||
// Use a rolling average to identify persistant errors that indicate skips, as opposed to vibration and noise.
|
||||
#define I2CPE_ERR_ROLLING_AVERAGE
|
||||
|
||||
#endif // I2C_POSITION_ENCODERS
|
||||
|
||||
/**
|
||||
* MAX7219 Debug Matrix
|
||||
*
|
||||
* Add support for a low-cost 8x8 LED Matrix based on the Max7219 chip as a realtime status display.
|
||||
* Requires 3 signal wires. Some useful debug options are included to demonstrate its usage.
|
||||
*/
|
||||
//#define MAX7219_DEBUG
|
||||
#if ENABLED(MAX7219_DEBUG)
|
||||
#define MAX7219_CLK_PIN 64
|
||||
#define MAX7219_DIN_PIN 57
|
||||
#define MAX7219_LOAD_PIN 44
|
||||
|
||||
//#define MAX7219_GCODE // Add the M7219 G-code to control the LED matrix
|
||||
#define MAX7219_INIT_TEST 2 // Do a test pattern at initialization (Set to 2 for spiral)
|
||||
#define MAX7219_NUMBER_UNITS 1 // Number of Max7219 units in chain.
|
||||
#define MAX7219_ROTATE 0 // Rotate the display clockwise (in multiples of +/- 90°)
|
||||
// connector at: right=0 bottom=-90 top=90 left=180
|
||||
//#define MAX7219_REVERSE_ORDER // The individual LED matrix units may be in reversed order
|
||||
|
||||
/**
|
||||
* Sample debug features
|
||||
* If you add more debug displays, be careful to avoid conflicts!
|
||||
*/
|
||||
#define MAX7219_DEBUG_PRINTER_ALIVE // Blink corner LED of 8x8 matrix to show that the firmware is functioning
|
||||
#define MAX7219_DEBUG_PLANNER_HEAD 3 // Show the planner queue head position on this and the next LED matrix row
|
||||
#define MAX7219_DEBUG_PLANNER_TAIL 5 // Show the planner queue tail position on this and the next LED matrix row
|
||||
|
||||
#define MAX7219_DEBUG_PLANNER_QUEUE 0 // Show the current planner queue depth on this and the next LED matrix row
|
||||
// If you experience stuttering, reboots, etc. this option can reveal how
|
||||
// tweaks made to the configuration are affecting the printer in real-time.
|
||||
#endif
|
||||
|
||||
/**
|
||||
* NanoDLP Sync support
|
||||
*
|
||||
* Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp"
|
||||
* string to enable synchronization with DLP projector exposure. This change will allow to use
|
||||
* [[WaitForDoneMessage]] instead of populating your gcode with M400 commands
|
||||
*/
|
||||
//#define NANODLP_Z_SYNC
|
||||
#if ENABLED(NANODLP_Z_SYNC)
|
||||
//#define NANODLP_ALL_AXIS // Enables "Z_move_comp" output on any axis move.
|
||||
// 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"
|
||||
//#define WEBSUPPORT // Start a webserver with auto-discovery
|
||||
//#define OTASUPPORT // Support over-the-air firmware updates
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Prusa Multi-Material Unit v2
|
||||
* Enable in Configuration.h
|
||||
*/
|
||||
#if ENABLED(PRUSA_MMU2)
|
||||
|
||||
// Serial port used for communication with MMU2.
|
||||
// For AVR enable the UART port used for the MMU. (e.g., internalSerial)
|
||||
// For 32-bit boards check your HAL for available serial ports. (e.g., Serial2)
|
||||
#define INTERNAL_SERIAL_PORT 2
|
||||
#define MMU2_SERIAL internalSerial
|
||||
|
||||
// Use hardware reset for MMU if a pin is defined for it
|
||||
//#define MMU2_RST_PIN 23
|
||||
|
||||
// Enable if the MMU2 has 12V stepper motors (MMU2 Firmware 1.0.2 and up)
|
||||
//#define MMU2_MODE_12V
|
||||
|
||||
// G-code to execute when MMU2 F.I.N.D.A. probe detects filament runout
|
||||
#define MMU2_FILAMENT_RUNOUT_SCRIPT "M600"
|
||||
|
||||
// Add an LCD menu for MMU2
|
||||
//#define MMU2_MENUS
|
||||
#if ENABLED(MMU2_MENUS)
|
||||
// Settings for filament load / unload from the LCD menu.
|
||||
// This is for Prusa MK3-style extruders. Customize for your hardware.
|
||||
#define MMU2_FILAMENTCHANGE_EJECT_FEED 80.0
|
||||
#define MMU2_LOAD_TO_NOZZLE_SEQUENCE \
|
||||
{ 7.2, 562 }, \
|
||||
{ 14.4, 871 }, \
|
||||
{ 36.0, 1393 }, \
|
||||
{ 14.4, 871 }, \
|
||||
{ 50.0, 198 }
|
||||
|
||||
#define MMU2_RAMMING_SEQUENCE \
|
||||
{ 1.0, 1000 }, \
|
||||
{ 1.0, 1500 }, \
|
||||
{ 2.0, 2000 }, \
|
||||
{ 1.5, 3000 }, \
|
||||
{ 2.5, 4000 }, \
|
||||
{ -15.0, 5000 }, \
|
||||
{ -14.0, 1200 }, \
|
||||
{ -6.0, 600 }, \
|
||||
{ 10.0, 700 }, \
|
||||
{ -10.0, 400 }, \
|
||||
{ -50.0, 2000 }
|
||||
|
||||
#endif
|
||||
|
||||
//#define MMU2_DEBUG // Write debug info to serial output
|
||||
|
||||
#endif // PRUSA_MMU2
|
||||
|
||||
/**
|
||||
* Advanced Print Counter settings
|
||||
*/
|
||||
#if ENABLED(PRINTCOUNTER)
|
||||
#define SERVICE_WARNING_BUZZES 3
|
||||
// Activate up to 3 service interval watchdogs
|
||||
//#define SERVICE_NAME_1 "Service S"
|
||||
//#define SERVICE_INTERVAL_1 100 // print hours
|
||||
//#define SERVICE_NAME_2 "Service L"
|
||||
//#define SERVICE_INTERVAL_2 200 // print hours
|
||||
//#define SERVICE_NAME_3 "Service 3"
|
||||
//#define SERVICE_INTERVAL_3 1 // print hours
|
||||
#endif
|
||||
|
||||
// @section develop
|
||||
|
||||
/**
|
||||
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
||||
*/
|
||||
//#define PINS_DEBUGGING
|
||||
|
||||
// Enable Marlin dev mode which adds some special commands
|
||||
//#define MARLIN_DEV_MODE
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -378,7 +392,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 998
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 60
|
||||
|
@ -397,8 +410,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -408,7 +419,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -420,7 +430,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -463,7 +472,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1415,7 +1424,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1895,6 +1904,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2052,10 +2067,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 0
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -462,7 +471,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1413,7 +1422,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1893,6 +1902,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2050,10 +2065,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -378,7 +392,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 998
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 60
|
||||
|
@ -397,8 +410,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -408,7 +419,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -420,7 +430,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -463,7 +472,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1415,7 +1424,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1895,6 +1904,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2052,10 +2067,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -462,7 +471,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1444,7 +1453,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1924,6 +1933,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 5
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -462,7 +471,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1413,7 +1422,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1893,6 +1902,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2050,10 +2065,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -271,13 +271,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -404,7 +418,6 @@
|
|||
#define TEMP_SENSOR_BED 0
|
||||
#endif
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -423,8 +436,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -434,7 +445,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -446,7 +456,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 100
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -499,7 +508,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1469,7 +1478,7 @@
|
|||
#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1949,6 +1958,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2106,10 +2121,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G27" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 0
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 260
|
||||
#define HEATER_5_MAXTEMP 260
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -462,7 +471,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1413,7 +1422,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1893,6 +1902,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2050,10 +2065,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 501
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 130
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -462,7 +471,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1417,7 +1426,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1897,6 +1906,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2054,10 +2069,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -251,13 +251,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -379,7 +393,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -398,8 +411,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -409,7 +420,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -425,7 +435,6 @@
|
|||
// Tronxy X5S-2E:
|
||||
// The OEM stock model uses a clone MK3a 300 @ 12V with no insulation and can reach a maximum 70C at 25C ambient.
|
||||
#define BED_MAXTEMP 81
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -475,7 +484,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1434,7 +1443,7 @@
|
|||
#define NOZZLE_PARK_FEATURE P2
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1914,6 +1923,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2071,10 +2086,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G27" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -461,7 +470,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1412,7 +1421,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1892,6 +1901,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2049,10 +2064,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 0
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -473,7 +482,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1424,7 +1433,7 @@
|
|||
#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1904,6 +1913,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2061,10 +2076,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 0
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -462,7 +471,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1413,7 +1422,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1893,6 +1902,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2050,10 +2065,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 0
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -462,7 +471,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1413,7 +1422,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1893,6 +1902,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2050,10 +2065,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -467,7 +476,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1422,7 +1431,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1902,6 +1911,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2059,10 +2074,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -269,13 +269,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -397,7 +411,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 5
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -416,8 +429,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -427,7 +438,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -439,7 +449,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -486,7 +495,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1443,7 +1452,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1926,6 +1935,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2085,10 +2100,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -59,6 +59,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -140,8 +153,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -469,6 +482,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 4, 4, 8 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -786,8 +800,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -975,6 +992,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1023,6 +1046,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 0
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -462,7 +471,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1413,7 +1422,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1893,6 +1902,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 1000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 3
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 0
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -462,7 +471,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1413,7 +1422,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1893,6 +1902,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
|
|
@ -268,13 +268,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -396,7 +410,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 0
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -415,8 +428,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -426,7 +437,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -438,7 +448,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -481,7 +490,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1432,7 +1441,7 @@
|
|||
#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 190 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 10 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1912,6 +1921,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2069,10 +2084,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G27" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 120
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -467,7 +476,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1423,7 +1432,7 @@
|
|||
#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1906,6 +1915,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2063,10 +2078,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -772,8 +786,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G27" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -961,6 +978,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1009,6 +1032,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 0
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -462,7 +471,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1413,7 +1422,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1893,6 +1902,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2050,10 +2065,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -264,13 +264,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -398,7 +412,6 @@
|
|||
#endif
|
||||
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -417,8 +430,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -428,7 +439,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -440,7 +450,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 120
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -488,7 +497,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1603,7 +1612,7 @@
|
|||
#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { 0, 0, 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 100 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -2083,6 +2092,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2240,10 +2255,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 5 // deltas need the same for all three axes
|
||||
#define HOMING_BUMP_DIVISOR { 10, 10, 10 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -772,8 +786,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G27" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -961,6 +978,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1009,6 +1032,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 5
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 250
|
||||
#define HEATER_5_MAXTEMP 250
|
||||
#define BED_MAXTEMP 115
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -467,7 +476,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1541,7 +1550,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), 0, 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -2021,6 +2030,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2178,10 +2193,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 5 // deltas need the same for all three axes
|
||||
#define HOMING_BUMP_DIVISOR { 10, 10, 10 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -772,8 +786,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -961,6 +978,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1009,6 +1032,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 5
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 250
|
||||
#define HEATER_5_MAXTEMP 250
|
||||
#define BED_MAXTEMP 115
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -467,7 +476,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1540,7 +1549,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), 0, 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -2020,6 +2029,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2177,10 +2192,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 5 // deltas need the same for all three axes
|
||||
#define HOMING_BUMP_DIVISOR { 10, 10, 10 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -772,8 +786,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -961,6 +978,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1009,6 +1032,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -467,7 +476,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1540,7 +1549,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), 0, 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -2020,6 +2029,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2177,10 +2192,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 5 // deltas need the same for all three axes
|
||||
#define HOMING_BUMP_DIVISOR { 10, 10, 10 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -772,8 +786,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -961,6 +978,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1009,6 +1032,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -462,7 +471,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1116,9 +1125,6 @@
|
|||
#define Y_MAX_POS DELTA_PRINTABLE_RADIUS
|
||||
#define Z_MAX_POS MANUAL_Z_HOME_POS
|
||||
|
||||
// Z raise distance for tool-change, as needed for some extruders
|
||||
#define TOOLCHANGE_ZRAISE 2 // (mm)
|
||||
|
||||
/**
|
||||
* Software Endstops
|
||||
*
|
||||
|
@ -1531,7 +1537,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), 0, 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -2011,6 +2017,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2168,10 +2180,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 5 // deltas need the same for all three axes
|
||||
#define HOMING_BUMP_DIVISOR { 10, 10, 10 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -772,8 +786,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -961,6 +978,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1009,6 +1032,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -254,13 +254,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -382,7 +396,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -401,8 +414,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -412,7 +423,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -424,7 +434,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -472,7 +481,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1543,7 +1552,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), 0, 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -2023,6 +2032,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2180,10 +2195,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 5
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -462,7 +471,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1528,7 +1537,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -2008,6 +2017,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2165,10 +2180,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 5 // deltas need the same for all three axes
|
||||
#define HOMING_BUMP_DIVISOR { 10, 10, 10 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -772,8 +786,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -961,6 +978,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1009,6 +1032,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -466,7 +475,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1521,7 +1530,7 @@
|
|||
#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { 0, 0, (DELTA_HEIGHT - 10) }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -2001,6 +2010,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2158,10 +2173,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 5 // deltas need the same for all three axes
|
||||
#define HOMING_BUMP_DIVISOR { 10, 10, 10 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -772,8 +786,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G27" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -961,6 +978,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1009,6 +1032,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 0
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -462,7 +471,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1528,7 +1537,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), 0, 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -2008,6 +2017,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2165,10 +2180,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 5 // deltas need the same for all three axes
|
||||
#define HOMING_BUMP_DIVISOR { 10, 10, 10 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -772,8 +786,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -961,6 +978,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1009,6 +1032,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 11
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -462,7 +471,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1530,7 +1539,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), 0, 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -2010,6 +2019,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2167,10 +2182,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 5 // deltas need the same for all three axes
|
||||
#define HOMING_BUMP_DIVISOR { 10, 10, 10 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -771,8 +785,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -960,6 +977,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1008,6 +1031,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -253,13 +253,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -381,7 +395,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 5
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -400,8 +413,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -411,7 +422,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -423,7 +433,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -454,7 +463,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1531,7 +1540,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), 0, 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -2011,6 +2020,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2168,10 +2183,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 5
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -466,7 +475,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1531,7 +1540,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), 0, 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -2011,6 +2020,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2168,10 +2183,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2 // deltas need the same for all three axes
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -772,8 +786,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -961,6 +978,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1009,6 +1032,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -254,13 +254,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -385,7 +399,6 @@
|
|||
// a Fortek SSR to do it. If you are using an unaltered gCreate machine, this needs
|
||||
// to be set to 0
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -404,8 +417,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -415,7 +426,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -427,7 +437,6 @@
|
|||
#define HEATER_4_MAXTEMP 245
|
||||
#define HEATER_5_MAXTEMP 245
|
||||
#define BED_MAXTEMP 115
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -475,7 +484,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1416,7 +1425,7 @@
|
|||
#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1896,6 +1905,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2053,10 +2068,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G27" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 12
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -462,7 +471,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1416,7 +1425,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1896,6 +1905,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2053,10 +2068,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 5
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -451,7 +460,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1408,7 +1417,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1888,6 +1897,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2045,10 +2060,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 1
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -773,8 +787,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G27" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -962,6 +979,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1010,6 +1033,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 0
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -467,7 +476,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1418,7 +1427,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1898,6 +1907,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2055,10 +2070,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -774,8 +788,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -963,6 +980,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1011,6 +1034,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -302,12 +302,11 @@ monitor_speed = 250000
|
|||
# MKS Robin (STM32F103ZET6)
|
||||
#
|
||||
[env:mks_robin]
|
||||
platform = ststm32@5.1.0
|
||||
platform = ststm32@5.3.0
|
||||
framework = arduino
|
||||
board = genericSTM32F103ZE
|
||||
extra_scripts = buildroot/share/PlatformIO/scripts/mks_robin.py
|
||||
build_flags = !python Marlin/src/HAL/HAL_STM32F1/STM32F1_flag_script.py
|
||||
-DSTM32_XL_DENSITY
|
||||
${common.build_flags}
|
||||
-DSTM32_XL_DENSITY
|
||||
src_filter = ${common.default_src_filter} +<src/HAL/HAL_STM32F1>
|
||||
|
@ -319,6 +318,24 @@ lib_ignore = c1921b4
|
|||
Adafruit NeoPixel
|
||||
libf3e
|
||||
TMC26XStepper
|
||||
U8glib-HAL
|
||||
|
||||
#
|
||||
# STM32F407VET6 with RAMPS-like shield
|
||||
# 'Black' STM32F407VET6 board - http://wiki.stm32duino.com/index.php?title=STM32F407
|
||||
# Shield - https://github.com/jmz52/Hardware
|
||||
#
|
||||
[env:black_stm32f407ve]
|
||||
platform = ststm32
|
||||
framework = arduino
|
||||
board = blackSTM32F407VET6
|
||||
extra_scripts = pre:buildroot/share/PlatformIO/scripts/black_stm32f407vet6.py
|
||||
build_flags = ${common.build_flags}
|
||||
-DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 -DUSB_PRODUCT=\"BLACK_F407VE\"
|
||||
lib_deps = ${common.lib_deps}
|
||||
lib_ignore = Adafruit NeoPixel, c1921b4, TMCStepper, TMC26XStepper, SailfishLCD, SailfishRGB_LED, SlowSoftI2CMaster
|
||||
src_filter = ${common.default_src_filter} +<src/HAL/HAL_STM32>
|
||||
monitor_speed = 250000
|
||||
|
||||
#
|
||||
# Teensy 3.5 / 3.6 (ARM Cortex-M4)
|
||||
|
|
Reference in a new issue