Skip to content

Commit

Permalink
Merge Elegoo Marlin source of v1.1.5.1a from 2023-02-10
Browse files Browse the repository at this point in the history
  • Loading branch information
Stefan Römer committed Mar 19, 2023
2 parents 398cae7 + 85847db commit ca93703
Show file tree
Hide file tree
Showing 44 changed files with 10,440 additions and 334 deletions.
203 changes: 140 additions & 63 deletions Marlin/Configuration.h

Large diffs are not rendered by default.

77 changes: 45 additions & 32 deletions Marlin/Configuration_adv.h
Original file line number Diff line number Diff line change
Expand Up @@ -628,7 +628,7 @@
* 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 -1
//#define E0_AUTO_FAN_PIN -1
#define E1_AUTO_FAN_PIN -1
#define E2_AUTO_FAN_PIN -1
#define E3_AUTO_FAN_PIN -1
Expand Down Expand Up @@ -694,12 +694,12 @@
/**
* M355 Case Light on-off / brightness
*/
//#define CASE_LIGHT_ENABLE
#define CASE_LIGHT_ENABLE
#if ENABLED(CASE_LIGHT_ENABLE)
//#define CASE_LIGHT_PIN 4 // Override the default pin if needed
#define CASE_LIGHT_PIN LED3_PIN // 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 CASE_LIGHT_DEFAULT_ON false // Set default power-up state on
#define CASE_LIGHT_DEFAULT_BRIGHTNESS 255 // Set default power-up brightness (0-255, requires PWM pin)
//#define CASE_LIGHT_NO_BRIGHTNESS // Disable brightness control. Enable for non-PWM lighting.
//#define CASE_LIGHT_MAX_PWM 128 // Limit PWM duty cycle (0-255)
//#define CASE_LIGHT_MENU // Add Case Light options to the LCD menu
Expand Down Expand Up @@ -867,7 +867,7 @@
//#define SENSORLESS_BACKOFF_MM { 2, 2, 0 } // (linear=mm, rotational=°) Backoff from endstops before sensorless homing

#define HOMING_BUMP_MM { 5, 5, 2 } // (linear=mm, rotational=°) Backoff from endstops after first bump
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
#define HOMING_BUMP_DIVISOR { 2, 2, 5 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)

//#define HOMING_BACKOFF_POST_MM { 2, 2, 2 } // (linear=mm, rotational=°) Backoff from endstops after homing

Expand Down Expand Up @@ -1069,16 +1069,20 @@
* The Deactive Time can be overridden with M18 and M84. Set to 0 for No Timeout.
*/
#define DEFAULT_STEPPER_DEACTIVE_TIME 120
#define DISABLE_INACTIVE_X true
#define DISABLE_INACTIVE_Y true
#define DISABLE_INACTIVE_Z true // Set 'false' if the nozzle could fall onto your printed part!
//#define DISABLE_INACTIVE_X true
//#define DISABLE_INACTIVE_Y true
//#define DISABLE_INACTIVE_Z true // Set 'false' if the nozzle could fall onto your printed part!
#define DISABLE_INACTIVE_X false
#define DISABLE_INACTIVE_Y false
#define DISABLE_INACTIVE_Z false
#define DISABLE_INACTIVE_I true
#define DISABLE_INACTIVE_J true
#define DISABLE_INACTIVE_K true
#define DISABLE_INACTIVE_U true
#define DISABLE_INACTIVE_V true
#define DISABLE_INACTIVE_W true
#define DISABLE_INACTIVE_E true
//#define DISABLE_INACTIVE_E true
#define DISABLE_INACTIVE_E false

// Default Minimum Feedrates for printing and travel moves
#define DEFAULT_MINIMUMFEEDRATE 0.0 // (mm/s. °/s for rotational-only moves) Minimum feedrate. Set with M205 S.
Expand Down Expand Up @@ -1479,7 +1483,7 @@

//#define GCODE_REPEAT_MARKERS // Enable G-code M808 to set repeat markers and do looping

#define SD_PROCEDURE_DEPTH 1 // Increase if you need more nested M32 calls
//#define SD_PROCEDURE_DEPTH 1 // Increase if you need more nested M32 calls

#define SD_FINISHED_STEPPERRELEASE true // Disable steppers when SD Print is finished
#define SD_FINISHED_RELEASECOMMAND "M84" // Use "M84XYE" to keep Z enabled so your bed stays in place
Expand All @@ -1499,6 +1503,14 @@

#define EVENT_GCODE_SD_ABORT "G28XY" // G-code to run on SD Abort Print (e.g., "G28XY" or "G27")

#if NEPTUNE_3_PRO
#define EVENT_GCODE_SD_ABORT_2 "G1 F3000 X0 Y230" // G-code to run on SD Abort Print (e.g., "G28XY" or "G27")
#elif NEPTUNE_3_PLUS
#define EVENT_GCODE_SD_ABORT_2 "G1 F3000 X0 Y330" // G-code to run on SD Abort Print (e.g., "G28XY" or "G27")
#elif NEPTUNE_3_MAX
#define EVENT_GCODE_SD_ABORT_2 "G1 F3000 X0 Y430" // G-code to run on SD Abort Print (e.g., "G28XY" or "G27")
#endif

#if ENABLED(PRINTER_EVENT_LEDS)
#define PE_LEDS_COMPLETED_TIME (30*60) // (seconds) Time to keep the LED "done" color before restoring normal illumination
#endif
Expand All @@ -1511,9 +1523,10 @@
* an option on the LCD screen to continue the print from the last-known
* point in the file.
*/
//#define POWER_LOSS_RECOVERY
#define POWER_LOSS_RECOVERY
#if ENABLED(POWER_LOSS_RECOVERY)
#define PLR_ENABLED_DEFAULT false // Power Loss Recovery enabled by default. (Set with 'M413 Sn' & M500)
//#define PLR_ENABLED_DEFAULT false // Power Loss Recovery enabled by default. (Set with 'M413 Sn' & M500)
#define PLR_ENABLED_DEFAULT true // Power Loss Recovery enabled by default. (Set with 'M413 Sn' & M500)
//#define BACKUP_POWER_SUPPLY // Backup power / UPS to move the steppers on power loss
//#define POWER_LOSS_ZRAISE 2 // (mm) Z axis raise on resume (on power loss with UPS)
//#define POWER_LOSS_PIN 44 // Pin to detect power loss. Set to -1 to disable default pin on boards without module.
Expand All @@ -1525,7 +1538,7 @@

// Without a POWER_LOSS_PIN the following option helps reduce wear on the SD card,
// especially with "vase mode" printing. Set too high and vases cannot be continued.
#define POWER_LOSS_MIN_Z_CHANGE 0.05 // (mm) Minimum Z change before saving power-loss data
#define POWER_LOSS_MIN_Z_CHANGE 0.08 // (mm) Minimum Z change before saving power-loss data

// Enable if Z homing is needed for proper recovery. 99.9% of the time this should be disabled!
//#define POWER_LOSS_RECOVER_ZHOME
Expand Down Expand Up @@ -1576,10 +1589,10 @@
// LCD's font must contain the characters. Check your selected LCD language.
//#define UTF_FILENAME_SUPPORT

//#define LONG_FILENAME_HOST_SUPPORT // Get the long filename of a file/folder with 'M33 <dosname>' and list long filenames with 'M20 L'
#define LONG_FILENAME_HOST_SUPPORT // Get the long filename of a file/folder with 'M33 <dosname>' and list long filenames with 'M20 L'
//#define LONG_FILENAME_WRITE_SUPPORT // Create / delete files with long filenames via M28, M30, and Binary Transfer Protocol

//#define SCROLL_LONG_FILENAMES // Scroll long filenames in the SD card menu
#define SCROLL_LONG_FILENAMES // Scroll long filenames in the SD card menu

//#define SD_ABORT_NO_COOLDOWN // Leave the heaters on after Stop Print (not recommended!)

Expand Down Expand Up @@ -2009,18 +2022,18 @@
*
* Warning: Does not respect endstops!
*/
//#define BABYSTEPPING
#define BABYSTEPPING
#if ENABLED(BABYSTEPPING)
//#define INTEGRATED_BABYSTEPPING // EXPERIMENTAL integration of babystepping into the Stepper ISR
//#define BABYSTEP_WITHOUT_HOMING
//#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 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_MILLIMETER_UNITS // Specify BABYSTEP_MULTIPLICATOR_(XY|Z) in mm instead of micro-steps
#define BABYSTEP_MULTIPLICATOR_Z 1 // (steps or mm) Steps or millimeter distance for each Z babystep
#define BABYSTEP_MILLIMETER_UNITS // Specify BABYSTEP_MULTIPLICATOR_(XY|Z) in mm instead of micro-steps
#define BABYSTEP_MULTIPLICATOR_Z 0.1 // (steps or mm) Steps or millimeter distance for each Z babystep
#define BABYSTEP_MULTIPLICATOR_XY 1 // (steps or mm) Steps or millimeter distance for each XY babystep

//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
#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.
Expand All @@ -2032,7 +2045,7 @@

//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28

//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
#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
Expand All @@ -2056,13 +2069,13 @@
*
* See https://marlinfw.org/docs/features/lin_advance.html for full instructions.
*/
//#define LIN_ADVANCE
#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 LIN_ADVANCE_K 0.00 // Unit: mm compression per 1mm/s extruder speed
//#define LA_DEBUG // If enabled, this will generate debug information output over USB.
//#define EXPERIMENTAL_SCURVE // Enable this option to permit S-Curve Acceleration
//#define ALLOW_LOW_EJERK // Allow a DEFAULT_EJERK value of <10. Recommended for direct drive hotends.
#define EXPERIMENTAL_SCURVE // Enable this option to permit S-Curve Acceleration
#define ALLOW_LOW_EJERK // Allow a DEFAULT_EJERK value of <10. Recommended for direct drive hotends.
#endif

// @section leveling
Expand Down Expand Up @@ -2339,7 +2352,7 @@

// The ASCII buffer for serial input
#define MAX_CMD_SIZE 96
#define BUFSIZE 4
#define BUFSIZE 16

// Transmission to Host Buffer Size
// To save 386 bytes of flash (and TX_BUFFER_SIZE+3 bytes of RAM) set to 0.
Expand Down Expand Up @@ -2579,7 +2592,7 @@
*
* Enable PARK_HEAD_ON_PAUSE to add the G-code M125 Pause and Park.
*/
//#define ADVANCED_PAUSE_FEATURE
#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.
Expand All @@ -2599,8 +2612,8 @@
// 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.
#define ADVANCED_PAUSE_PURGE_FEEDRATE 5 // (mm/s) Extrude feedrate (after loading). Should be slower than load feedrate.
#define ADVANCED_PAUSE_PURGE_LENGTH 20 // (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.
Expand Down Expand Up @@ -3923,10 +3936,10 @@
* 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
#define HOST_ACTION_COMMANDS
#if ENABLED(HOST_ACTION_COMMANDS)
//#define HOST_PAUSE_M76 // Tell the host to pause in response to M76
//#define HOST_PROMPT_SUPPORT // Initiate host prompts to get user feedback
#define HOST_PROMPT_SUPPORT // Initiate host prompts to get user feedback
#if ENABLED(HOST_PROMPT_SUPPORT)
//#define HOST_STATUS_NOTIFICATIONS // Send some status messages to the host as notifications
#endif
Expand Down
19 changes: 19 additions & 0 deletions Marlin/src/HAL/AVR/MarlinSerial.h
Original file line number Diff line number Diff line change
Expand Up @@ -290,6 +290,25 @@
extern MSerialLCD lcdSerial;
#endif

#ifdef LCD_SERIAL_PORT_2

template <uint8_t serial>
struct LCDSerialCfg {
static constexpr int PORT = serial;
static constexpr unsigned int RX_SIZE = TERN(HAS_DGUS_LCD, DGUS_RX_BUFFER_SIZE, 64);
static constexpr unsigned int TX_SIZE = TERN(HAS_DGUS_LCD, DGUS_TX_BUFFER_SIZE, 128);
static constexpr bool XONOFF = false;
static constexpr bool EMERGENCYPARSER = ENABLED(EMERGENCY_PARSER);
static constexpr bool DROPPED_RX = false;
static constexpr bool RX_FRAMING_ERRORS = false;
static constexpr bool MAX_RX_QUEUED = false;
static constexpr bool RX_OVERRUNS = BOTH(HAS_DGUS_LCD, SERIAL_STATS_RX_BUFFER_OVERRUNS);
};

typedef Serial1Class< MarlinSerial< LCDSerialCfg<LCD_SERIAL_PORT_2> > > MSerialLCD_2;
extern MSerialLCD_2 lcdSerial_2;
#endif

// Use the UART for Bluetooth in AT90USB configurations
#if defined(USBCON) && ENABLED(BLUETOOTH)
typedef Serial1Class<HardwareSerial> MSerialBT;
Expand Down
9 changes: 8 additions & 1 deletion Marlin/src/HAL/STM32/HAL.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,6 +77,11 @@ void MarlinHAL::init() {
#if PIN_EXISTS(LED)
OUT_WRITE(LED_PIN, LOW);
#endif

// Turn on frame light
#ifdef RTS_AVAILABLE
OUT_WRITE(LED3_PIN, HIGH);
#endif

#if ENABLED(SRAM_EEPROM_EMULATION)
__HAL_RCC_PWR_CLK_ENABLE();
Expand Down Expand Up @@ -145,7 +150,9 @@ void MarlinHAL::clear_reset_source() { __HAL_RCC_CLEAR_RESET_FLAGS(); }
// ------------------------

#if ENABLED(USE_WATCHDOG)

#if ENABLED(RTS_AVAILABLE)
#define WATCHDOG_DURATION_8S
#endif
#define WDT_TIMEOUT_US TERN(WATCHDOG_DURATION_8S, 8000000, 4000000) // 4 or 8 second timeout

#include <IWatchdog.h>
Expand Down
15 changes: 15 additions & 0 deletions Marlin/src/HAL/STM32/HAL.h
Original file line number Diff line number Diff line change
Expand Up @@ -117,6 +117,21 @@
#endif
#endif

#ifdef LCD_SERIAL_PORT_2
#if WITHIN(LCD_SERIAL_PORT_2, 1, 6)
#define LCD_SERIAL_2 MSERIAL(LCD_SERIAL_PORT_2)
#elif !defined(USBCON)
#error "SERIAL_PORT must be from 1 to 6."
#elif LCD_SERIAL_PORT == -1
#define LCD_SERIAL MSerialUSB
#else
#error "LCD_SERIAL_PORT must be from 1 to 6, or -1 for Native USB."
#endif
#if HAS_DGUS_LCD
#define SERIAL2_GET_TX_BUFFER_FREE() LCD_SERIAL_2.availableForWrite()
#endif
#endif

/**
* TODO: review this to return 1 for pins that are not analog input
*/
Expand Down
52 changes: 40 additions & 12 deletions Marlin/src/MarlinCore.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -252,6 +252,10 @@
#include "tests/marlin_tests.h"
#endif

#if ENABLED(RTS_AVAILABLE)
#include "lcd/extui/dgus/elegoo/DGUSDisplayDef.h"
#endif

PGMSTR(M112_KILL_STR, "M112 Shutdown");

MarlinState marlin_state = MF_INITIALIZING;
Expand All @@ -264,14 +268,19 @@ bool wait_for_heatup = true;
bool wait_for_user; // = false;

void wait_for_user_response(millis_t ms/*=0*/, const bool no_sleep/*=false*/) {
UNUSED(no_sleep);
KEEPALIVE_STATE(PAUSED_FOR_USER);
wait_for_user = true;
if (ms) ms += millis(); // expire time
while (wait_for_user && !(ms && ELAPSED(millis(), ms)))
idle(TERN_(ADVANCED_PAUSE_FEATURE, no_sleep));
wait_for_user = false;
while (ui.button_pressed()) safe_delay(50);

#if ENABLED(RTS_AVAILABLE)
wait_for_user = false;
#else
UNUSED(no_sleep);
KEEPALIVE_STATE(PAUSED_FOR_USER);
wait_for_user = true;
if (ms) ms += millis(); // expire time
while (wait_for_user && !(ms && ELAPSED(millis(), ms)))
idle(TERN_(ADVANCED_PAUSE_FEATURE, no_sleep));
wait_for_user = false;
while (ui.button_pressed()) safe_delay(50);
#endif
}

#endif
Expand Down Expand Up @@ -373,11 +382,28 @@ void startOrResumeJob() {

TERN_(POWER_LOSS_RECOVERY, recovery.purge());

#ifdef EVENT_GCODE_SD_ABORT
queue.inject(F(EVENT_GCODE_SD_ABORT));
#if ENABLED(RTS_AVAILABLE)
if(abortSD_flag)
{
do_blocking_move_to_z(current_position.z + 5, 100);
#ifdef EVENT_GCODE_SD_ABORT_2
queue.inject(F(EVENT_GCODE_SD_ABORT_2));
#endif
abortSD_flag = false;
}
else
{
#ifdef EVENT_GCODE_SD_ABORT
queue.inject(F(EVENT_GCODE_SD_ABORT));
#endif
}
queue.enqueue_now_P(PSTR("M84"));
TERN_(PASSWORD_AFTER_SD_PRINT_ABORT, password.lock_machine());
#else
#ifdef EVENT_GCODE_SD_ABORT
queue.inject(F(EVENT_GCODE_SD_ABORT));
#endif
#endif

TERN_(PASSWORD_AFTER_SD_PRINT_ABORT, password.lock_machine());
}

inline void finishSDPrinting() {
Expand Down Expand Up @@ -842,6 +868,8 @@ void idle(bool no_stepper_sleep/*=false*/) {
// Handle UI input / draw events
TERN(DWIN_CREALITY_LCD, DWIN_Update(), ui.update());

TERN_(EXTENSIBLE_UI, ExtUI::onIdle());

// Run i2c Position Encoders
#if ENABLED(I2C_POSITION_ENCODERS)
{
Expand Down
1 change: 1 addition & 0 deletions Marlin/src/core/boards.h
Original file line number Diff line number Diff line change
Expand Up @@ -421,6 +421,7 @@
#define BOARD_ARTILLERY_RUBY 4238 // Artillery Ruby (STM32F401RC)
#define BOARD_FYSETC_SPIDER_V2_2 4239 // FYSETC Spider V2.2 (STM32F446VE)
#define BOARD_CREALITY_V24S1_301F4 4240 // Creality v2.4.S1_301F4 (STM32F401RC) as found in the Ender-3 S1 F4
#define BOARD_MKS_E3D_V2 4241 // MKS Robin E3D (STM32F401RCT6)

//
// ARM Cortex M7
Expand Down
Loading

0 comments on commit ca93703

Please sign in to comment.