Merge latest patches

This commit is contained in:
Scott Lahteine 2020-03-31 14:43:42 -05:00
commit 0f9a14dfda
137 changed files with 1947 additions and 1150 deletions

View File

@ -473,7 +473,7 @@
#if ENABLED(PIDTEMP) #if ENABLED(PIDTEMP)
//#define PID_EDIT_MENU // Add PID editing to the "Advanced Settings" menu. (~700 bytes of PROGMEM) //#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_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_DEBUG // Sends debug data to the serial port. Use 'M303 D' to toggle activation.
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX //#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 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) //#define PID_PARAMS_PER_HOTEND // Uses separate PID parameters for each extruder (useful for mismatched extruders)

View File

@ -1049,6 +1049,10 @@
#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27") #define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
#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
/** /**
* Continue after Power-Loss (Creality3D) * Continue after Power-Loss (Creality3D)
* *

View File

@ -25,7 +25,7 @@
#if EITHER(EEPROM_SETTINGS, SD_FIRMWARE_UPDATE) #if EITHER(EEPROM_SETTINGS, SD_FIRMWARE_UPDATE)
#include "../shared/persistent_store_api.h" #include "../shared/eeprom_api.h"
bool PersistentStore::access_start() { return true; } bool PersistentStore::access_start() { return true; }
bool PersistentStore::access_finish() { return true; } bool PersistentStore::access_finish() { return true; }

View File

@ -98,9 +98,9 @@
#define SET_INPUT(IO) _SET_INPUT(IO) #define SET_INPUT(IO) _SET_INPUT(IO)
#define SET_INPUT_PULLUP(IO) do{ _SET_INPUT(IO); _WRITE(IO, HIGH); }while(0) #define SET_INPUT_PULLUP(IO) do{ _SET_INPUT(IO); _WRITE(IO, HIGH); }while(0)
#define SET_INPUT_PULLDOWN SET_INPUT
#define SET_OUTPUT(IO) _SET_OUTPUT(IO) #define SET_OUTPUT(IO) _SET_OUTPUT(IO)
#define SET_PWM SET_OUTPUT
#define SET_PWM(IO) SET_OUTPUT(IO)
#define IS_INPUT(IO) _IS_INPUT(IO) #define IS_INPUT(IO) _IS_INPUT(IO)
#define IS_OUTPUT(IO) _IS_OUTPUT(IO) #define IS_OUTPUT(IO) _IS_OUTPUT(IO)

View File

@ -57,7 +57,7 @@
#if ENABLED(FLASH_EEPROM_EMULATION) #if ENABLED(FLASH_EEPROM_EMULATION)
#include "../shared/Marduino.h" #include "../shared/Marduino.h"
#include "../shared/persistent_store_api.h" #include "../shared/eeprom_api.h"
#define EEPROMSize 4096 #define EEPROMSize 4096
#define PagesPerGroup 128 #define PagesPerGroup 128

View File

@ -27,7 +27,7 @@
#if ENABLED(EEPROM_SETTINGS) #if ENABLED(EEPROM_SETTINGS)
#include "../../inc/MarlinConfig.h" #include "../../inc/MarlinConfig.h"
#include "../shared/persistent_store_api.h" #include "../shared/eeprom_api.h"
#if !defined(E2END) && ENABLED(FLASH_EEPROM_EMULATION) #if !defined(E2END) && ENABLED(FLASH_EEPROM_EMULATION)
#define E2END 0xFFF // Default to Flash emulated EEPROM size (EepromEmulation_Due.cpp) #define E2END 0xFFF // Default to Flash emulated EEPROM size (EepromEmulation_Due.cpp)

View File

@ -166,7 +166,7 @@
// Set pin as output (wrapper) - reads the pin and sets the output to that value // Set pin as output (wrapper) - reads the pin and sets the output to that value
#define SET_OUTPUT(IO) _SET_OUTPUT(IO) #define SET_OUTPUT(IO) _SET_OUTPUT(IO)
// Set pin as PWM // Set pin as PWM
#define SET_PWM(IO) SET_OUTPUT(IO) #define SET_PWM SET_OUTPUT
// Check if pin is an input // Check if pin is an input
#define IS_INPUT(IO) ((digitalPinToPort(IO)->PIO_OSR & digitalPinToBitMask(IO)) == 0) #define IS_INPUT(IO) ((digitalPinToPort(IO)->PIO_OSR & digitalPinToBitMask(IO)) == 0)

View File

@ -46,6 +46,31 @@
#include "G2_PWM.h" #include "G2_PWM.h"
#if PIN_EXISTS(MOTOR_CURRENT_PWM_X)
#define G2_PWM_X 1
#else
#define G2_PWM_X 0
#endif
#if PIN_EXISTS(MOTOR_CURRENT_PWM_Y)
#define G2_PWM_Y 1
#else
#define G2_PWM_Y 0
#endif
#if PIN_EXISTS(MOTOR_CURRENT_PWM_Z)
#define G2_PWM_Z 1
#else
#define G2_PWM_Z 0
#endif
#if PIN_EXISTS(MOTOR_CURRENT_PWM_E)
#define G2_PWM_E 1
#else
#define G2_PWM_E 0
#endif
#define G2_MASK_X(V) (G2_PWM_X * (V))
#define G2_MASK_Y(V) (G2_PWM_Y * (V))
#define G2_MASK_Z(V) (G2_PWM_Z * (V))
#define G2_MASK_E(V) (G2_PWM_E * (V))
volatile uint32_t *SODR_A = &PIOA->PIO_SODR, volatile uint32_t *SODR_A = &PIOA->PIO_SODR,
*SODR_B = &PIOB->PIO_SODR, *SODR_B = &PIOB->PIO_SODR,
*CODR_A = &PIOA->PIO_CODR, *CODR_A = &PIOA->PIO_CODR,
@ -55,10 +80,18 @@ PWM_map ISR_table[NUM_PWMS] = PWM_MAP_INIT;
void Stepper::digipot_init() { void Stepper::digipot_init() {
OUT_WRITE(MOTOR_CURRENT_PWM_X_PIN, 0); // init pins #if PIN_EXISTS(MOTOR_CURRENT_PWM_X)
OUT_WRITE(MOTOR_CURRENT_PWM_Y_PIN, 0); OUT_WRITE(MOTOR_CURRENT_PWM_X_PIN, 0); // init pins
OUT_WRITE(MOTOR_CURRENT_PWM_Z_PIN, 0); #endif
OUT_WRITE(MOTOR_CURRENT_PWM_E_PIN, 0); #if PIN_EXISTS(MOTOR_CURRENT_PWM_Y)
OUT_WRITE(MOTOR_CURRENT_PWM_Y_PIN, 0);
#endif
#if G2_PWM_Z
OUT_WRITE(MOTOR_CURRENT_PWM_Z_PIN, 0);
#endif
#if G2_PWM_E
OUT_WRITE(MOTOR_CURRENT_PWM_E_PIN, 0);
#endif
#define WPKEY (0x50574D << 8) // “PWM” in ASCII #define WPKEY (0x50574D << 8) // “PWM” in ASCII
#define WPCMD_DIS_SW 0 // command to disable Write Protect SW #define WPCMD_DIS_SW 0 // command to disable Write Protect SW
@ -71,30 +104,51 @@ void Stepper::digipot_init() {
PWM->PWM_WPCR = WPKEY | WPRG_ALL | WPCMD_DIS_SW; // enable setting of all PWM registers PWM->PWM_WPCR = WPKEY | WPRG_ALL | WPCMD_DIS_SW; // enable setting of all PWM registers
PWM->PWM_CLK = PWM_CLOCK_F; // enable CLK_A and set it to 1MHz, leave CLK_B disabled PWM->PWM_CLK = PWM_CLOCK_F; // enable CLK_A and set it to 1MHz, leave CLK_B disabled
PWM->PWM_CH_NUM[0].PWM_CMR = 0b1011; // set channel 0 to Clock A input & to left aligned PWM->PWM_CH_NUM[0].PWM_CMR = 0b1011; // set channel 0 to Clock A input & to left aligned
PWM->PWM_CH_NUM[1].PWM_CMR = 0b1011; // set channel 1 to Clock A input & to left aligned if (G2_PWM_X) PWM->PWM_CH_NUM[1].PWM_CMR = 0b1011; // set channel 1 to Clock A input & to left aligned
PWM->PWM_CH_NUM[2].PWM_CMR = 0b1011; // set channel 2 to Clock A input & to left aligned if (G2_PWM_Y) PWM->PWM_CH_NUM[2].PWM_CMR = 0b1011; // set channel 2 to Clock A input & to left aligned
PWM->PWM_CH_NUM[3].PWM_CMR = 0b1011; // set channel 3 to Clock A input & to left aligned if (G2_PWM_Z) PWM->PWM_CH_NUM[3].PWM_CMR = 0b1011; // set channel 3 to Clock A input & to left aligned
PWM->PWM_CH_NUM[4].PWM_CMR = 0b1011; // set channel 4 to Clock A input & to left aligned if (G2_PWM_E) PWM->PWM_CH_NUM[4].PWM_CMR = 0b1011; // set channel 4 to Clock A input & to left aligned
PWM->PWM_CH_NUM[0].PWM_CPRD = PWM_PERIOD_US; // set channel 0 Period PWM->PWM_CH_NUM[0].PWM_CPRD = PWM_PERIOD_US; // set channel 0 Period
PWM->PWM_IER2 = PWM_IER1_CHID0; // generate interrupt when counter0 overflows PWM->PWM_IER2 = PWM_IER1_CHID0; // generate interrupt when counter0 overflows
PWM->PWM_IER2 = PWM_IER2_CMPM0 | PWM_IER2_CMPM1 | PWM_IER2_CMPM2 | PWM_IER2_CMPM3 | PWM_IER2_CMPM4; // generate interrupt on compare event PWM->PWM_IER2 = PWM_IER2_CMPM0
| G2_MASK_X(PWM_IER2_CMPM1)
| G2_MASK_Y(PWM_IER2_CMPM2)
| G2_MASK_Z(PWM_IER2_CMPM3)
| G2_MASK_E(PWM_IER2_CMPM4)
; // generate interrupt on compare event
PWM->PWM_CMP[1].PWM_CMPV = 0x010000000LL | G2_VREF_COUNT(G2_VREF(motor_current_setting[0])); // interrupt when counter0 == CMPV - used to set Motor 1 PWM inactive if (G2_PWM_X) PWM->PWM_CMP[1].PWM_CMPV = 0x010000000LL | G2_VREF_COUNT(G2_VREF(motor_current_setting[0])); // interrupt when counter0 == CMPV - used to set Motor 1 PWM inactive
PWM->PWM_CMP[2].PWM_CMPV = 0x010000000LL | G2_VREF_COUNT(G2_VREF(motor_current_setting[0])); // interrupt when counter0 == CMPV - used to set Motor 2 PWM inactive if (G2_PWM_Y) PWM->PWM_CMP[2].PWM_CMPV = 0x010000000LL | G2_VREF_COUNT(G2_VREF(motor_current_setting[0])); // interrupt when counter0 == CMPV - used to set Motor 2 PWM inactive
PWM->PWM_CMP[3].PWM_CMPV = 0x010000000LL | G2_VREF_COUNT(G2_VREF(motor_current_setting[1])); // interrupt when counter0 == CMPV - used to set Motor 3 PWM inactive if (G2_PWM_Z) PWM->PWM_CMP[3].PWM_CMPV = 0x010000000LL | G2_VREF_COUNT(G2_VREF(motor_current_setting[1])); // interrupt when counter0 == CMPV - used to set Motor 3 PWM inactive
PWM->PWM_CMP[4].PWM_CMPV = 0x010000000LL | G2_VREF_COUNT(G2_VREF(motor_current_setting[2])); // interrupt when counter0 == CMPV - used to set Motor 4 PWM inactive if (G2_PWM_E) PWM->PWM_CMP[4].PWM_CMPV = 0x010000000LL | G2_VREF_COUNT(G2_VREF(motor_current_setting[2])); // interrupt when counter0 == CMPV - used to set Motor 4 PWM inactive
PWM->PWM_CMP[1].PWM_CMPM = 0x0001; // enable compare event if (G2_PWM_X) PWM->PWM_CMP[1].PWM_CMPM = 0x0001; // enable compare event
PWM->PWM_CMP[2].PWM_CMPM = 0x0001; // enable compare event if (G2_PWM_Y) PWM->PWM_CMP[2].PWM_CMPM = 0x0001; // enable compare event
PWM->PWM_CMP[3].PWM_CMPM = 0x0001; // enable compare event if (G2_PWM_Z) PWM->PWM_CMP[3].PWM_CMPM = 0x0001; // enable compare event
PWM->PWM_CMP[4].PWM_CMPM = 0x0001; // enable compare event if (G2_PWM_E) PWM->PWM_CMP[4].PWM_CMPM = 0x0001; // enable compare event
PWM->PWM_SCM = PWM_SCM_UPDM_MODE0 | PWM_SCM_SYNC0 | PWM_SCM_SYNC1 | PWM_SCM_SYNC2 | PWM_SCM_SYNC3 | PWM_SCM_SYNC4; // sync 1-4 with 0, use mode 0 for updates PWM->PWM_SCM = PWM_SCM_UPDM_MODE0 | PWM_SCM_SYNC0
| G2_MASK_X(PWM_SCM_SYNC1)
| G2_MASK_Y(PWM_SCM_SYNC2)
| G2_MASK_Z(PWM_SCM_SYNC3)
| G2_MASK_E(PWM_SCM_SYNC4)
; // sync 1-4 with 0, use mode 0 for updates
PWM->PWM_ENA = PWM_ENA_CHID0 | PWM_ENA_CHID1 | PWM_ENA_CHID2 | PWM_ENA_CHID3 | PWM_ENA_CHID4; // enable the channels used by G2 PWM->PWM_ENA = PWM_ENA_CHID0
PWM->PWM_IER1 = PWM_IER1_CHID0 | PWM_IER1_CHID1 | PWM_IER1_CHID2 | PWM_IER1_CHID3 | PWM_IER1_CHID4; // enable interrupts for the channels used by G2 | G2_MASK_X(PWM_ENA_CHID1)
| G2_MASK_Y(PWM_ENA_CHID2)
| G2_MASK_Z(PWM_ENA_CHID3)
| G2_MASK_E(PWM_ENA_CHID4)
; // enable channels used by G2
PWM->PWM_IER1 = PWM_IER1_CHID0
| G2_MASK_X(PWM_IER1_CHID1)
| G2_MASK_Y(PWM_IER1_CHID2)
| G2_MASK_Z(PWM_IER1_CHID3)
| G2_MASK_E(PWM_IER1_CHID4)
; // enable interrupts for channels used by G2
NVIC_EnableIRQ(PWM_IRQn); // Enable interrupt handler NVIC_EnableIRQ(PWM_IRQn); // Enable interrupt handler
NVIC_SetPriority(PWM_IRQn, NVIC_EncodePriority(0, 10, 0)); // normal priority for PWM module (can stand some jitter on the Vref signals) NVIC_SetPriority(PWM_IRQn, NVIC_EncodePriority(0, 10, 0)); // normal priority for PWM module (can stand some jitter on the Vref signals)
@ -105,20 +159,27 @@ void Stepper::digipot_current(const uint8_t driver, const int16_t current) {
if (!(PWM->PWM_CH_NUM[0].PWM_CPRD == PWM_PERIOD_US)) digipot_init(); // Init PWM system if needed if (!(PWM->PWM_CH_NUM[0].PWM_CPRD == PWM_PERIOD_US)) digipot_init(); // Init PWM system if needed
switch (driver) { switch (driver) {
case 0: PWM->PWM_CMP[1].PWM_CMPVUPD = 0x010000000LL | G2_VREF_COUNT(G2_VREF(current)); // update X & Y case 0:
PWM->PWM_CMP[2].PWM_CMPVUPD = 0x010000000LL | G2_VREF_COUNT(G2_VREF(current)); if (G2_PWM_X) PWM->PWM_CMP[1].PWM_CMPVUPD = 0x010000000LL | G2_VREF_COUNT(G2_VREF(current)); // update X & Y
PWM->PWM_CMP[1].PWM_CMPMUPD = 0x0001; // enable compare event if (G2_PWM_Y) PWM->PWM_CMP[2].PWM_CMPVUPD = 0x010000000LL | G2_VREF_COUNT(G2_VREF(current));
PWM->PWM_CMP[2].PWM_CMPMUPD = 0x0001; // enable compare event if (G2_PWM_X) PWM->PWM_CMP[1].PWM_CMPMUPD = 0x0001; // enable compare event
PWM->PWM_SCUC = PWM_SCUC_UPDULOCK; // tell the PWM controller to update the values on the next cycle if (G2_PWM_Y) PWM->PWM_CMP[2].PWM_CMPMUPD = 0x0001; // enable compare event
break; if (G2_PWM_X || G2_PWM_Y) PWM->PWM_SCUC = PWM_SCUC_UPDULOCK; // tell the PWM controller to update the values on the next cycle
case 1: PWM->PWM_CMP[3].PWM_CMPVUPD = 0x010000000LL | G2_VREF_COUNT(G2_VREF(current)); // update Z break;
PWM->PWM_CMP[3].PWM_CMPMUPD = 0x0001; // enable compare event case 1:
PWM->PWM_SCUC = PWM_SCUC_UPDULOCK; // tell the PWM controller to update the values on the next cycle if (G2_PWM_Z) {
break; PWM->PWM_CMP[3].PWM_CMPVUPD = 0x010000000LL | G2_VREF_COUNT(G2_VREF(current)); // update Z
default:PWM->PWM_CMP[4].PWM_CMPVUPD = 0x010000000LL | G2_VREF_COUNT(G2_VREF(current)); // update E PWM->PWM_CMP[3].PWM_CMPMUPD = 0x0001; // enable compare event
PWM->PWM_CMP[4].PWM_CMPMUPD = 0x0001; // enable compare event PWM->PWM_SCUC = PWM_SCUC_UPDULOCK; // tell the PWM controller to update the values on the next cycle
PWM->PWM_SCUC = PWM_SCUC_UPDULOCK; // tell the PWM controller to update the values on the next cycle }
break; break;
default:
if (G2_PWM_E) {
PWM->PWM_CMP[4].PWM_CMPVUPD = 0x010000000LL | G2_VREF_COUNT(G2_VREF(current)); // update E
PWM->PWM_CMP[4].PWM_CMPMUPD = 0x0001; // enable compare event
PWM->PWM_SCUC = PWM_SCUC_UPDULOCK; // tell the PWM controller to update the values on the next cycle
}
break;
} }
} }
@ -127,17 +188,17 @@ volatile uint32_t PWM_ISR1_STATUS, PWM_ISR2_STATUS;
void PWM_Handler() { void PWM_Handler() {
PWM_ISR1_STATUS = PWM->PWM_ISR1; PWM_ISR1_STATUS = PWM->PWM_ISR1;
PWM_ISR2_STATUS = PWM->PWM_ISR2; PWM_ISR2_STATUS = PWM->PWM_ISR2;
if (PWM_ISR1_STATUS & PWM_IER1_CHID0) { // CHAN_0 interrupt if (PWM_ISR1_STATUS & PWM_IER1_CHID0) { // CHAN_0 interrupt
*ISR_table[0].set_register = ISR_table[0].write_mask; // set X to active if (G2_PWM_X) *ISR_table[0].set_register = ISR_table[0].write_mask; // set X to active
*ISR_table[1].set_register = ISR_table[1].write_mask; // set Y to active if (G2_PWM_Y) *ISR_table[1].set_register = ISR_table[1].write_mask; // set Y to active
*ISR_table[2].set_register = ISR_table[2].write_mask; // set Z to active if (G2_PWM_Z) *ISR_table[2].set_register = ISR_table[2].write_mask; // set Z to active
*ISR_table[3].set_register = ISR_table[3].write_mask; // set E to active if (G2_PWM_E) *ISR_table[3].set_register = ISR_table[3].write_mask; // set E to active
} }
else { else {
if (PWM_ISR2_STATUS & PWM_IER2_CMPM1) *ISR_table[0].clr_register = ISR_table[0].write_mask; // set X to inactive if (G2_PWM_X && (PWM_ISR2_STATUS & PWM_IER2_CMPM1)) *ISR_table[0].clr_register = ISR_table[0].write_mask; // set X to inactive
if (PWM_ISR2_STATUS & PWM_IER2_CMPM2) *ISR_table[1].clr_register = ISR_table[1].write_mask; // set Y to inactive if (G2_PWM_Y && (PWM_ISR2_STATUS & PWM_IER2_CMPM2)) *ISR_table[1].clr_register = ISR_table[1].write_mask; // set Y to inactive
if (PWM_ISR2_STATUS & PWM_IER2_CMPM3) *ISR_table[2].clr_register = ISR_table[2].write_mask; // set Z to inactive if (G2_PWM_Z && (PWM_ISR2_STATUS & PWM_IER2_CMPM3)) *ISR_table[2].clr_register = ISR_table[2].write_mask; // set Z to inactive
if (PWM_ISR2_STATUS & PWM_IER2_CMPM4) *ISR_table[3].clr_register = ISR_table[3].write_mask; // set E to inactive if (G2_PWM_E && (PWM_ISR2_STATUS & PWM_IER2_CMPM4)) *ISR_table[3].clr_register = ISR_table[3].write_mask; // set E to inactive
} }
return; return;
} }

View File

@ -21,7 +21,7 @@
*/ */
#pragma once #pragma once
#if USE_EMULATED_EEPROM #if USE_FALLBACK_EEPROM
#undef SRAM_EEPROM_EMULATION #undef SRAM_EEPROM_EMULATION
#undef SDCARD_EEPROM_EMULATION #undef SDCARD_EEPROM_EMULATION
#define FLASH_EEPROM_EMULATION #define FLASH_EEPROM_EMULATION

View File

@ -26,7 +26,7 @@
#if ENABLED(EEPROM_SETTINGS) && DISABLED(FLASH_EEPROM_EMULATION) #if ENABLED(EEPROM_SETTINGS) && DISABLED(FLASH_EEPROM_EMULATION)
#include "../shared/persistent_store_api.h" #include "../shared/eeprom_api.h"
#include "EEPROM.h" #include "EEPROM.h"
#define EEPROM_SIZE 4096 #define EEPROM_SIZE 4096

View File

@ -56,7 +56,7 @@
#define SET_OUTPUT(IO) do{ _SET_OUTPUT(IO); }while(0) #define SET_OUTPUT(IO) do{ _SET_OUTPUT(IO); }while(0)
// Set pin as PWM // Set pin as PWM
#define SET_PWM(IO) SET_OUTPUT(IO) #define SET_PWM SET_OUTPUT
// Set pin as output and init // Set pin as output and init
#define OUT_WRITE(IO,V) do{ _SET_OUTPUT(IO); WRITE(IO,V); }while(0) #define OUT_WRITE(IO,V) do{ _SET_OUTPUT(IO); WRITE(IO,V); }while(0)

View File

@ -22,6 +22,6 @@
#pragma once #pragma once
// If no real EEPROM, Flash emulation, or SRAM emulation is available fall back to SD emulation // If no real EEPROM, Flash emulation, or SRAM emulation is available fall back to SD emulation
#if ENABLED(EEPROM_SETTINGS) && NONE(USE_REAL_EEPROM, FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION) #if ENABLED(EEPROM_SETTINGS) && NONE(USE_WIRED_EEPROM, FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION)
#define SDCARD_EEPROM_EMULATION #define SDCARD_EEPROM_EMULATION
#endif #endif

View File

@ -26,7 +26,7 @@
#if ENABLED(EEPROM_SETTINGS) #if ENABLED(EEPROM_SETTINGS)
#include "../shared/persistent_store_api.h" #include "../shared/eeprom_api.h"
#include <stdio.h> #include <stdio.h>
#define LINUX_EEPROM_SIZE (E2END + 1) #define LINUX_EEPROM_SIZE (E2END + 1)

View File

@ -21,6 +21,6 @@
*/ */
#pragma once #pragma once
#include "../shared/persistent_store_api.h" #include "../shared/eeprom_api.h"
#define FLASH_EEPROM_EMULATION #define FLASH_EEPROM_EMULATION

View File

@ -40,7 +40,7 @@
#if ENABLED(FLASH_EEPROM_EMULATION) #if ENABLED(FLASH_EEPROM_EMULATION)
#include "persistent_store_api.h" #include "eeprom_api.h"
extern "C" { extern "C" {
#include <lpc17xx_iap.h> #include <lpc17xx_iap.h>

View File

@ -26,7 +26,7 @@
#if ENABLED(SDCARD_EEPROM_EMULATION) #if ENABLED(SDCARD_EEPROM_EMULATION)
#include "persistent_store_api.h" #include "eeprom_api.h"
#include <chanfs/diskio.h> #include <chanfs/diskio.h>
#include <chanfs/ff.h> #include <chanfs/ff.h>

View File

@ -104,7 +104,7 @@
/// set pin as output wrapper - reads the pin and sets the output to that value /// set pin as output wrapper - reads the pin and sets the output to that value
#define SET_OUTPUT(IO) do{ _WRITE(IO, _READ(IO)); _SET_OUTPUT(IO); }while(0) #define SET_OUTPUT(IO) do{ _WRITE(IO, _READ(IO)); _SET_OUTPUT(IO); }while(0)
// set pin as PWM // set pin as PWM
#define SET_PWM(IO) SET_OUTPUT(IO) #define SET_PWM SET_OUTPUT
/// check if pin is an input wrapper /// check if pin is an input wrapper
#define IS_INPUT(IO) _IS_INPUT(IO) #define IS_INPUT(IO) _IS_INPUT(IO)

View File

@ -21,6 +21,6 @@
*/ */
#pragma once #pragma once
#if USE_EMULATED_EEPROM && NONE(SDCARD_EEPROM_EMULATION, SRAM_EEPROM_EMULATION) #if USE_FALLBACK_EEPROM && NONE(SDCARD_EEPROM_EMULATION, SRAM_EEPROM_EMULATION)
#define FLASH_EEPROM_EMULATION #define FLASH_EEPROM_EMULATION
#endif #endif

View File

@ -90,7 +90,7 @@ void HAL_init() {
//debug_frmwrk_init(); //debug_frmwrk_init();
//_DBG("\n\nDebug running\n"); //_DBG("\n\nDebug running\n");
// Initialise the SD card chip select pins as soon as possible // Initialize the SD card chip select pins as soon as possible
#if PIN_EXISTS(SS) #if PIN_EXISTS(SS)
OUT_WRITE(SS_PIN, HIGH); OUT_WRITE(SS_PIN, HIGH);
#endif #endif

View File

@ -0,0 +1,78 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#include "../../inc/MarlinConfig.h"
#if ENABLED(QSPI_EEPROM)
#include "QSPIFlash.h"
#define INVALID_ADDR 0xffffffff
#define SECTOR_OF(a) (a & ~(SFLASH_SECTOR_SIZE - 1))
#define OFFSET_OF(a) (a & (SFLASH_SECTOR_SIZE - 1))
Adafruit_SPIFlashBase * QSPIFlash::_flashBase = nullptr;
uint8_t QSPIFlash::_buf[SFLASH_SECTOR_SIZE];
uint32_t QSPIFlash::_addr = INVALID_ADDR;
void QSPIFlash::begin() {
if (_flashBase != nullptr) return;
_flashBase = new Adafruit_SPIFlashBase(new Adafruit_FlashTransport_QSPI());
_flashBase->begin(NULL);
}
size_t QSPIFlash::size() {
return _flashBase->size();
}
uint8_t QSPIFlash::readByte(const uint32_t address) {
if (SECTOR_OF(address) == _addr) return _buf[OFFSET_OF(address)];
return _flashBase->read8(address);
}
void QSPIFlash::writeByte(const uint32_t address, const uint8_t value) {
uint32_t const sector_addr = SECTOR_OF(address);
// Page changes, flush old and update new cache
if (sector_addr != _addr) {
flush();
_addr = sector_addr;
// read a whole page from flash
_flashBase->readBuffer(sector_addr, _buf, SFLASH_SECTOR_SIZE);
}
_buf[OFFSET_OF(address)] = value;
}
void QSPIFlash::flush() {
if (_addr == INVALID_ADDR) return;
_flashBase->eraseSector(_addr / SFLASH_SECTOR_SIZE);
_flashBase->writeBuffer(_addr, _buf, SFLASH_SECTOR_SIZE);
_addr = INVALID_ADDR;
}
#endif // QSPI_EEPROM

View File

@ -0,0 +1,51 @@
/**
* @file QSPIFlash.h
*
* The MIT License (MIT)
*
* Copyright (c) 2019 Ha Thach and Dean Miller for Adafruit Industries LLC
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*
* Derived from Adafruit_SPIFlash class with no SdFat references
*
*/
#pragma once
#include "Adafruit_SPIFlashBase.h"
// This class extends Adafruit_SPIFlashBase by adding caching support.
//
// This class will use 4096 Bytes of RAM as a block cache.
class QSPIFlash {
public:
static void begin();
static size_t size();
static uint8_t readByte(const uint32_t address);
static void writeByte(const uint32_t address, const uint8_t v);
static void flush();
private:
static Adafruit_SPIFlashBase * _flashBase;
static uint8_t _buf[SFLASH_SECTOR_SIZE];
static uint32_t _addr;
};
extern QSPIFlash qspi;

View File

@ -0,0 +1,66 @@
/**
* Marlin 3D Printer Firmware
*
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
*
* 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 __SAMD51__
#include "../../inc/MarlinConfig.h"
#if ENABLED(EEPROM_SETTINGS) && NONE(QSPI_EEPROM, FLASH_EEPROM_EMULATION)
#include "../shared/eeprom_api.h"
size_t PersistentStore::capacity() { return E2END + 1; }
bool PersistentStore::access_start() { return true; }
bool PersistentStore::access_finish() { return true; }
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
while (size--) {
const uint8_t v = *value;
uint8_t * const p = (uint8_t * const)pos;
if (v != eeprom_read_byte(p)) {
eeprom_write_byte(p, v);
delay(2);
if (eeprom_read_byte(p) != v) {
SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE);
return true;
}
}
crc16(crc, &v, 1);
pos++;
value++;
}
return false;
}
bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
while (size--) {
uint8_t c = eeprom_read_byte((uint8_t*)pos);
if (writing) *value = c;
crc16(crc, &c, 1);
pos++;
value++;
}
return false;
}
#endif // EEPROM_SETTINGS && !(QSPI_EEPROM || FLASH_EEPROM_EMULATION)
#endif // __SAMD51__

View File

@ -0,0 +1,96 @@
/**
* Marlin 3D Printer Firmware
*
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
*
* 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 __SAMD51__
#include "../../inc/MarlinConfig.h"
#if ENABLED(FLASH_EEPROM_EMULATION)
#include "../shared/eeprom_api.h"
#define NVMCTRL_CMD(c) do{ \
SYNC(!NVMCTRL->STATUS.bit.READY); \
NVMCTRL->INTFLAG.bit.DONE = true; \
NVMCTRL->CTRLB.reg = c | NVMCTRL_CTRLB_CMDEX_KEY; \
SYNC(NVMCTRL->INTFLAG.bit.DONE); \
}while(0)
#define NVMCTRL_FLUSH() do{ \
if (NVMCTRL->SEESTAT.bit.LOAD) \
NVMCTRL_CMD(NVMCTRL_CTRLB_CMD_SEEFLUSH); \
}while(0)
size_t PersistentStore::capacity() {
const uint8_t psz = NVMCTRL->SEESTAT.bit.PSZ,
sblk = NVMCTRL->SEESTAT.bit.SBLK;
return (!psz && !sblk) ? 0
: (psz <= 2) ? (0x200 << psz)
: (sblk == 1 || psz == 3) ? 4096
: (sblk == 2 || psz == 4) ? 8192
: (sblk <= 4 || psz == 5) ? 16384
: (sblk >= 9 && psz == 7) ? 65536
: 32768;
}
bool PersistentStore::access_start() {
NVMCTRL->SEECFG.reg = NVMCTRL_SEECFG_WMODE_BUFFERED; // Buffered mode and segment reallocation active
if (NVMCTRL->SEESTAT.bit.RLOCK)
NVMCTRL_CMD(NVMCTRL_CTRLB_CMD_USEE); // Unlock E2P data write access
return true;
}
bool PersistentStore::access_finish() {
NVMCTRL_FLUSH();
if (!NVMCTRL->SEESTAT.bit.LOCK)
NVMCTRL_CMD(NVMCTRL_CTRLB_CMD_LSEE); // Lock E2P data write access
return true;
}
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
while (size--) {
const uint8_t v = *value;
SYNC(NVMCTRL->SEESTAT.bit.BUSY);
if (NVMCTRL->INTFLAG.bit.SEESFULL)
NVMCTRL_FLUSH(); // Next write will trigger a sector reallocation. I need to flush 'pagebuffer'
((volatile uint8_t *)SEEPROM_ADDR)[pos] = v;
SYNC(!NVMCTRL->INTFLAG.bit.SEEWRC);
crc16(crc, &v, 1);
pos++;
value++;
}
return false;
}
bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
while (size--) {
SYNC(NVMCTRL->SEESTAT.bit.BUSY);
uint8_t c = ((volatile uint8_t *)SEEPROM_ADDR)[pos];
if (writing) *value = c;
crc16(crc, &c, 1);
pos++;
value++;
}
return false;
}
#endif // FLASH_EEPROM_EMULATION
#endif // __SAMD51__

View File

@ -0,0 +1,71 @@
/**
* Marlin 3D Printer Firmware
*
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
*
* 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 __SAMD51__
#include "../../inc/MarlinConfig.h"
#if ENABLED(QSPI_EEPROM)
#include "../shared/eeprom_api.h"
#include "QSPIFlash.h"
static bool initialized;
size_t PersistentStore::capacity() { return qspi.size(); }
bool PersistentStore::access_start() {
if (!initialized) {
qspi.begin();
initialized = true;
}
return true;
}
bool PersistentStore::access_finish() {
qspi.flush();
return true;
}
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
while (size--) {
const uint8_t v = *value;
qspi.writeByte(pos, v);
crc16(crc, &v, 1);
pos++;
value++;
}
return false;
}
bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
while (size--) {
uint8_t c = qspi.readByte(pos);
if (writing) *value = c;
crc16(crc, &c, 1);
pos++;
value++;
}
return false;
}
#endif // QSPI_EEPROM
#endif // __SAMD51__

View File

@ -100,9 +100,9 @@
PORT->Group[port].DIRCLR.reg = MASK(pin); \ PORT->Group[port].DIRCLR.reg = MASK(pin); \
}while(0) }while(0)
// Set pin as PWM (push pull) // Set pin as PWM (push pull)
#define SET_PWM(IO) SET_OUTPUT(IO) #define SET_PWM SET_OUTPUT
// Set pin as PWM (open drain) // Set pin as PWM (open drain)
#define SET_PWM_OD(IO) SET_OUTPUT_OD(IO) #define SET_PWM_OD SET_OUTPUT_OD
// check if pin is an output // check if pin is an output
#define IS_OUTPUT(IO) ((PORT->Group[(EPortType)GET_SAMD_PORT(IO)].DIR.reg & MASK(GET_SAMD_PIN(IO))) \ #define IS_OUTPUT(IO) ((PORT->Group[(EPortType)GET_SAMD_PORT(IO)].DIR.reg & MASK(GET_SAMD_PIN(IO))) \

View File

@ -21,8 +21,6 @@
*/ */
#pragma once #pragma once
#if USE_EMULATED_EEPROM #if USE_FALLBACK_EEPROM && NONE(SDCARD_EEPROM_EMULATION, SRAM_EEPROM_EMULATION)
#undef SRAM_EEPROM_EMULATION
#undef SDCARD_EEPROM_EMULATION
#define FLASH_EEPROM_EMULATION #define FLASH_EEPROM_EMULATION
#endif #endif

View File

@ -1,129 +0,0 @@
/**
* Marlin 3D Printer Firmware
*
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
*
* 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 __SAMD51__
#include "../../inc/MarlinConfig.h"
#if ENABLED(EEPROM_SETTINGS)
#include "../shared/persistent_store_api.h"
#if ENABLED(FLASH_EEPROM_EMULATION)
#define NVMCTRL_CMD(c) do{ \
SYNC(!NVMCTRL->STATUS.bit.READY); \
NVMCTRL->INTFLAG.bit.DONE = true; \
NVMCTRL->CTRLB.reg = c | NVMCTRL_CTRLB_CMDEX_KEY; \
SYNC(NVMCTRL->INTFLAG.bit.DONE); \
}while(0)
#define NVMCTRL_FLUSH() do{ \
if (NVMCTRL->SEESTAT.bit.LOAD) \
NVMCTRL_CMD(NVMCTRL_CTRLB_CMD_SEEFLUSH); \
}while(0)
#endif
bool PersistentStore::access_start() {
#if ENABLED(FLASH_EEPROM_EMULATION)
NVMCTRL->SEECFG.reg = NVMCTRL_SEECFG_WMODE_BUFFERED; // Buffered mode and segment reallocation active
#endif
return true;
}
bool PersistentStore::access_finish() {
#if ENABLED(FLASH_EEPROM_EMULATION)
NVMCTRL_FLUSH();
if (!NVMCTRL->SEESTAT.bit.LOCK)
NVMCTRL_CMD(NVMCTRL_CTRLB_CMD_LSEE); // Lock E2P data write access
#endif
return true;
}
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
#if ENABLED(FLASH_EEPROM_EMULATION)
if (NVMCTRL->SEESTAT.bit.RLOCK)
NVMCTRL_CMD(NVMCTRL_CTRLB_CMD_USEE); // Unlock E2P data write access
#endif
while (size--) {
const uint8_t v = *value;
#if ENABLED(FLASH_EEPROM_EMULATION)
SYNC(NVMCTRL->SEESTAT.bit.BUSY);
if (NVMCTRL->INTFLAG.bit.SEESFULL)
NVMCTRL_FLUSH(); // Next write will trigger a sector reallocation. I need to flush 'pagebuffer'
((volatile uint8_t *)SEEPROM_ADDR)[pos] = v;
SYNC(!NVMCTRL->INTFLAG.bit.SEEWRC);
#else
uint8_t * const p = (uint8_t * const)pos;
if (v != eeprom_read_byte(p)) {
eeprom_write_byte(p, v);
delay(2);
if (eeprom_read_byte(p) != v) {
SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE);
return true;
}
}
#endif
crc16(crc, &v, 1);
pos++;
value++;
}
return false;
}
bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
while (size--) {
uint8_t c;
#if ENABLED(FLASH_EEPROM_EMULATION)
SYNC(NVMCTRL->SEESTAT.bit.BUSY);
c = ((volatile uint8_t *)SEEPROM_ADDR)[pos];
#else
c = eeprom_read_byte((uint8_t*)pos);
#endif
if (writing) *value = c;
crc16(crc, &c, 1);
pos++;
value++;
}
return false;
}
size_t PersistentStore::capacity() {
#if ENABLED(FLASH_EEPROM_EMULATION)
const uint8_t psz = NVMCTRL->SEESTAT.bit.PSZ,
sblk = NVMCTRL->SEESTAT.bit.SBLK;
if (!psz && !sblk) return 0;
else if (psz <= 2) return (0x200 << psz);
else if (sblk == 1 || psz == 3) return 4096;
else if (sblk == 2 || psz == 4) return 8192;
else if (sblk <= 4 || psz == 5) return 16384;
else if (sblk >= 9 && psz == 7) return 65536;
else return 32768;
#else
return E2END + 1;
#endif
}
#endif // EEPROM_SETTINGS
#endif // __SAMD51__

View File

@ -29,9 +29,7 @@
* The latest version of this library can always be found at * The latest version of this library can always be found at
* http://arduiniana.org. * http://arduiniana.org.
*/ */
#pragma once
#ifndef SOFTWARESERIAL_H
#define SOFTWARESERIAL_H
#include <Arduino.h> #include <Arduino.h>
@ -64,7 +62,6 @@ class SoftwareSerial : public Stream {
uint32_t delta_start = 0; uint32_t delta_start = 0;
// static data // static data
static bool initialised;
static HardwareTimer timer; static HardwareTimer timer;
static const IRQn_Type timer_interrupt_number; static const IRQn_Type timer_interrupt_number;
static uint32_t timer_interrupt_priority; static uint32_t timer_interrupt_priority;
@ -91,7 +88,7 @@ class SoftwareSerial : public Stream {
public: public:
// public methods // public methods
SoftwareSerial(uint16_t receivePin, uint16_t transmitPin, bool inverse_logic = false); SoftwareSerial(uint16_t receivePin, uint16_t transmitPin, bool inverse_logic=false);
virtual ~SoftwareSerial(); virtual ~SoftwareSerial();
void begin(long speed); void begin(long speed);
bool listen(); bool listen();
@ -115,5 +112,3 @@ class SoftwareSerial : public Stream {
using Print::write; using Print::write;
}; };
#endif // SOFTWARESERIAL_H

View File

@ -27,7 +27,7 @@
#if BOTH(EEPROM_SETTINGS, FLASH_EEPROM_EMULATION) #if BOTH(EEPROM_SETTINGS, FLASH_EEPROM_EMULATION)
#include "../shared/persistent_store_api.h" #include "../shared/eeprom_api.h"
// Only STM32F4 can support wear leveling at this time // Only STM32F4 can support wear leveling at this time

View File

@ -24,9 +24,9 @@
#include "../../inc/MarlinConfig.h" #include "../../inc/MarlinConfig.h"
#if EITHER(USE_REAL_EEPROM, SRAM_EEPROM_EMULATION) #if EITHER(USE_WIRED_EEPROM, SRAM_EEPROM_EMULATION)
#include "../shared/persistent_store_api.h" #include "../shared/eeprom_api.h"
bool PersistentStore::access_start() { bool PersistentStore::access_start() {
return true; return true;
@ -41,7 +41,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui
uint8_t v = *value; uint8_t v = *value;
// Save to either external EEPROM, program flash or Backup SRAM // Save to either external EEPROM, program flash or Backup SRAM
#if USE_REAL_EEPROM #if USE_WIRED_EEPROM
// EEPROM has only ~100,000 write cycles, // EEPROM has only ~100,000 write cycles,
// so only write bytes that have changed! // so only write bytes that have changed!
uint8_t * const p = (uint8_t * const)pos; uint8_t * const p = (uint8_t * const)pos;
@ -68,7 +68,7 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t
do { do {
// Read from either external EEPROM, program flash or Backup SRAM // Read from either external EEPROM, program flash or Backup SRAM
const uint8_t c = ( const uint8_t c = (
#if USE_REAL_EEPROM #if USE_WIRED_EEPROM
eeprom_read_byte((uint8_t*)pos) eeprom_read_byte((uint8_t*)pos)
#else #else
(*(__IO uint8_t *)(BKPSRAM_BASE + ((uint8_t*)pos))) (*(__IO uint8_t *)(BKPSRAM_BASE + ((uint8_t*)pos)))
@ -85,7 +85,7 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t
size_t PersistentStore::capacity() { size_t PersistentStore::capacity() {
return ( return (
#if USE_REAL_EEPROM #if USE_WIRED_EEPROM
E2END + 1 E2END + 1
#else #else
4096 // 4kB 4096 // 4kB
@ -93,5 +93,5 @@ size_t PersistentStore::capacity() {
); );
} }
#endif // USE_REAL_EEPROM || SRAM_EEPROM_EMULATION #endif // USE_WIRED_EEPROM || SRAM_EEPROM_EMULATION
#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC #endif // ARDUINO_ARCH_STM32 && !STM32GENERIC

View File

@ -30,7 +30,7 @@
#if ENABLED(SDCARD_EEPROM_EMULATION) #if ENABLED(SDCARD_EEPROM_EMULATION)
#include "../shared/persistent_store_api.h" #include "../shared/eeprom_api.h"
#ifndef E2END #ifndef E2END
#define E2END 0xFFF // 4KB #define E2END 0xFFF // 4KB

View File

@ -22,6 +22,6 @@
#pragma once #pragma once
// If no real EEPROM, Flash emulation, or SRAM emulation is available fall back to SD emulation // If no real EEPROM, Flash emulation, or SRAM emulation is available fall back to SD emulation
#if ENABLED(EEPROM_SETTINGS) && NONE(USE_REAL_EEPROM, FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION) #if ENABLED(EEPROM_SETTINGS) && NONE(USE_WIRED_EEPROM, FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION)
#define SDCARD_EEPROM_EMULATION #define SDCARD_EEPROM_EMULATION
#endif #endif

View File

@ -22,9 +22,9 @@
#include "../../inc/MarlinConfig.h" #include "../../inc/MarlinConfig.h"
#if USE_REAL_EEPROM #if USE_WIRED_EEPROM
#include "../shared/persistent_store_api.h" #include "../shared/eeprom_api.h"
bool PersistentStore::access_start() { bool PersistentStore::access_start() {
#if ENABLED(SPI_EEPROM) #if ENABLED(SPI_EEPROM)
@ -73,5 +73,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t
size_t PersistentStore::capacity() { return E2END + 1; } size_t PersistentStore::capacity() { return E2END + 1; }
#endif // USE_REAL_EEPROM #endif // USE_WIRED_EEPROM
#endif // __STM32F1__ #endif // __STM32F1__

View File

@ -31,10 +31,9 @@
#include "../../inc/MarlinConfig.h" #include "../../inc/MarlinConfig.h"
// This is for EEPROM emulation in flash #if ENABLED(FLASH_EEPROM_EMULATION)
#if BOTH(EEPROM_SETTINGS, FLASH_EEPROM_EMULATION)
#include "../shared/persistent_store_api.h" #include "../shared/eeprom_api.h"
#include <flash_stm32.h> #include <flash_stm32.h>
#include <EEPROM.h> #include <EEPROM.h>
@ -108,5 +107,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, const size_t size, uin
size_t PersistentStore::capacity() { return EEPROM_SIZE; } size_t PersistentStore::capacity() { return EEPROM_SIZE; }
#endif // EEPROM_SETTINGS && EEPROM FLASH #endif // FLASH_EEPROM_EMULATION
#endif // __STM32F1__ #endif // __STM32F1__

View File

@ -31,7 +31,7 @@
#if ENABLED(SDCARD_EEPROM_EMULATION) #if ENABLED(SDCARD_EEPROM_EMULATION)
#include "../shared/persistent_store_api.h" #include "../shared/eeprom_api.h"
#ifndef E2END #ifndef E2END
#define E2END 0xFFF // 4KB #define E2END 0xFFF // 4KB
@ -101,5 +101,4 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, const size_t size, uin
size_t PersistentStore::capacity() { return HAL_EEPROM_SIZE; } size_t PersistentStore::capacity() { return HAL_EEPROM_SIZE; }
#endif // SDCARD_EEPROM_EMULATION #endif // SDCARD_EEPROM_EMULATION
#endif // __STM32F1__ #endif // __STM32F1__

View File

@ -27,7 +27,7 @@
#if ENABLED(EEPROM_SETTINGS) #if ENABLED(EEPROM_SETTINGS)
#include "../shared/persistent_store_api.h" #include "../shared/eeprom_api.h"
bool PersistentStore::access_start() { return true; } bool PersistentStore::access_start() { return true; }
bool PersistentStore::access_finish() { return true; } bool PersistentStore::access_finish() { return true; }

View File

@ -22,7 +22,7 @@
#pragma once #pragma once
#if ENABLED(EEPROM_SETTINGS) && defined(STM32F7) #if ENABLED(EEPROM_SETTINGS) && defined(STM32F7)
#undef USE_REAL_EEPROM #undef USE_WIRED_EEPROM
#undef SRAM_EEPROM_EMULATION #undef SRAM_EEPROM_EMULATION
#undef SDCARD_EEPROM_EMULATION #undef SDCARD_EEPROM_EMULATION
#define FLASH_EEPROM_EMULATION #define FLASH_EEPROM_EMULATION

View File

@ -22,7 +22,7 @@
#if ENABLED(EEPROM_SETTINGS) #if ENABLED(EEPROM_SETTINGS)
#include "../shared/persistent_store_api.h" #include "../shared/eeprom_api.h"
bool PersistentStore::access_start() { return true; } bool PersistentStore::access_start() { return true; }
bool PersistentStore::access_finish() { return true; } bool PersistentStore::access_finish() { return true; }

View File

@ -76,8 +76,9 @@
#define SET_INPUT(IO) _SET_INPUT(IO) #define SET_INPUT(IO) _SET_INPUT(IO)
#define SET_INPUT_PULLUP(IO) _SET_INPUT_PULLUP(IO) #define SET_INPUT_PULLUP(IO) _SET_INPUT_PULLUP(IO)
#define SET_INPUT_PULLDOWN SET_INPUT
#define SET_OUTPUT(IO) _SET_OUTPUT(IO) #define SET_OUTPUT(IO) _SET_OUTPUT(IO)
#define SET_PWM(IO) SET_OUTPUT(IO) #define SET_PWM SET_OUTPUT
#define IS_INPUT(IO) _IS_INPUT(IO) #define IS_INPUT(IO) _IS_INPUT(IO)
#define IS_OUTPUT(IO) _IS_OUTPUT(IO) #define IS_OUTPUT(IO) _IS_OUTPUT(IO)

View File

@ -22,6 +22,6 @@
#pragma once #pragma once
// If no real EEPROM, Flash emulation, or SRAM emulation is available fall back to SD emulation // If no real EEPROM, Flash emulation, or SRAM emulation is available fall back to SD emulation
#if ENABLED(EEPROM_SETTINGS) && NONE(USE_REAL_EEPROM, FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION) #if ENABLED(EEPROM_SETTINGS) && NONE(USE_WIRED_EEPROM, FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION)
#define SDCARD_EEPROM_EMULATION #define SDCARD_EEPROM_EMULATION
#endif #endif

View File

@ -27,7 +27,7 @@
#if ENABLED(EEPROM_SETTINGS) #if ENABLED(EEPROM_SETTINGS)
#include "../shared/persistent_store_api.h" #include "../shared/eeprom_api.h"
#include <avr/eeprom.h> #include <avr/eeprom.h>
bool PersistentStore::access_start() { return true; } bool PersistentStore::access_start() { return true; }

View File

@ -76,8 +76,9 @@
#define SET_INPUT(IO) _SET_INPUT(IO) #define SET_INPUT(IO) _SET_INPUT(IO)
#define SET_INPUT_PULLUP(IO) _SET_INPUT_PULLUP(IO) #define SET_INPUT_PULLUP(IO) _SET_INPUT_PULLUP(IO)
#define SET_INPUT_PULLDOWN SET_INPUT
#define SET_OUTPUT(IO) _SET_OUTPUT(IO) #define SET_OUTPUT(IO) _SET_OUTPUT(IO)
#define SET_PWM(IO) SET_OUTPUT(IO) #define SET_PWM SET_OUTPUT
#define IS_INPUT(IO) _IS_INPUT(IO) #define IS_INPUT(IO) _IS_INPUT(IO)
#define IS_OUTPUT(IO) _IS_OUTPUT(IO) #define IS_OUTPUT(IO) _IS_OUTPUT(IO)

View File

@ -24,7 +24,7 @@
#if EITHER(EEPROM_SETTINGS, SD_FIRMWARE_UPDATE) #if EITHER(EEPROM_SETTINGS, SD_FIRMWARE_UPDATE)
#include "persistent_store_api.h" #include "eeprom_api.h"
PersistentStore persistentStore; PersistentStore persistentStore;
#endif #endif

View File

@ -210,6 +210,24 @@ bool wait_for_heatup = true;
// For M0/M1, this flag may be cleared (by M108) to exit the wait-for-user loop // For M0/M1, this flag may be cleared (by M108) to exit the wait-for-user loop
#if HAS_RESUME_CONTINUE #if HAS_RESUME_CONTINUE
bool wait_for_user; // = false; bool wait_for_user; // = false;
void wait_for_user_response(millis_t ms/*=0*/, const bool no_sleep/*=false*/) {
#if DISABLED(ADVANCED_PAUSE_FEATURE)
UNUSED(no_sleep);
#endif
KEEPALIVE_STATE(PAUSED_FOR_USER);
wait_for_user = true;
if (ms) ms += millis(); // expire time
while (wait_for_user && !(ms && ELAPSED(millis(), ms))) {
idle(
#if ENABLED(ADVANCED_PAUSE_FEATURE)
no_sleep
#endif
);
}
wait_for_user = false;
}
#endif #endif
// Inactivity shutdown // Inactivity shutdown
@ -418,52 +436,8 @@ void startOrResumeJob() {
} }
inline void finishSDPrinting() { inline void finishSDPrinting() {
if (queue.enqueue_one_P(PSTR("M1001")))
bool did_state = true; marlin_state = MF_RUNNING;
switch (card.sdprinting_done_state) {
case 1:
did_state = print_job_timer.duration() < 60 || queue.enqueue_one_P(PSTR("M31"));
break;
case 2:
did_state = queue.enqueue_one_P(PSTR("M77"));
break;
case 3:
#if ENABLED(LCD_SET_PROGRESS_MANUALLY)
ui.set_progress_done();
#endif
break;
case 4: // Display "Click to Continue..."
#if HAS_RESUME_CONTINUE // 30 min timeout with LCD, 1 min without
did_state = queue.enqueue_one_P(
print_job_timer.duration() < 60 ? PSTR("M0Q1P1") : PSTR("M0Q1S" TERN(HAS_LCD_MENU, "1800", "60"))
);
#endif
break;
case 5:
#if ENABLED(POWER_LOSS_RECOVERY)
recovery.purge();
#endif
#if ENABLED(SD_FINISHED_STEPPERRELEASE) && defined(SD_FINISHED_RELEASECOMMAND)
planner.finish_and_disable();
#endif
#if ENABLED(SD_REPRINT_LAST_SELECTED_FILE)
ui.reselect_last_file();
#endif
SERIAL_ECHOLNPGM(STR_FILE_PRINTED);
default:
did_state = false;
card.sdprinting_done_state = 0;
}
if (did_state) ++card.sdprinting_done_state;
} }
#endif // SDSUPPORT #endif // SDSUPPORT
@ -1208,7 +1182,7 @@ void loop() {
#if ENABLED(SDSUPPORT) #if ENABLED(SDSUPPORT)
card.checkautostart(); card.checkautostart();
if (card.flag.abort_sd_printing) abortSDPrinting(); if (card.flag.abort_sd_printing) abortSDPrinting();
if (card.sdprinting_done_state) finishSDPrinting(); if (marlin_state == MF_SD_COMPLETE) finishSDPrinting();
#endif #endif
queue.advance(); queue.advance();

View File

@ -83,6 +83,7 @@ enum MarlinState : uint8_t {
MF_PAUSED = _BV(1), MF_PAUSED = _BV(1),
MF_WAITING = _BV(2), MF_WAITING = _BV(2),
MF_STOPPED = _BV(3), MF_STOPPED = _BV(3),
MF_SD_COMPLETE = _BV(4),
MF_KILLED = _BV(7) MF_KILLED = _BV(7)
}; };
@ -98,6 +99,7 @@ extern bool wait_for_heatup;
#if HAS_RESUME_CONTINUE #if HAS_RESUME_CONTINUE
extern bool wait_for_user; extern bool wait_for_user;
void wait_for_user_response(millis_t ms=0, const bool no_sleep=false);
#endif #endif
// Inactivity shutdown timer // Inactivity shutdown timer

View File

@ -144,6 +144,7 @@
#define BOARD_LEAPFROG_XEED2015 1321 // Leapfrog Xeed 2015 #define BOARD_LEAPFROG_XEED2015 1321 // Leapfrog Xeed 2015
#define BOARD_PICA_REVB 1322 // PICA Shield (original version) #define BOARD_PICA_REVB 1322 // PICA Shield (original version)
#define BOARD_PICA 1323 // PICA Shield (rev C or later) #define BOARD_PICA 1323 // PICA Shield (rev C or later)
#define BOARD_INTAMSYS40 1324 // Intamsys 4.0 (Funmat HT)
// //
// ATmega1281, ATmega2561 // ATmega1281, ATmega2561

View File

@ -194,6 +194,9 @@
#define DISABLED(V...) DO(DIS,&&,V) #define DISABLED(V...) DO(DIS,&&,V)
#define TERN(O,A,B) _TERN(_ENA_1(O),B,A) // OPTION converted to '0' or '1' #define TERN(O,A,B) _TERN(_ENA_1(O),B,A) // OPTION converted to '0' or '1'
#define TERN0(O,A) _TERN(_ENA_1(O),0,A) // OPTION converted to A or '0'
#define TERN1(O,A) _TERN(_ENA_1(O),1,A) // OPTION converted to A or '1'
#define TERN_(O,A) _TERN(_ENA_1(O),,A) // OPTION converted to A or '<nul>'
#define _TERN(E,V...) __TERN(_CAT(T_,E),V) // Prepend 'T_' to get 'T_0' or 'T_1' #define _TERN(E,V...) __TERN(_CAT(T_,E),V) // Prepend 'T_' to get 'T_0' or 'T_1'
#define __TERN(T,V...) ___TERN(_CAT(_NO,T),V) // Prepend '_NO' to get '_NOT_0' or '_NOT_1' #define __TERN(T,V...) ___TERN(_CAT(_NO,T),V) // Prepend '_NO' to get '_NOT_0' or '_NOT_1'
#define ___TERN(P,V...) THIRD(P,V) // If first argument has a comma, A. Else B. #define ___TERN(P,V...) THIRD(P,V) // If first argument has a comma, A. Else B.

View File

@ -113,7 +113,7 @@ void Backlash::add_correction_steps(const int32_t &da, const int32_t &db, const
error_correction = 0; // Don't take up any backlash in this segment, as it would subtract steps error_correction = 0; // Don't take up any backlash in this segment, as it would subtract steps
} }
#endif #endif
// Making a correction reduces the residual error and modifies delta_mm // Making a correction reduces the residual error and adds block steps
if (error_correction) { if (error_correction) {
block->steps[axis] += ABS(error_correction); block->steps[axis] += ABS(error_correction);
residual_error[axis] -= error_correction; residual_error[axis] -= error_correction;

View File

@ -27,7 +27,7 @@
#include "../bedlevel.h" #include "../bedlevel.h"
#include "../../../MarlinCore.h" #include "../../../MarlinCore.h"
#include "../../../HAL/shared/persistent_store_api.h" #include "../../../HAL/shared/eeprom_api.h"
#include "../../../libs/hex_print_routines.h" #include "../../../libs/hex_print_routines.h"
#include "../../../module/configuration_store.h" #include "../../../module/configuration_store.h"
#include "../../../lcd/ultralcd.h" #include "../../../lcd/ultralcd.h"

View File

@ -121,7 +121,7 @@ uint8_t Max7219::suspended; // = 0;
#define CRITICAL_SECTION_START() NOOP #define CRITICAL_SECTION_START() NOOP
#define CRITICAL_SECTION_END() NOOP #define CRITICAL_SECTION_END() NOOP
#else #else
#define SIG_DELAY() DELAY_NS(188) // Delay for 0.1875µs (16MHz AVR) or 0.15µs (20MHz AVR) #define SIG_DELAY() DELAY_NS(250)
#endif #endif
void Max7219::error(const char * const func, const int32_t v1, const int32_t v2/*=-1*/) { void Max7219::error(const char * const func, const int32_t v1, const int32_t v2/*=-1*/) {

View File

@ -707,14 +707,13 @@ void MMU2::filament_runout() {
if (recover) { if (recover) {
LCD_MESSAGEPGM(MSG_MMU2_EJECT_RECOVER); LCD_MESSAGEPGM(MSG_MMU2_EJECT_RECOVER);
BUZZ(200, 404); BUZZ(200, 404);
wait_for_user = true;
#if ENABLED(HOST_PROMPT_SUPPORT) #if ENABLED(HOST_PROMPT_SUPPORT)
host_prompt_do(PROMPT_USER_CONTINUE, PSTR("MMU2 Eject Recover"), CONTINUE_STR); host_prompt_do(PROMPT_USER_CONTINUE, PSTR("MMU2 Eject Recover"), CONTINUE_STR);
#endif #endif
#if ENABLED(EXTENSIBLE_UI) #if ENABLED(EXTENSIBLE_UI)
ExtUI::onUserConfirmRequired_P(PSTR("MMU2 Eject Recover")); ExtUI::onUserConfirmRequired_P(PSTR("MMU2 Eject Recover"));
#endif #endif
while (wait_for_user) idle(); wait_for_user_response();
BUZZ(200, 404); BUZZ(200, 404);
BUZZ(200, 404); BUZZ(200, 404);

View File

@ -134,15 +134,6 @@ static bool ensure_safe_temperature(const PauseMode mode=PAUSE_MODE_SAME) {
return thermalManager.wait_for_hotend(active_extruder); return thermalManager.wait_for_hotend(active_extruder);
} }
void do_pause_e_move(const float &length, const feedRate_t &fr_mm_s) {
#if HAS_FILAMENT_SENSOR
runout.reset();
#endif
current_position.e += length / planner.e_factor[active_extruder];
line_to_current_position(fr_mm_s);
planner.synchronize();
}
/** /**
* Load filament into the hotend * Load filament into the hotend
* *
@ -184,7 +175,6 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l
#endif #endif
KEEPALIVE_STATE(PAUSED_FOR_USER); KEEPALIVE_STATE(PAUSED_FOR_USER);
wait_for_user = true; // LCD click or M108 will clear this
#if ENABLED(HOST_PROMPT_SUPPORT) #if ENABLED(HOST_PROMPT_SUPPORT)
const char tool = '0' const char tool = '0'
#if NUM_RUNOUT_SENSORS > 1 #if NUM_RUNOUT_SENSORS > 1
@ -218,7 +208,7 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l
#endif #endif
// Slow Load filament // Slow Load filament
if (slow_load_length) do_pause_e_move(slow_load_length, FILAMENT_CHANGE_SLOW_LOAD_FEEDRATE); if (slow_load_length) unscaled_e_move(slow_load_length, FILAMENT_CHANGE_SLOW_LOAD_FEEDRATE);
// Fast Load Filament // Fast Load Filament
if (fast_load_length) { if (fast_load_length) {
@ -227,7 +217,7 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l
planner.settings.retract_acceleration = FILAMENT_CHANGE_FAST_LOAD_ACCEL; planner.settings.retract_acceleration = FILAMENT_CHANGE_FAST_LOAD_ACCEL;
#endif #endif
do_pause_e_move(fast_load_length, FILAMENT_CHANGE_FAST_LOAD_FEEDRATE); unscaled_e_move(fast_load_length, FILAMENT_CHANGE_FAST_LOAD_FEEDRATE);
#if FILAMENT_CHANGE_FAST_LOAD_ACCEL > 0 #if FILAMENT_CHANGE_FAST_LOAD_ACCEL > 0
planner.settings.retract_acceleration = saved_acceleration; planner.settings.retract_acceleration = saved_acceleration;
@ -246,15 +236,15 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l
if (show_lcd) lcd_pause_show_message(PAUSE_MESSAGE_PURGE); if (show_lcd) lcd_pause_show_message(PAUSE_MESSAGE_PURGE);
#endif #endif
wait_for_user = true;
#if ENABLED(HOST_PROMPT_SUPPORT) #if ENABLED(HOST_PROMPT_SUPPORT)
host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Filament Purging..."), CONTINUE_STR); host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Filament Purging..."), CONTINUE_STR);
#endif #endif
#if ENABLED(EXTENSIBLE_UI) #if ENABLED(EXTENSIBLE_UI)
ExtUI::onUserConfirmRequired_P(PSTR("Filament Purging...")); ExtUI::onUserConfirmRequired_P(PSTR("Filament Purging..."));
#endif #endif
wait_for_user = true; // A click or M108 breaks the purge_length loop
for (float purge_count = purge_length; purge_count > 0 && wait_for_user; --purge_count) for (float purge_count = purge_length; purge_count > 0 && wait_for_user; --purge_count)
do_pause_e_move(1, ADVANCED_PAUSE_PURGE_FEEDRATE); unscaled_e_move(1, ADVANCED_PAUSE_PURGE_FEEDRATE);
wait_for_user = false; wait_for_user = false;
#else #else
@ -267,7 +257,7 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l
#endif #endif
// Extrude filament to get into hotend // Extrude filament to get into hotend
do_pause_e_move(purge_length, ADVANCED_PAUSE_PURGE_FEEDRATE); unscaled_e_move(purge_length, ADVANCED_PAUSE_PURGE_FEEDRATE);
} }
#if ENABLED(HOST_PROMPT_SUPPORT) #if ENABLED(HOST_PROMPT_SUPPORT)
@ -332,13 +322,13 @@ bool unload_filament(const float &unload_length, const bool show_lcd/*=false*/,
#endif #endif
// Retract filament // Retract filament
do_pause_e_move(-(FILAMENT_UNLOAD_PURGE_RETRACT) * mix_multiplier, (PAUSE_PARK_RETRACT_FEEDRATE) * mix_multiplier); unscaled_e_move(-(FILAMENT_UNLOAD_PURGE_RETRACT) * mix_multiplier, (PAUSE_PARK_RETRACT_FEEDRATE) * mix_multiplier);
// Wait for filament to cool // Wait for filament to cool
safe_delay(FILAMENT_UNLOAD_PURGE_DELAY); safe_delay(FILAMENT_UNLOAD_PURGE_DELAY);
// Quickly purge // Quickly purge
do_pause_e_move((FILAMENT_UNLOAD_PURGE_RETRACT + FILAMENT_UNLOAD_PURGE_LENGTH) * mix_multiplier, unscaled_e_move((FILAMENT_UNLOAD_PURGE_RETRACT + FILAMENT_UNLOAD_PURGE_LENGTH) * mix_multiplier,
(FILAMENT_UNLOAD_PURGE_FEEDRATE) * mix_multiplier); (FILAMENT_UNLOAD_PURGE_FEEDRATE) * mix_multiplier);
// Unload filament // Unload filament
@ -347,7 +337,7 @@ bool unload_filament(const float &unload_length, const bool show_lcd/*=false*/,
planner.settings.retract_acceleration = FILAMENT_CHANGE_UNLOAD_ACCEL; planner.settings.retract_acceleration = FILAMENT_CHANGE_UNLOAD_ACCEL;
#endif #endif
do_pause_e_move(unload_length * mix_multiplier, (FILAMENT_CHANGE_UNLOAD_FEEDRATE) * mix_multiplier); unscaled_e_move(unload_length * mix_multiplier, (FILAMENT_CHANGE_UNLOAD_FEEDRATE) * mix_multiplier);
#if FILAMENT_CHANGE_FAST_LOAD_ACCEL > 0 #if FILAMENT_CHANGE_FAST_LOAD_ACCEL > 0
planner.settings.retract_acceleration = saved_acceleration; planner.settings.retract_acceleration = saved_acceleration;
@ -437,7 +427,7 @@ bool pause_print(const float &retract, const xyz_pos_t &park_point, const float
// Initial retract before move to filament change position // Initial retract before move to filament change position
if (retract && thermalManager.hotEnoughToExtrude(active_extruder)) if (retract && thermalManager.hotEnoughToExtrude(active_extruder))
do_pause_e_move(retract, PAUSE_PARK_RETRACT_FEEDRATE); unscaled_e_move(retract, PAUSE_PARK_RETRACT_FEEDRATE);
// Park the nozzle by moving up by z_lift and then moving to (x_pos, y_pos) // Park the nozzle by moving up by z_lift and then moving to (x_pos, y_pos)
if (!axes_need_homing()) if (!axes_need_homing())
@ -508,13 +498,13 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep
// Wait for filament insert by user and press button // Wait for filament insert by user and press button
KEEPALIVE_STATE(PAUSED_FOR_USER); KEEPALIVE_STATE(PAUSED_FOR_USER);
wait_for_user = true; // LCD click or M108 will clear this
#if ENABLED(HOST_PROMPT_SUPPORT) #if ENABLED(HOST_PROMPT_SUPPORT)
host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Nozzle Parked"), CONTINUE_STR); host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Nozzle Parked"), CONTINUE_STR);
#endif #endif
#if ENABLED(EXTENSIBLE_UI) #if ENABLED(EXTENSIBLE_UI)
ExtUI::onUserConfirmRequired_P(PSTR("Nozzle Parked")); ExtUI::onUserConfirmRequired_P(PSTR("Nozzle Parked"));
#endif #endif
wait_for_user = true; // LCD click or M108 will clear this
while (wait_for_user) { while (wait_for_user) {
#if HAS_BUZZER #if HAS_BUZZER
filament_change_beep(max_beep_count); filament_change_beep(max_beep_count);
@ -540,8 +530,7 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep
ExtUI::onUserConfirmRequired_P(PSTR("HeaterTimeout")); ExtUI::onUserConfirmRequired_P(PSTR("HeaterTimeout"));
#endif #endif
// Wait for LCD click or M108 wait_for_user_response(0, true); // Wait for LCD click or M108
while (wait_for_user) idle_no_sleep();
#if ENABLED(HOST_PROMPT_SUPPORT) #if ENABLED(HOST_PROMPT_SUPPORT)
host_prompt_do(PROMPT_INFO, PSTR("Reheating")); host_prompt_do(PROMPT_INFO, PSTR("Reheating"));
@ -633,11 +622,11 @@ void resume_print(const float &slow_load_length/*=0*/, const float &fast_load_le
#if ENABLED(FWRETRACT) #if ENABLED(FWRETRACT)
// If retracted before goto pause // If retracted before goto pause
if (fwretract.retracted[active_extruder]) if (fwretract.retracted[active_extruder])
do_pause_e_move(-fwretract.settings.retract_length, fwretract.settings.retract_feedrate_mm_s); unscaled_e_move(-fwretract.settings.retract_length, fwretract.settings.retract_feedrate_mm_s);
#endif #endif
// If resume_position is negative // If resume_position is negative
if (resume_position.e < 0) do_pause_e_move(resume_position.e, feedRate_t(PAUSE_PARK_RETRACT_FEEDRATE)); if (resume_position.e < 0) unscaled_e_move(resume_position.e, feedRate_t(PAUSE_PARK_RETRACT_FEEDRATE));
// Move XY to starting position, then Z // Move XY to starting position, then Z
do_blocking_move_to_xy(resume_position, feedRate_t(NOZZLE_PARK_XY_FEEDRATE)); do_blocking_move_to_xy(resume_position, feedRate_t(NOZZLE_PARK_XY_FEEDRATE));
@ -646,7 +635,7 @@ void resume_print(const float &slow_load_length/*=0*/, const float &fast_load_le
do_blocking_move_to_z(resume_position.z, feedRate_t(NOZZLE_PARK_Z_FEEDRATE)); do_blocking_move_to_z(resume_position.z, feedRate_t(NOZZLE_PARK_Z_FEEDRATE));
#if ADVANCED_PAUSE_RESUME_PRIME != 0 #if ADVANCED_PAUSE_RESUME_PRIME != 0
do_pause_e_move(ADVANCED_PAUSE_RESUME_PRIME, feedRate_t(ADVANCED_PAUSE_PURGE_FEEDRATE)); unscaled_e_move(ADVANCED_PAUSE_RESUME_PRIME, feedRate_t(ADVANCED_PAUSE_PURGE_FEEDRATE));
#endif #endif
// Now all extrusion positions are resumed and ready to be confirmed // Now all extrusion positions are resumed and ready to be confirmed

View File

@ -83,8 +83,6 @@ extern uint8_t did_pause_print;
#define DXC_PASS #define DXC_PASS
#endif #endif
void do_pause_e_move(const float &length, const feedRate_t &fr_mm_s);
bool pause_print(const float &retract, const xyz_pos_t &park_point, const float &unload_length=0, const bool show_lcd=false DXC_PARAMS); bool pause_print(const float &retract, const xyz_pos_t &park_point, const float &unload_length=0, const bool show_lcd=false DXC_PARAMS);
void wait_for_confirmation(const bool is_reload=false, const int8_t max_beep_count=0 DXC_PARAMS); void wait_for_confirmation(const bool is_reload=false, const int8_t max_beep_count=0 DXC_PARAMS);

View File

@ -49,37 +49,27 @@ void TWIBus::address(const uint8_t adr) {
addr = adr; addr = adr;
#if ENABLED(DEBUG_TWIBUS) debug(PSTR("address"), adr);
debug(PSTR("address"), adr);
#endif
} }
void TWIBus::addbyte(const char c) { void TWIBus::addbyte(const char c) {
if (buffer_s >= COUNT(buffer)) return; if (buffer_s >= COUNT(buffer)) return;
buffer[buffer_s++] = c; buffer[buffer_s++] = c;
#if ENABLED(DEBUG_TWIBUS) debug(PSTR("addbyte"), c);
debug(PSTR("addbyte"), c);
#endif
} }
void TWIBus::addbytes(char src[], uint8_t bytes) { void TWIBus::addbytes(char src[], uint8_t bytes) {
#if ENABLED(DEBUG_TWIBUS) debug(PSTR("addbytes"), bytes);
debug(PSTR("addbytes"), bytes);
#endif
while (bytes--) addbyte(*src++); while (bytes--) addbyte(*src++);
} }
void TWIBus::addstring(char str[]) { void TWIBus::addstring(char str[]) {
#if ENABLED(DEBUG_TWIBUS) debug(PSTR("addstring"), str);
debug(PSTR("addstring"), str);
#endif
while (char c = *str++) addbyte(c); while (char c = *str++) addbyte(c);
} }
void TWIBus::send() { void TWIBus::send() {
#if ENABLED(DEBUG_TWIBUS) debug(PSTR("send"), addr);
debug(PSTR("send"), addr);
#endif
Wire.beginTransmission(I2C_ADDRESS(addr)); Wire.beginTransmission(I2C_ADDRESS(addr));
Wire.write(buffer, buffer_s); Wire.write(buffer, buffer_s);
@ -89,21 +79,21 @@ void TWIBus::send() {
} }
// static // static
void TWIBus::echoprefix(uint8_t bytes, const char prefix[], uint8_t adr) { void TWIBus::echoprefix(uint8_t bytes, const char pref[], uint8_t adr) {
SERIAL_ECHO_START(); SERIAL_ECHO_START();
serialprintPGM(prefix); serialprintPGM(pref);
SERIAL_ECHOPAIR(": from:", adr, " bytes:", bytes, " data:"); SERIAL_ECHOPAIR(": from:", adr, " bytes:", bytes, " data:");
} }
// static // static
void TWIBus::echodata(uint8_t bytes, const char prefix[], uint8_t adr) { void TWIBus::echodata(uint8_t bytes, const char pref[], uint8_t adr) {
echoprefix(bytes, prefix, adr); echoprefix(bytes, pref, adr);
while (bytes-- && Wire.available()) SERIAL_CHAR(Wire.read()); while (bytes-- && Wire.available()) SERIAL_CHAR(Wire.read());
SERIAL_EOL(); SERIAL_EOL();
} }
void TWIBus::echobuffer(const char prefix[], uint8_t adr) { void TWIBus::echobuffer(const char pref[], uint8_t adr) {
echoprefix(buffer_s, prefix, adr); echoprefix(buffer_s, pref, adr);
LOOP_L_N(i, buffer_s) SERIAL_CHAR(buffer[i]); LOOP_L_N(i, buffer_s) SERIAL_CHAR(buffer[i]);
SERIAL_EOL(); SERIAL_EOL();
} }
@ -111,15 +101,11 @@ void TWIBus::echobuffer(const char prefix[], uint8_t adr) {
bool TWIBus::request(const uint8_t bytes) { bool TWIBus::request(const uint8_t bytes) {
if (!addr) return false; if (!addr) return false;
#if ENABLED(DEBUG_TWIBUS) debug(PSTR("request"), bytes);
debug(PSTR("request"), bytes);
#endif
// requestFrom() is a blocking function // requestFrom() is a blocking function
if (Wire.requestFrom(addr, bytes) == 0) { if (Wire.requestFrom(addr, bytes) == 0) {
#if ENABLED(DEBUG_TWIBUS) debug("request fail", addr);
debug("request fail", addr);
#endif
return false; return false;
} }
@ -127,9 +113,7 @@ bool TWIBus::request(const uint8_t bytes) {
} }
void TWIBus::relay(const uint8_t bytes) { void TWIBus::relay(const uint8_t bytes) {
#if ENABLED(DEBUG_TWIBUS) debug(PSTR("relay"), bytes);
debug(PSTR("relay"), bytes);
#endif
if (request(bytes)) if (request(bytes))
echodata(bytes, PSTR("i2c-reply"), addr); echodata(bytes, PSTR("i2c-reply"), addr);
@ -141,9 +125,7 @@ uint8_t TWIBus::capture(char *dst, const uint8_t bytes) {
while (count < bytes && Wire.available()) while (count < bytes && Wire.available())
dst[count++] = Wire.read(); dst[count++] = Wire.read();
#if ENABLED(DEBUG_TWIBUS) debug(PSTR("capture"), count);
debug(PSTR("capture"), count);
#endif
return count; return count;
} }
@ -156,16 +138,12 @@ void TWIBus::flush() {
#if I2C_SLAVE_ADDRESS > 0 #if I2C_SLAVE_ADDRESS > 0
void TWIBus::receive(uint8_t bytes) { void TWIBus::receive(uint8_t bytes) {
#if ENABLED(DEBUG_TWIBUS) debug(PSTR("receive"), bytes);
debug(PSTR("receive"), bytes);
#endif
echodata(bytes, PSTR("i2c-receive"), 0); echodata(bytes, PSTR("i2c-receive"), 0);
} }
void TWIBus::reply(char str[]/*=nullptr*/) { void TWIBus::reply(char str[]/*=nullptr*/) {
#if ENABLED(DEBUG_TWIBUS) debug(PSTR("reply"), str);
debug(PSTR("reply"), str);
#endif
if (str) { if (str) {
reset(); reset();

View File

@ -223,7 +223,6 @@ class TWIBus {
#endif #endif
#if ENABLED(DEBUG_TWIBUS) #if ENABLED(DEBUG_TWIBUS)
/** /**
* @brief Prints a debug message * @brief Prints a debug message
* @details Prints a simple debug message "TWIBus::function: value" * @details Prints a simple debug message "TWIBus::function: value"
@ -233,6 +232,10 @@ class TWIBus {
static void debug(const char func[], char c); static void debug(const char func[], char c);
static void debug(const char func[], char adr[]); static void debug(const char func[], char adr[]);
static inline void debug(const char func[], uint8_t v) { debug(func, (uint32_t)v); } static inline void debug(const char func[], uint8_t v) { debug(func, (uint32_t)v); }
#else
static inline void debug(const char[], uint32_t) {}
static inline void debug(const char[], char) {}
static inline void debug(const char[], char[]) {}
static inline void debug(const char[], uint8_t) {}
#endif #endif
}; };

View File

@ -255,28 +255,28 @@ void GcodeSuite::G28() {
#define HAS_HOMING_CURRENT (HAS_CURRENT_HOME(X) || HAS_CURRENT_HOME(X2) || HAS_CURRENT_HOME(Y) || HAS_CURRENT_HOME(Y2)) #define HAS_HOMING_CURRENT (HAS_CURRENT_HOME(X) || HAS_CURRENT_HOME(X2) || HAS_CURRENT_HOME(Y) || HAS_CURRENT_HOME(Y2))
#if HAS_HOMING_CURRENT #if HAS_HOMING_CURRENT
auto debug_current = [](const char * const s, const int16_t a, const int16_t b){ auto debug_current = [](PGM_P const s, const int16_t a, const int16_t b){
DEBUG_ECHO(s); DEBUG_ECHOLNPAIR(" current: ", a, " -> ", b); serialprintPGM(s); DEBUG_ECHOLNPAIR(" current: ", a, " -> ", b);
}; };
#if HAS_CURRENT_HOME(X) #if HAS_CURRENT_HOME(X)
const int16_t tmc_save_current_X = stepperX.getMilliamps(); const int16_t tmc_save_current_X = stepperX.getMilliamps();
stepperX.rms_current(X_CURRENT_HOME); stepperX.rms_current(X_CURRENT_HOME);
if (DEBUGGING(LEVELING)) debug_current("X", tmc_save_current_X, X_CURRENT_HOME); if (DEBUGGING(LEVELING)) debug_current(PSTR("X"), tmc_save_current_X, X_CURRENT_HOME);
#endif #endif
#if HAS_CURRENT_HOME(X2) #if HAS_CURRENT_HOME(X2)
const int16_t tmc_save_current_X2 = stepperX2.getMilliamps(); const int16_t tmc_save_current_X2 = stepperX2.getMilliamps();
stepperX2.rms_current(X2_CURRENT_HOME); stepperX2.rms_current(X2_CURRENT_HOME);
if (DEBUGGING(LEVELING)) debug_current("X2", tmc_save_current_X2, X2_CURRENT_HOME); if (DEBUGGING(LEVELING)) debug_current(PSTR("X2"), tmc_save_current_X2, X2_CURRENT_HOME);
#endif #endif
#if HAS_CURRENT_HOME(Y) #if HAS_CURRENT_HOME(Y)
const int16_t tmc_save_current_Y = stepperY.getMilliamps(); const int16_t tmc_save_current_Y = stepperY.getMilliamps();
stepperY.rms_current(Y_CURRENT_HOME); stepperY.rms_current(Y_CURRENT_HOME);
if (DEBUGGING(LEVELING)) debug_current("Y", tmc_save_current_Y, Y_CURRENT_HOME); if (DEBUGGING(LEVELING)) debug_current(PSTR("Y"), tmc_save_current_Y, Y_CURRENT_HOME);
#endif #endif
#if HAS_CURRENT_HOME(Y2) #if HAS_CURRENT_HOME(Y2)
const int16_t tmc_save_current_Y2 = stepperY2.getMilliamps(); const int16_t tmc_save_current_Y2 = stepperY2.getMilliamps();
stepperY2.rms_current(Y2_CURRENT_HOME); stepperY2.rms_current(Y2_CURRENT_HOME);
if (DEBUGGING(LEVELING)) debug_current("Y2", tmc_save_current_Y2, Y2_CURRENT_HOME); if (DEBUGGING(LEVELING)) debug_current(PSTR("Y2"), tmc_save_current_Y2, Y2_CURRENT_HOME);
#endif #endif
#endif #endif
@ -345,12 +345,8 @@ void GcodeSuite::G28() {
#endif #endif
// Home Y (before X) // Home Y (before X)
#if ENABLED(HOME_Y_BEFORE_X) if (ENABLED(HOME_Y_BEFORE_X) && (doY || (ENABLED(CODEPENDENT_XY_HOMING) && doX)))
homeaxis(Y_AXIS);
if (doY || (doX && ENABLED(CODEPENDENT_XY_HOMING)))
homeaxis(Y_AXIS);
#endif
// Home X // Home X
if (doX || (doY && ENABLED(CODEPENDENT_XY_HOMING) && DISABLED(HOME_Y_BEFORE_X))) { if (doX || (doY && ENABLED(CODEPENDENT_XY_HOMING) && DISABLED(HOME_Y_BEFORE_X))) {

View File

@ -37,6 +37,21 @@
#include "../../module/endstops.h" #include "../../module/endstops.h"
#include "../../feature/bedlevel/bedlevel.h" #include "../../feature/bedlevel/bedlevel.h"
#if !AXIS_CAN_CALIBRATE(X)
#undef CALIBRATION_MEASURE_LEFT
#undef CALIBRATION_MEASURE_RIGHT
#endif
#if !AXIS_CAN_CALIBRATE(Y)
#undef CALIBRATION_MEASURE_FRONT
#undef CALIBRATION_MEASURE_BACK
#endif
#if !AXIS_CAN_CALIBRATE(Z)
#undef CALIBRATION_MEASURE_AT_TOP_EDGES
#endif
/** /**
* G425 backs away from the calibration object by various distances * G425 backs away from the calibration object by various distances
* depending on the confidence level: * depending on the confidence level:
@ -207,42 +222,52 @@ inline float measure(const AxisEnum axis, const int dir, const bool stop_state,
inline void probe_side(measurements_t &m, const float uncertainty, const side_t side, const bool probe_top_at_edge=false) { inline void probe_side(measurements_t &m, const float uncertainty, const side_t side, const bool probe_top_at_edge=false) {
const xyz_float_t dimensions = CALIBRATION_OBJECT_DIMENSIONS; const xyz_float_t dimensions = CALIBRATION_OBJECT_DIMENSIONS;
AxisEnum axis; AxisEnum axis;
float dir; float dir = 1;
park_above_object(m, uncertainty); park_above_object(m, uncertainty);
switch (side) { switch (side) {
case TOP: { #if AXIS_CAN_CALIBRATE(Z)
const float measurement = measure(Z_AXIS, -1, true, &m.backlash[TOP], uncertainty); case TOP: {
m.obj_center.z = measurement - dimensions.z / 2; const float measurement = measure(Z_AXIS, -1, true, &m.backlash[TOP], uncertainty);
m.obj_side[TOP] = measurement; m.obj_center.z = measurement - dimensions.z / 2;
return; m.obj_side[TOP] = measurement;
} return;
case RIGHT: axis = X_AXIS; dir = -1; break; }
case FRONT: axis = Y_AXIS; dir = 1; break; #endif
case LEFT: axis = X_AXIS; dir = 1; break; #if AXIS_CAN_CALIBRATE(X)
case BACK: axis = Y_AXIS; dir = -1; break; case LEFT: axis = X_AXIS; break;
case RIGHT: axis = X_AXIS; dir = -1; break;
#endif
#if AXIS_CAN_CALIBRATE(Y)
case FRONT: axis = Y_AXIS; break;
case BACK: axis = Y_AXIS; dir = -1; break;
#endif
default: return; default: return;
} }
if (probe_top_at_edge) { if (probe_top_at_edge) {
// Probe top nearest the side we are probing #if AXIS_CAN_CALIBRATE(Z)
current_position[axis] = m.obj_center[axis] + (-dir) * (dimensions[axis] / 2 - m.nozzle_outer_dimension[axis]); // Probe top nearest the side we are probing
calibration_move(); current_position[axis] = m.obj_center[axis] + (-dir) * (dimensions[axis] / 2 - m.nozzle_outer_dimension[axis]);
m.obj_side[TOP] = measure(Z_AXIS, -1, true, &m.backlash[TOP], uncertainty); calibration_move();
m.obj_center.z = m.obj_side[TOP] - dimensions.z / 2; m.obj_side[TOP] = measure(Z_AXIS, -1, true, &m.backlash[TOP], uncertainty);
m.obj_center.z = m.obj_side[TOP] - dimensions.z / 2;
#endif
} }
// Move to safe distance to the side of the calibration object if (AXIS_CAN_CALIBRATE(X) && axis == X_AXIS || AXIS_CAN_CALIBRATE(Y) && axis == Y_AXIS) {
current_position[axis] = m.obj_center[axis] + (-dir) * (dimensions[axis] / 2 + m.nozzle_outer_dimension[axis] / 2 + uncertainty); // Move to safe distance to the side of the calibration object
calibration_move(); current_position[axis] = m.obj_center[axis] + (-dir) * (dimensions[axis] / 2 + m.nozzle_outer_dimension[axis] / 2 + uncertainty);
calibration_move();
// Plunge below the side of the calibration object and measure // Plunge below the side of the calibration object and measure
current_position.z = m.obj_side[TOP] - CALIBRATION_NOZZLE_TIP_HEIGHT * 0.7; current_position.z = m.obj_side[TOP] - (CALIBRATION_NOZZLE_TIP_HEIGHT) * 0.7f;
calibration_move(); calibration_move();
const float measurement = measure(axis, dir, true, &m.backlash[side], uncertainty); const float measurement = measure(axis, dir, true, &m.backlash[side], uncertainty);
m.obj_center[axis] = measurement + dir * (dimensions[axis] / 2 + m.nozzle_outer_dimension[axis] / 2); m.obj_center[axis] = measurement + dir * (dimensions[axis] / 2 + m.nozzle_outer_dimension[axis] / 2);
m.obj_side[side] = measurement; m.obj_side[side] = measurement;
}
} }
/** /**
@ -252,7 +277,7 @@ inline void probe_side(measurements_t &m, const float uncertainty, const side_t
* uncertainty in - How far away from the calibration object to begin probing * uncertainty in - How far away from the calibration object to begin probing
*/ */
inline void probe_sides(measurements_t &m, const float uncertainty) { inline void probe_sides(measurements_t &m, const float uncertainty) {
#ifdef CALIBRATION_MEASURE_AT_TOP_EDGES #if ENABLED(CALIBRATION_MEASURE_AT_TOP_EDGES)
constexpr bool probe_top_at_edge = true; constexpr bool probe_top_at_edge = true;
#else #else
// Probing at the exact center only works if the center is flat. Probing on a washer // Probing at the exact center only works if the center is flat. Probing on a washer
@ -261,18 +286,18 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
probe_side(m, uncertainty, TOP); probe_side(m, uncertainty, TOP);
#endif #endif
#ifdef CALIBRATION_MEASURE_RIGHT #if ENABLED(CALIBRATION_MEASURE_RIGHT)
probe_side(m, uncertainty, RIGHT, probe_top_at_edge); probe_side(m, uncertainty, RIGHT, probe_top_at_edge);
#endif #endif
#ifdef CALIBRATION_MEASURE_FRONT #if ENABLED(CALIBRATION_MEASURE_FRONT)
probe_side(m, uncertainty, FRONT, probe_top_at_edge); probe_side(m, uncertainty, FRONT, probe_top_at_edge);
#endif #endif
#ifdef CALIBRATION_MEASURE_LEFT #if ENABLED(CALIBRATION_MEASURE_LEFT)
probe_side(m, uncertainty, LEFT, probe_top_at_edge); probe_side(m, uncertainty, LEFT, probe_top_at_edge);
#endif #endif
#ifdef CALIBRATION_MEASURE_BACK #if ENABLED(CALIBRATION_MEASURE_BACK)
probe_side(m, uncertainty, BACK, probe_top_at_edge); probe_side(m, uncertainty, BACK, probe_top_at_edge);
#endif #endif
@ -313,7 +338,9 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
#if ENABLED(CALIBRATION_REPORTING) #if ENABLED(CALIBRATION_REPORTING)
inline void report_measured_faces(const measurements_t &m) { inline void report_measured_faces(const measurements_t &m) {
SERIAL_ECHOLNPGM("Sides:"); SERIAL_ECHOLNPGM("Sides:");
SERIAL_ECHOLNPAIR(" Top: ", m.obj_side[TOP]); #if AXIS_CAN_CALIBRATE(Z)
SERIAL_ECHOLNPAIR(" Top: ", m.obj_side[TOP]);
#endif
#if ENABLED(CALIBRATION_MEASURE_LEFT) #if ENABLED(CALIBRATION_MEASURE_LEFT)
SERIAL_ECHOLNPAIR(" Left: ", m.obj_side[LEFT]); SERIAL_ECHOLNPAIR(" Left: ", m.obj_side[LEFT]);
#endif #endif
@ -343,19 +370,25 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
inline void report_measured_backlash(const measurements_t &m) { inline void report_measured_backlash(const measurements_t &m) {
SERIAL_ECHOLNPGM("Backlash:"); SERIAL_ECHOLNPGM("Backlash:");
#if ENABLED(CALIBRATION_MEASURE_LEFT) #if AXIS_CAN_CALIBRATE(X)
SERIAL_ECHOLNPAIR(" Left: ", m.backlash[LEFT]); #if ENABLED(CALIBRATION_MEASURE_LEFT)
SERIAL_ECHOLNPAIR(" Left: ", m.backlash[LEFT]);
#endif
#if ENABLED(CALIBRATION_MEASURE_RIGHT)
SERIAL_ECHOLNPAIR(" Right: ", m.backlash[RIGHT]);
#endif
#endif #endif
#if ENABLED(CALIBRATION_MEASURE_RIGHT) #if AXIS_CAN_CALIBRATE(Y)
SERIAL_ECHOLNPAIR(" Right: ", m.backlash[RIGHT]); #if ENABLED(CALIBRATION_MEASURE_FRONT)
SERIAL_ECHOLNPAIR(" Front: ", m.backlash[FRONT]);
#endif
#if ENABLED(CALIBRATION_MEASURE_BACK)
SERIAL_ECHOLNPAIR(" Back: ", m.backlash[BACK]);
#endif
#endif #endif
#if ENABLED(CALIBRATION_MEASURE_FRONT) #if AXIS_CAN_CALIBRATE(Z)
SERIAL_ECHOLNPAIR(" Front: ", m.backlash[FRONT]); SERIAL_ECHOLNPAIR(" Top: ", m.backlash[TOP]);
#endif #endif
#if ENABLED(CALIBRATION_MEASURE_BACK)
SERIAL_ECHOLNPAIR(" Back: ", m.backlash[BACK]);
#endif
SERIAL_ECHOLNPAIR(" Top: ", m.backlash[TOP]);
SERIAL_EOL(); SERIAL_EOL();
} }
@ -369,7 +402,7 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
#if HAS_Y_CENTER #if HAS_Y_CENTER
SERIAL_ECHOLNPAIR_P(SP_Y_STR, m.pos_error.y); SERIAL_ECHOLNPAIR_P(SP_Y_STR, m.pos_error.y);
#endif #endif
SERIAL_ECHOLNPAIR_P(SP_Z_STR, m.pos_error.z); if (AXIS_CAN_CALIBRATE(Z)) SERIAL_ECHOLNPAIR_P(SP_Z_STR, m.pos_error.z);
SERIAL_EOL(); SERIAL_EOL();
} }
@ -417,6 +450,7 @@ inline void calibrate_backlash(measurements_t &m, const float uncertainty) {
probe_sides(m, uncertainty); probe_sides(m, uncertainty);
#if ENABLED(BACKLASH_GCODE) #if ENABLED(BACKLASH_GCODE)
#if HAS_X_CENTER #if HAS_X_CENTER
backlash.distance_mm.x = (m.backlash[LEFT] + m.backlash[RIGHT]) / 2; backlash.distance_mm.x = (m.backlash[LEFT] + m.backlash[RIGHT]) / 2;
#elif ENABLED(CALIBRATION_MEASURE_LEFT) #elif ENABLED(CALIBRATION_MEASURE_LEFT)
@ -433,18 +467,18 @@ inline void calibrate_backlash(measurements_t &m, const float uncertainty) {
backlash.distance_mm.y = m.backlash[BACK]; backlash.distance_mm.y = m.backlash[BACK];
#endif #endif
backlash.distance_mm.z = m.backlash[TOP]; if (AXIS_CAN_CALIBRATE(Z)) backlash.distance_mm.z = m.backlash[TOP];
#endif #endif
} }
#if ENABLED(BACKLASH_GCODE) #if ENABLED(BACKLASH_GCODE)
// Turn on backlash compensation and move in all // Turn on backlash compensation and move in all
// directions to take up any backlash // allowed directions to take up any backlash
{ {
// New scope for TEMPORARY_BACKLASH_CORRECTION // New scope for TEMPORARY_BACKLASH_CORRECTION
TEMPORARY_BACKLASH_CORRECTION(all_on); TEMPORARY_BACKLASH_CORRECTION(all_on);
TEMPORARY_BACKLASH_SMOOTHING(0.0f); TEMPORARY_BACKLASH_SMOOTHING(0.0f);
const xyz_float_t move = { 3, 3, 3 }; const xyz_float_t move = { AXIS_CAN_CALIBRATE(X) * 3, AXIS_CAN_CALIBRATE(Y) * 3, AXIS_CAN_CALIBRATE(Z) * 3 };
current_position += move; calibration_move(); current_position += move; calibration_move();
current_position -= move; calibration_move(); current_position -= move; calibration_move();
} }
@ -482,26 +516,18 @@ inline void calibrate_toolhead(measurements_t &m, const float uncertainty, const
// Adjust the hotend offset // Adjust the hotend offset
#if HAS_HOTEND_OFFSET #if HAS_HOTEND_OFFSET
#if HAS_X_CENTER if (ENABLED(HAS_X_CENTER) && AXIS_CAN_CALIBRATE(X)) hotend_offset[extruder].x += m.pos_error.x;
hotend_offset[extruder].x += m.pos_error.x; if (ENABLED(HAS_Y_CENTER) && AXIS_CAN_CALIBRATE(Y)) hotend_offset[extruder].y += m.pos_error.y;
#endif if (AXIS_CAN_CALIBRATE(Z)) hotend_offset[extruder].z += m.pos_error.z;
#if HAS_Y_CENTER
hotend_offset[extruder].y += m.pos_error.y;
#endif
hotend_offset[extruder].z += m.pos_error.z;
normalize_hotend_offsets(); normalize_hotend_offsets();
#endif #endif
// Correct for positional error, so the object // Correct for positional error, so the object
// is at the known actual spot // is at the known actual spot
planner.synchronize(); planner.synchronize();
#if HAS_X_CENTER if (ENABLED(HAS_X_CENTER) && AXIS_CAN_CALIBRATE(X)) update_measurements(m, X_AXIS);
update_measurements(m, X_AXIS); if (ENABLED(HAS_Y_CENTER) && AXIS_CAN_CALIBRATE(Y)) update_measurements(m, Y_AXIS);
#endif if (AXIS_CAN_CALIBRATE(Z)) update_measurements(m, Z_AXIS);
#if HAS_Y_CENTER
update_measurements(m, Y_AXIS);
#endif
update_measurements(m, Z_AXIS);
sync_plan_position(); sync_plan_position();
} }

View File

@ -47,7 +47,7 @@ void GcodeSuite::M425() {
bool noArgs = true; bool noArgs = true;
LOOP_XYZ(a) { LOOP_XYZ(a) {
if (parser.seen(XYZ_CHAR(a))) { if (CAN_CALIBRATE(a) && parser.seen(XYZ_CHAR(a))) {
planner.synchronize(); planner.synchronize();
backlash.distance_mm[a] = parser.has_value() ? parser.value_linear_units() : backlash.get_measurement(AxisEnum(a)); backlash.distance_mm[a] = parser.has_value() ? parser.value_linear_units() : backlash.get_measurement(AxisEnum(a));
noArgs = false; noArgs = false;
@ -74,7 +74,7 @@ void GcodeSuite::M425() {
SERIAL_ECHOLNPGM("active:"); SERIAL_ECHOLNPGM("active:");
SERIAL_ECHOLNPAIR(" Correction Amount/Fade-out: F", backlash.get_correction(), " (F1.0 = full, F0.0 = none)"); SERIAL_ECHOLNPAIR(" Correction Amount/Fade-out: F", backlash.get_correction(), " (F1.0 = full, F0.0 = none)");
SERIAL_ECHOPGM(" Backlash Distance (mm): "); SERIAL_ECHOPGM(" Backlash Distance (mm): ");
LOOP_XYZ(a) { LOOP_XYZ(a) if (CAN_CALIBRATE(a)) {
SERIAL_CHAR(' ', XYZ_CHAR(a)); SERIAL_CHAR(' ', XYZ_CHAR(a));
SERIAL_ECHO(backlash.distance_mm[a]); SERIAL_ECHO(backlash.distance_mm[a]);
SERIAL_EOL(); SERIAL_EOL();
@ -87,7 +87,7 @@ void GcodeSuite::M425() {
#if ENABLED(MEASURE_BACKLASH_WHEN_PROBING) #if ENABLED(MEASURE_BACKLASH_WHEN_PROBING)
SERIAL_ECHOPGM(" Average measured backlash (mm):"); SERIAL_ECHOPGM(" Average measured backlash (mm):");
if (backlash.has_any_measurement()) { if (backlash.has_any_measurement()) {
LOOP_XYZ(a) if (backlash.has_measurement(AxisEnum(a))) { LOOP_XYZ(a) if (CAN_CALIBRATE(a) && backlash.has_measurement(AxisEnum(a))) {
SERIAL_CHAR(' ', XYZ_CHAR(a)); SERIAL_CHAR(' ', XYZ_CHAR(a));
SERIAL_ECHO(backlash.get_measurement(AxisEnum(a))); SERIAL_ECHO(backlash.get_measurement(AxisEnum(a)));
} }

View File

@ -67,7 +67,11 @@ inline void toggle_pins() {
else { else {
watchdog_refresh(); watchdog_refresh();
report_pin_state_extended(pin, ignore_protection, true, PSTR("Pulsing ")); report_pin_state_extended(pin, ignore_protection, true, PSTR("Pulsing "));
const bool prior_mode = GET_PINMODE(pin); #ifdef __STM32F1__
const auto prior_mode = _GET_MODE(i);
#else
const bool prior_mode = GET_PINMODE(pin);
#endif
#if AVR_AT90USB1286_FAMILY // Teensy IDEs don't know about these pins so must use FASTIO #if AVR_AT90USB1286_FAMILY // Teensy IDEs don't know about these pins so must use FASTIO
if (pin == TEENSY_E2) { if (pin == TEENSY_E2) {
SET_OUTPUT(TEENSY_E2); SET_OUTPUT(TEENSY_E2);
@ -96,7 +100,11 @@ inline void toggle_pins() {
watchdog_refresh(); watchdog_refresh();
} }
} }
pinMode(pin, prior_mode); #ifdef __STM32F1__
_SET_MODE(i, prior_mode);
#else
pinMode(pin, prior_mode);
#endif
} }
SERIAL_EOL(); SERIAL_EOL();
} }

View File

@ -48,14 +48,8 @@
#ifdef PHOTO_RETRACT_MM #ifdef PHOTO_RETRACT_MM
inline void e_move_m240(const float length, const feedRate_t &fr_mm_s) { inline void e_move_m240(const float length, const feedRate_t &fr_mm_s) {
if (length && thermalManager.hotEnoughToExtrude(active_extruder)) { if (length && thermalManager.hotEnoughToExtrude(active_extruder))
#if ENABLED(ADVANCED_PAUSE_FEATURE) unscaled_e_move(length, fr_mm_s);
do_pause_e_move(length, fr_mm_s);
#else
current_position.e += length / planner.e_factor[active_extruder];
line_to_current_position(fr_mm_s);
#endif
}
} }
#endif #endif

View File

@ -63,7 +63,7 @@ void GcodeSuite::M1000() {
#if HAS_LCD_MENU #if HAS_LCD_MENU
ui.goto_screen(menu_job_recovery); ui.goto_screen(menu_job_recovery);
#elif ENABLED(EXTENSIBLE_UI) #elif ENABLED(EXTENSIBLE_UI)
ExtUI::OnPowerLossResume(); ExtUI::onPowerLossResume();
#else #else
SERIAL_ECHO_MSG("Resume requires LCD."); SERIAL_ECHO_MSG("Resume requires LCD.");
#endif #endif

View File

@ -857,7 +857,11 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) {
#if ENABLED(POWER_LOSS_RECOVERY) #if ENABLED(POWER_LOSS_RECOVERY)
case 413: M413(); break; // M413: Enable/disable/query Power-Loss Recovery case 413: M413(); break; // M413: Enable/disable/query Power-Loss Recovery
case 1000: M1000(); break; // M1000: Resume from power-loss case 1000: M1000(); break; // M1000: [INTERNAL] Resume from power-loss
#endif
#if ENABLED(SDSUPPORT)
case 1001: M1001(); break; // M1001: [INTERNAL] Handle SD completion
#endif #endif
#if ENABLED(MAX7219_GCODE) #if ENABLED(MAX7219_GCODE)

View File

@ -968,6 +968,10 @@ private:
static void M1000(); static void M1000();
#endif #endif
#if ENABLED(SDSUPPORT)
static void M1001();
#endif
#if ENABLED(MAX7219_GCODE) #if ENABLED(MAX7219_GCODE)
static void M7219(); static void M7219();
#endif #endif

View File

@ -24,23 +24,19 @@
#if HAS_RESUME_CONTINUE #if HAS_RESUME_CONTINUE
#include "../gcode.h"
#include "../../module/planner.h"
#include "../../inc/MarlinConfig.h" #include "../../inc/MarlinConfig.h"
#include "../gcode.h"
#include "../../module/planner.h" // for synchronize()
#include "../../MarlinCore.h" // for wait_for_user_response()
#if HAS_LCD_MENU #if HAS_LCD_MENU
#include "../../lcd/ultralcd.h" #include "../../lcd/ultralcd.h"
#endif #elif ENABLED(EXTENSIBLE_UI)
#if ENABLED(EXTENSIBLE_UI)
#include "../../lcd/extui/ui_api.h" #include "../../lcd/extui/ui_api.h"
#endif #endif
#if HAS_LEDS_OFF_FLAG
#include "../../feature/leds/printer_event_leds.h"
#endif
#if ENABLED(HOST_PROMPT_SUPPORT) #if ENABLED(HOST_PROMPT_SUPPORT)
#include "../../feature/host_actions.h" #include "../../feature/host_actions.h"
#endif #endif
@ -56,16 +52,11 @@ void GcodeSuite::M0_M1() {
planner.synchronize(); planner.synchronize();
const bool seenQ = parser.seen('Q');
#if HAS_LEDS_OFF_FLAG
if (seenQ) printerEventLEDs.onPrintCompleted(); // Change LED color for Print Completed
#endif
#if HAS_LCD_MENU #if HAS_LCD_MENU
if (parser.string_arg) if (parser.string_arg)
ui.set_status(parser.string_arg, true); ui.set_status(parser.string_arg, true);
else if (!seenQ) { else {
LCD_MESSAGEPGM(MSG_USERWAIT); LCD_MESSAGEPGM(MSG_USERWAIT);
#if ENABLED(LCD_PROGRESS_BAR) && PROGRESS_MSG_EXPIRE > 0 #if ENABLED(LCD_PROGRESS_BAR) && PROGRESS_MSG_EXPIRE > 0
ui.reset_progress_bar_timeout(); ui.reset_progress_bar_timeout();
@ -73,12 +64,10 @@ void GcodeSuite::M0_M1() {
} }
#elif ENABLED(EXTENSIBLE_UI) #elif ENABLED(EXTENSIBLE_UI)
if (parser.string_arg) if (parser.string_arg)
ExtUI::onUserConfirmRequired(parser.string_arg); // Can this take an SRAM string?? ExtUI::onUserConfirmRequired(parser.string_arg); // Can this take an SRAM string??
else else
ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_USERWAIT)); ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_USERWAIT));
#else #else
if (parser.string_arg) { if (parser.string_arg) {
@ -88,25 +77,15 @@ void GcodeSuite::M0_M1() {
#endif #endif
KEEPALIVE_STATE(PAUSED_FOR_USER);
wait_for_user = true;
#if ENABLED(HOST_PROMPT_SUPPORT) #if ENABLED(HOST_PROMPT_SUPPORT)
host_prompt_do(PROMPT_USER_CONTINUE, parser.codenum ? PSTR("M1 Stop") : PSTR("M0 Stop"), CONTINUE_STR); host_prompt_do(PROMPT_USER_CONTINUE, parser.codenum ? PSTR("M1 Stop") : PSTR("M0 Stop"), CONTINUE_STR);
#endif #endif
if (ms > 0) ms += millis(); // wait until this time for a click wait_for_user_response(ms);
while (wait_for_user && (ms == 0 || PENDING(millis(), ms))) idle();
#if HAS_LEDS_OFF_FLAG
printerEventLEDs.onResumeAfterWait();
#endif
#if HAS_LCD_MENU #if HAS_LCD_MENU
if (!seenQ) ui.reset_status(); ui.reset_status();
#endif #endif
wait_for_user = false;
} }
#endif // HAS_RESUME_CONTINUE #endif // HAS_RESUME_CONTINUE

View File

@ -236,7 +236,7 @@ void plan_arc(
planner.apply_leveling(raw); planner.apply_leveling(raw);
#endif #endif
planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, seg_length planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, 0
#if ENABLED(SCARA_FEEDRATE_SCALING) #if ENABLED(SCARA_FEEDRATE_SCALING)
, inv_duration , inv_duration
#endif #endif

View File

@ -0,0 +1,109 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#include "../../inc/MarlinConfig.h"
#if ENABLED(SDSUPPORT)
#include "../gcode.h"
#include "../../module/printcounter.h"
#if EITHER(LCD_SET_PROGRESS_MANUALLY, SD_REPRINT_LAST_SELECTED_FILE)
#include "../../lcd/ultralcd.h"
#endif
#if ENABLED(POWER_LOSS_RECOVERY)
#include "../../feature/powerloss.h"
#endif
#if HAS_LEDS_OFF_FLAG
#include "../../feature/leds/printer_event_leds.h"
#endif
#if ENABLED(EXTENSIBLE_UI)
#include "../../lcd/extui/ui_api.h"
#endif
#if ENABLED(HOST_ACTION_COMMANDS)
#include "../../feature/host_actions.h"
#endif
#if ENABLED(SD_FINISHED_STEPPERRELEASE) && defined(SD_FINISHED_RELEASECOMMAND)
#include "../../module/planner.h"
#endif
#ifndef PE_LEDS_COMPLETED_TIME
#define PE_LEDS_COMPLETED_TIME (30*60)
#endif
/**
* M1001: Execute actions for SD print completion
*/
void GcodeSuite::M1001() {
// Report total print time
const bool long_print = print_job_timer.duration() > 60;
if (long_print) gcode.process_subcommands_now_P(PSTR("M31"));
// Stop the print job timer
gcode.process_subcommands_now_P(PSTR("M77"));
// Set the progress bar "done" state
#if ENABLED(LCD_SET_PROGRESS_MANUALLY)
ui.set_progress_done();
#endif
// Purge the recovery file
#if ENABLED(POWER_LOSS_RECOVERY)
recovery.purge();
#endif
// Announce SD file completion
SERIAL_ECHOLNPGM(STR_FILE_PRINTED);
// Update the status LED color
#if HAS_LEDS_OFF_FLAG
if (long_print) {
printerEventLEDs.onPrintCompleted();
#if ENABLED(EXTENSIBLE_UI)
ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_PRINT_DONE));
#endif
#if ENABLED(HOST_PROMPT_SUPPORT)
host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT(MSG_PRINT_DONE), CONTINUE_STR);
#endif
wait_for_user_response(1000UL * TERN(HAS_LCD_MENU, PE_LEDS_COMPLETED_TIME, 30));
printerEventLEDs.onResumeAfterWait();
}
#endif
// Wait for the queue to empty (and "clean"), inject SD_FINISHED_RELEASECOMMAND
#if ENABLED(SD_FINISHED_STEPPERRELEASE) && defined(SD_FINISHED_RELEASECOMMAND)
planner.finish_and_disable();
#endif
// Re-select the last printed file in the UI
#if ENABLED(SD_REPRINT_LAST_SELECTED_FILE)
ui.reselect_last_file();
#endif
}
#endif // SDSUPPORT

View File

@ -34,12 +34,31 @@
/** /**
* M303: PID relay autotune * M303: PID relay autotune
* *
* S<temperature> sets the target temperature. (default 150C / 70C) * S<temperature> Set the target temperature. (Default: 150C / 70C)
* E<extruder> (-1 for the bed) (default 0) * E<extruder> Extruder number to tune, or -1 for the bed. (Default: E0)
* C<cycles> Minimum 3. Default 5. * C<cycles> Number of times to repeat the procedure. (Minimum: 3, Default: 5)
* U<bool> with a non-zero value will apply the result to current settings * U<bool> Flag to apply the result to the current PID values
*
* With PID_DEBUG:
* D Toggle PID debugging and EXIT without further action.
*/ */
#if ENABLED(PID_DEBUG)
bool pid_debug_flag = 0;
#endif
void GcodeSuite::M303() { void GcodeSuite::M303() {
#if ENABLED(PID_DEBUG)
if (parser.seen('D')) {
pid_debug_flag = !pid_debug_flag;
SERIAL_ECHO_START();
SERIAL_ECHOPGM("PID Debug ");
serialprintln_onoff(pid_debug_flag);
return;
}
#endif
#if ENABLED(PIDTEMPBED) #if ENABLED(PIDTEMPBED)
#define SI H_BED #define SI H_BED
#else #else
@ -54,7 +73,7 @@ void GcodeSuite::M303() {
if (!WITHIN(e, SI, EI)) { if (!WITHIN(e, SI, EI)) {
SERIAL_ECHOLNPGM(STR_PID_BAD_EXTRUDER_NUM); SERIAL_ECHOLNPGM(STR_PID_BAD_EXTRUDER_NUM);
#if ENABLED(EXTENSIBLE_UI) #if ENABLED(EXTENSIBLE_UI)
ExtUI::OnPidTuning(ExtUI::result_t::PID_BAD_EXTRUDER_NUM); ExtUI::onPidTuning(ExtUI::result_t::PID_BAD_EXTRUDER_NUM);
#endif #endif
return; return;
} }

View File

@ -93,7 +93,7 @@
#if EITHER(MIN_SOFTWARE_ENDSTOPS, MAX_SOFTWARE_ENDSTOPS) #if EITHER(MIN_SOFTWARE_ENDSTOPS, MAX_SOFTWARE_ENDSTOPS)
#define HAS_SOFTWARE_ENDSTOPS 1 #define HAS_SOFTWARE_ENDSTOPS 1
#endif #endif
#if ANY(EXTENSIBLE_UI, NEWPANEL, EMERGENCY_PARSER) #if ANY(EXTENSIBLE_UI, NEWPANEL, EMERGENCY_PARSER, HAS_ADC_BUTTONS)
#define HAS_RESUME_CONTINUE 1 #define HAS_RESUME_CONTINUE 1
#endif #endif

View File

@ -35,16 +35,19 @@
#define HAS_LINEAR_E_JERK 1 #define HAS_LINEAR_E_JERK 1
#endif #endif
// If no real EEPROM, Flash emulation, or SRAM emulation is available fall back to SD emulation // Determine which type of 'EEPROM' is in use
#if ENABLED(EEPROM_SETTINGS) #if ENABLED(EEPROM_SETTINGS)
#if NONE(FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) && EITHER(I2C_EEPROM, SPI_EEPROM) // EEPROM type may be defined by compile flags, configs, HALs, or pins
#define USE_REAL_EEPROM 1 // Set additional flags to let HALs choose in their Conditionals_post.h
#if NONE(FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) && ANY(I2C_EEPROM, SPI_EEPROM, QSPI_EEPROM)
#define USE_WIRED_EEPROM 1
#else #else
#define USE_EMULATED_EEPROM 1 #define USE_FALLBACK_EEPROM 1
#endif #endif
#else #else
#undef I2C_EEPROM #undef I2C_EEPROM
#undef SPI_EEPROM #undef SPI_EEPROM
#undef QSPI_EEPROM
#undef SDCARD_EEPROM_EMULATION #undef SDCARD_EEPROM_EMULATION
#undef SRAM_EEPROM_EMULATION #undef SRAM_EEPROM_EMULATION
#undef FLASH_EEPROM_EMULATION #undef FLASH_EEPROM_EMULATION
@ -136,6 +139,19 @@
#define CORESIGN(n) (ANY(COREYX, COREZX, COREZY) ? (-(n)) : (n)) #define CORESIGN(n) (ANY(COREYX, COREZX, COREZY) ? (-(n)) : (n))
#endif #endif
// Calibration codes only for non-core axes
#if EITHER(BACKLASH_GCODE, CALIBRATION_GCODE)
#if IS_CORE
#define X_AXIS_INDEX 0
#define Y_AXIS_INDEX 1
#define Z_AXIS_INDEX 2
#define CAN_CALIBRATE(A,B) (A##_AXIS_INDEX == B##_INDEX)
#else
#define CAN_CALIBRATE(...) 1
#endif
#endif
#define AXIS_CAN_CALIBRATE(A) CAN_CALIBRATE(A,NORMAL_AXIS)
/** /**
* No adjustable bed on non-cartesians * No adjustable bed on non-cartesians
*/ */

View File

@ -35,11 +35,12 @@
#include "Conditionals_post.h" #include "Conditionals_post.h"
#include HAL_PATH(../HAL, inc/Conditionals_post.h) #include HAL_PATH(../HAL, inc/Conditionals_post.h)
#include "../core/types.h" // Ahead of sanity-checks
#include "SanityCheck.h" #include "SanityCheck.h"
#include HAL_PATH(../HAL, inc/SanityCheck.h) #include HAL_PATH(../HAL, inc/SanityCheck.h)
// Include all core headers // Include all core headers
#include "../core/types.h"
#include "../core/language.h" #include "../core/language.h"
#include "../core/utility.h" #include "../core/utility.h"
#include "../core/serial.h" #include "../core/serial.h"

View File

@ -42,7 +42,7 @@
* version was tagged. * version was tagged.
*/ */
#ifndef STRING_DISTRIBUTION_DATE #ifndef STRING_DISTRIBUTION_DATE
#define STRING_DISTRIBUTION_DATE "2020-03-24" #define STRING_DISTRIBUTION_DATE "2020-03-31"
#endif #endif
/** /**

View File

@ -38,6 +38,11 @@ namespace FTDI {
SET_OUTPUT(CLCD_SPI_CS); SET_OUTPUT(CLCD_SPI_CS);
WRITE(CLCD_SPI_CS, 1); WRITE(CLCD_SPI_CS, 1);
#ifdef CLCD_SPI_EXTRA_CS
SET_OUTPUT(CLCD_SPI_EXTRA_CS);
WRITE(CLCD_SPI_EXTRA_CS, 1);
#endif
#ifdef SPI_FLASH_SS #ifdef SPI_FLASH_SS
SET_OUTPUT(SPI_FLASH_SS); SET_OUTPUT(SPI_FLASH_SS);
WRITE(SPI_FLASH_SS, 1); WRITE(SPI_FLASH_SS, 1);
@ -111,12 +116,18 @@ namespace FTDI {
::SPI.beginTransaction(spi_settings); ::SPI.beginTransaction(spi_settings);
#endif #endif
WRITE(CLCD_SPI_CS, 0); WRITE(CLCD_SPI_CS, 0);
#ifdef CLCD_SPI_EXTRA_CS
WRITE(CLCD_SPI_EXTRA_CS, 0);
#endif
delayMicroseconds(1); delayMicroseconds(1);
} }
// CLCD SPI - Chip Deselect // CLCD SPI - Chip Deselect
void SPI::spi_ftdi_deselect() { void SPI::spi_ftdi_deselect() {
WRITE(CLCD_SPI_CS, 1); WRITE(CLCD_SPI_CS, 1);
#ifdef CLCD_SPI_EXTRA_CS
WRITE(CLCD_SPI_EXTRA_CS, 1);
#endif
#ifndef CLCD_USE_SOFT_SPI #ifndef CLCD_USE_SOFT_SPI
::SPI.endTransaction(); ::SPI.endTransaction();
#endif #endif

View File

@ -176,11 +176,12 @@
#undef MAKE_ARDUINO_PINS #undef MAKE_ARDUINO_PINS
} // namespace fast_io } // namespace fast_io
#define SET_INPUT(pin) fast_io::pin::set_input() #define SET_INPUT(pin) fast_io::pin::set_input()
#define SET_INPUT_PULLUP(pin) fast_io::pin::set_input(); fast_io::pin::set_high() #define SET_INPUT_PULLUP(pin) do{ fast_io::pin::set_input(); fast_io::pin::set_high(); }while(0)
#define SET_OUTPUT(pin) fast_io::pin::set_output() #define SET_INPUT_PULLDOWN SET_INPUT
#define READ(pin) fast_io::pin::read() #define SET_OUTPUT(pin) fast_io::pin::set_output()
#define WRITE(pin, value) fast_io::pin::write(value) #define READ(pin) fast_io::pin::read()
#define WRITE(pin, value) fast_io::pin::write(value)
#ifndef pgm_read_word_far #ifndef pgm_read_word_far
#define pgm_read_word_far pgm_read_word #define pgm_read_word_far pgm_read_word
@ -195,11 +196,11 @@
#endif #endif
#define SERIAL_ECHO_START() #define SERIAL_ECHO_START()
#define SERIAL_ECHOLNPGM(str) Serial.println(F(str)) #define SERIAL_ECHOLNPGM(str) Serial.println(F(str))
#define SERIAL_ECHOPGM(str) Serial.print(F(str)) #define SERIAL_ECHOPGM(str) Serial.print(F(str))
#define SERIAL_ECHO_MSG(str) Serial.println(str) #define SERIAL_ECHO_MSG(str) Serial.println(str)
#define SERIAL_ECHOLNPAIR(str, val) {Serial.print(F(str)); Serial.println(val);} #define SERIAL_ECHOLNPAIR(str, val) do{ Serial.print(F(str)); Serial.println(val); }while(0)
#define SERIAL_ECHOPAIR(str, val) {Serial.print(F(str)); Serial.print(val);} #define SERIAL_ECHOPAIR(str, val) do{ Serial.print(F(str)); Serial.print(val); }while(0)
#define safe_delay delay #define safe_delay delay

View File

@ -191,7 +191,7 @@ namespace FTDI {
#if ENABLED(TOUCH_UI_DEBUG) #if ENABLED(TOUCH_UI_DEBUG)
SERIAL_ECHO_START(); SERIAL_ECHO_START();
SERIAL_ECHOLNPAIR("Touch end: ", tag); SERIAL_ECHOLNPAIR("Touch end: ", pressed_tag);
#endif #endif
const uint8_t saved_pressed_tag = pressed_tag; const uint8_t saved_pressed_tag = pressed_tag;

View File

@ -70,13 +70,15 @@ namespace Language_en {
PROGMEM Language_Str MSG_PRINT_FINISHED = u8"Print finished"; PROGMEM Language_Str MSG_PRINT_FINISHED = u8"Print finished";
PROGMEM Language_Str MSG_PRINT_ERROR = u8"Print error"; PROGMEM Language_Str MSG_PRINT_ERROR = u8"Print error";
PROGMEM Language_Str MSG_ABOUT_TOUCH_PANEL_1 = u8"Color Touch Panel"; PROGMEM Language_Str MSG_ABOUT_TOUCH_PANEL_1 = u8"Color Touch Panel";
PROGMEM Language_Str MSG_ABOUT_TOUCH_PANEL_2 = u8"Portions " COPYRIGHT_SIGN " 2019 Aleph Objects, Inc.\n" PROGMEM Language_Str MSG_ABOUT_TOUCH_PANEL_2 = WEBSITE_URL;
"Portions " COPYRIGHT_SIGN " 2019 Cocoa Press"; PROGMEM Language_Str MSG_LICENSE = u8"This program is free software: you can redistribute it and/or modify it under the terms of "
PROGMEM Language_Str MSG_FIRMWARE_FOR_TOOLHEAD = u8"Firmware for toolhead:\n%s\n\n"; "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.\n\nTo view a copy of the GNU General "
"Public License, go to the following location: http://www.gnu.org/licenses.";
PROGMEM Language_Str MSG_RUNOUT_1 = u8"Runout 1"; PROGMEM Language_Str MSG_RUNOUT_1 = u8"Runout 1";
PROGMEM Language_Str MSG_RUNOUT_2 = u8"Runout 2"; PROGMEM Language_Str MSG_RUNOUT_2 = u8"Runout 2";
PROGMEM Language_Str MSG_DISPLAY_MENU = u8"Display"; PROGMEM Language_Str MSG_DISPLAY_MENU = u8"Display";
PROGMEM Language_Str MSG_INTERFACE_SETTINGS = u8"Interface Settings"; PROGMEM Language_Str MSG_INTERFACE = u8"Interface";
PROGMEM Language_Str MSG_MEASURE_AUTOMATICALLY = u8"Measure automatically"; PROGMEM Language_Str MSG_MEASURE_AUTOMATICALLY = u8"Measure automatically";
PROGMEM Language_Str MSG_H_OFFSET = u8"H Offset"; PROGMEM Language_Str MSG_H_OFFSET = u8"H Offset";
PROGMEM Language_Str MSG_V_OFFSET = u8"V Offset"; PROGMEM Language_Str MSG_V_OFFSET = u8"V Offset";
@ -129,7 +131,7 @@ namespace Language_en {
PROGMEM Language_Str MSG_SOUND_VOLUME = u8"Sound volume"; PROGMEM Language_Str MSG_SOUND_VOLUME = u8"Sound volume";
PROGMEM Language_Str MSG_SCREEN_LOCK = u8"Screen lock"; PROGMEM Language_Str MSG_SCREEN_LOCK = u8"Screen lock";
PROGMEM Language_Str MSG_BOOT_SCREEN = u8"Boot screen"; PROGMEM Language_Str MSG_BOOT_SCREEN = u8"Boot screen";
PROGMEM Language_Str MSG_INTERFACE_SOUNDS = u8"Interface Sounds"; PROGMEM Language_Str MSG_SOUNDS = u8"Sounds";
PROGMEM Language_Str MSG_CLICK_SOUNDS = u8"Click sounds"; PROGMEM Language_Str MSG_CLICK_SOUNDS = u8"Click sounds";
PROGMEM Language_Str MSG_EEPROM_RESTORED = u8"Settings restored from backup"; PROGMEM Language_Str MSG_EEPROM_RESTORED = u8"Settings restored from backup";
PROGMEM Language_Str MSG_EEPROM_RESET = u8"Settings restored to default"; PROGMEM Language_Str MSG_EEPROM_RESET = u8"Settings restored to default";
@ -144,12 +146,12 @@ namespace Language_en {
PROGMEM Language_Str MSG_TOUCH_CALIBRATION_START = u8"Release to begin screen calibration"; PROGMEM Language_Str MSG_TOUCH_CALIBRATION_START = u8"Release to begin screen calibration";
PROGMEM Language_Str MSG_TOUCH_CALIBRATION_PROMPT = u8"Touch the dots to calibrate"; PROGMEM Language_Str MSG_TOUCH_CALIBRATION_PROMPT = u8"Touch the dots to calibrate";
PROGMEM Language_Str MSG_AUTOLEVEL_X_AXIS = u8"Level X Axis";
#ifdef TOUCH_UI_LULZBOT_BIO #ifdef TOUCH_UI_LULZBOT_BIO
PROGMEM Language_Str MSG_MOVE_TO_HOME = u8"Move to Home"; PROGMEM Language_Str MSG_MOVE_TO_HOME = u8"Move to Home";
PROGMEM Language_Str MSG_RAISE_PLUNGER = u8"Raise Plunger"; PROGMEM Language_Str MSG_RAISE_PLUNGER = u8"Raise Plunger";
PROGMEM Language_Str MSG_RELEASE_XY_AXIS = u8"Release X and Y Axis"; PROGMEM Language_Str MSG_RELEASE_XY_AXIS = u8"Release X and Y Axis";
PROGMEM Language_Str MSG_AUTOLEVEL_X_AXIS = u8"Auto-level X Axis";
PROGMEM Language_Str MSG_BED_TEMPERATURE = u8"Bed Temperature"; PROGMEM Language_Str MSG_BED_TEMPERATURE = u8"Bed Temperature";
PROGMEM Language_Str MSG_HOME_XYZ_WARNING = u8"About to move to home position. Ensure the top and the bed of the printer are clear.\n\nContinue?"; PROGMEM Language_Str MSG_HOME_XYZ_WARNING = u8"About to move to home position. Ensure the top and the bed of the printer are clear.\n\nContinue?";
PROGMEM Language_Str MSG_HOME_E_WARNING = u8"About to re-home plunger and auto-level. Remove syringe prior to proceeding.\n\nContinue?"; PROGMEM Language_Str MSG_HOME_E_WARNING = u8"About to re-home plunger and auto-level. Remove syringe prior to proceeding.\n\nContinue?";

View File

@ -131,8 +131,14 @@ namespace ExtUI {
} }
#endif #endif
#if ENABLED(POWER_LOSS_RECOVERY)
void onPowerLossResume() {
// Called on resume from power-loss
}
#endif
#if HAS_PID_HEATING #if HAS_PID_HEATING
void OnPidTuning(const result_t rst) { void onPidTuning(const result_t rst) {
// Called for temperature PID tuning result // Called for temperature PID tuning result
SERIAL_ECHOLNPAIR("OnPidTuning:", rst); SERIAL_ECHOLNPAIR("OnPidTuning:", rst);
switch (rst) { switch (rst) {

View File

@ -129,12 +129,13 @@
* 9 GND GND GND --> GND * 9 GND GND GND --> GND
* 10 5V 5V 5V --> KILL [3] * 10 5V 5V 5V --> KILL [3]
* *
* [1] This configuration is not compatible with the * [1] This configuration allows daisy-chaining of the
* EinsyRetro 1.1a because there is a level shifter * display and SD/USB on EXP2, except for [2]
* on MISO enabled by SD/USB chip select.
* *
* [2] This configuration allows daisy-chaining of the * [2] The Ultimachine Einsy boards have a level shifter
* display and SD/USB on EXP2. * on MISO enabled by SD_CSEL chip select, hence it
* is not possible to run both the display and the
* SD/USB on EXP2.
* *
* [3] Archim Rambo provides 5V on this pin. On any other * [3] Archim Rambo provides 5V on this pin. On any other
* board, divert this wire from the ribbon cable and * board, divert this wire from the ribbon cable and
@ -148,4 +149,8 @@
#define CLCD_SPI_CS BTN_EN1 #define CLCD_SPI_CS BTN_EN1
#define CLCD_MOD_RESET BTN_EN2 #define CLCD_MOD_RESET BTN_EN2
#if MB(EINSY_RAMBO, EINSY_RETRO) && DISABLED(SDSUPPORT)
#define CLCD_SPI_EXTRA_CS SDSS
#endif
#endif #endif

View File

@ -27,7 +27,7 @@
#include "screens.h" #include "screens.h"
#define GRID_COLS 4 #define GRID_COLS 4
#define GRID_ROWS 9 #define GRID_ROWS 7
using namespace FTDI; using namespace FTDI;
using namespace Theme; using namespace Theme;
@ -45,7 +45,32 @@ void AboutScreen::onRedraw(draw_mode_t) {
.cmd(COLOR_RGB(bg_text_enabled)) .cmd(COLOR_RGB(bg_text_enabled))
.tag(0); .tag(0);
draw_text_box(cmd, BTN_POS(1,2), BTN_SIZE(4,1), #define HEADING_POS BTN_POS(1,2), BTN_SIZE(4,1)
#define FW_VERS_POS BTN_POS(1,3), BTN_SIZE(4,1)
#define FW_INFO_POS BTN_POS(1,4), BTN_SIZE(4,1)
#define LICENSE_POS BTN_POS(1,5), BTN_SIZE(4,2)
#define STATS_POS BTN_POS(1,7), BTN_SIZE(2,1)
#define BACK_POS BTN_POS(3,7), BTN_SIZE(2,1)
#define _INSET_POS(x,y,w,h) x + w/10, y, w - w/5, h
#define INSET_POS(pos) _INSET_POS(pos)
char about_str[
strlen_P(GET_TEXT(MSG_ABOUT_TOUCH_PANEL_2)) +
strlen_P(TOOLHEAD_NAME) + 1
];
#ifdef TOOLHEAD_NAME
// If MSG_ABOUT_TOUCH_PANEL_2 has %s, substitute in the toolhead name.
// But this is optional, so squelch the compiler warning here.
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wformat-extra-args"
sprintf_P(about_str, GET_TEXT(MSG_ABOUT_TOUCH_PANEL_2), TOOLHEAD_NAME);
#pragma GCC diagnostic pop
#else
strcpy_P(about_str, GET_TEXT(MSG_ABOUT_TOUCH_PANEL_2));
#endif
draw_text_box(cmd, HEADING_POS,
#ifdef CUSTOM_MACHINE_NAME #ifdef CUSTOM_MACHINE_NAME
F(CUSTOM_MACHINE_NAME) F(CUSTOM_MACHINE_NAME)
#else #else
@ -53,42 +78,29 @@ void AboutScreen::onRedraw(draw_mode_t) {
#endif #endif
, OPT_CENTER, font_xlarge , OPT_CENTER, font_xlarge
); );
draw_text_box(cmd, FW_VERS_POS, progmem_str(getFirmwareName_str()), OPT_CENTER, font_medium);
draw_text_box(cmd, FW_INFO_POS, about_str, OPT_CENTER, font_medium);
draw_text_box(cmd, INSET_POS(LICENSE_POS), GET_TEXT_F(MSG_LICENSE), OPT_CENTER, font_tiny);
#ifdef TOOLHEAD_NAME cmd.font(font_medium)
char about_str[ .colors(normal_btn)
strlen_P(GET_TEXT(FIRMWARE_FOR_TOOLHEAD)) + .tag(2).button(STATS_POS, GET_TEXT_F(MSG_INFO_STATS_MENU))
strlen_P(TOOLHEAD_NAME) + .colors(action_btn)
strlen_P(GET_TEXT(MSG_ABOUT_TOUCH_PANEL_2)) + 1 .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BACK));
];
sprintf_P(about_str, GET_TEXT(MSG_FIRMWARE_FOR_TOOLHEAD), TOOLHEAD_NAME);
strcat_P (about_str, GET_TEXT(MSG_ABOUT_TOUCH_PANEL_2));
#endif
cmd.tag(2);
draw_text_box(cmd, BTN_POS(1,3), BTN_SIZE(4,3),
#ifdef TOOLHEAD_NAME
about_str
#else
GET_TEXT_F(MSG_ABOUT_TOUCH_PANEL_2)
#endif
, OPT_CENTER, font_medium
);
cmd.tag(0);
draw_text_box(cmd, BTN_POS(1,6), BTN_SIZE(4,2), progmem_str(getFirmwareName_str()), OPT_CENTER, font_medium);
cmd.font(font_medium).colors(action_btn).tag(1).button(BTN_POS(2,8), BTN_SIZE(2,1), GET_TEXT_F(MSG_BUTTON_OKAY));
} }
bool AboutScreen::onTouchEnd(uint8_t tag) { bool AboutScreen::onTouchEnd(uint8_t tag) {
switch (tag) { switch (tag) {
case 1: GOTO_PREVIOUS(); return true; case 1: GOTO_PREVIOUS(); break;
#if ENABLED(TOUCH_UI_DEVELOPER_MENU) #if ENABLED(PRINTCOUNTER)
case 2: GOTO_SCREEN(DeveloperMenu); return true; case 2: GOTO_SCREEN(StatisticsScreen); break;
#endif #endif
default: return false; #if ENABLED(TOUCH_UI_DEVELOPER_MENU)
case 3: GOTO_SCREEN(DeveloperMenu); break;
#endif
default: return false;
} }
return true;
} }
#endif // TOUCH_UI_FTDI_EVE #endif // TOUCH_UI_FTDI_EVE

View File

@ -37,127 +37,116 @@ void AdvancedSettingsMenu::onRedraw(draw_mode_t what) {
.cmd(CLEAR(true,true,true)); .cmd(CLEAR(true,true,true));
} }
#ifdef TOUCH_UI_PORTRAIT
#if HAS_CASE_LIGHT || ENABLED(SENSORLESS_HOMING)
#define GRID_ROWS 9
#else
#define GRID_ROWS 8
#endif
#define GRID_COLS 2
#define RESTORE_DEFAULTS_POS BTN_POS(1,1), BTN_SIZE(2,1)
#define DISPLAY_POS BTN_POS(1,2), BTN_SIZE(1,1)
#define INTERFACE_POS BTN_POS(2,2), BTN_SIZE(1,1)
#define ZPROBE_ZOFFSET_POS BTN_POS(1,3), BTN_SIZE(1,1)
#define STEPS_PER_MM_POS BTN_POS(2,3), BTN_SIZE(1,1)
#define FILAMENT_POS BTN_POS(1,4), BTN_SIZE(1,1)
#define VELOCITY_POS BTN_POS(2,4), BTN_SIZE(1,1)
#define TMC_CURRENT_POS BTN_POS(1,5), BTN_SIZE(1,1)
#define ACCELERATION_POS BTN_POS(2,5), BTN_SIZE(1,1)
#define ENDSTOPS_POS BTN_POS(1,6), BTN_SIZE(1,1)
#define JERK_POS BTN_POS(2,6), BTN_SIZE(1,1)
#define OFFSETS_POS BTN_POS(1,7), BTN_SIZE(1,1)
#define BACKLASH_POS BTN_POS(2,7), BTN_SIZE(1,1)
#define CASE_LIGHT_POS BTN_POS(1,8), BTN_SIZE(1,1)
#define TMC_HOMING_THRS_POS BTN_POS(2,8), BTN_SIZE(1,1)
#if HAS_CASE_LIGHT || ENABLED(SENSORLESS_HOMING)
#define BACK_POS BTN_POS(1,9), BTN_SIZE(2,1)
#else
#define BACK_POS BTN_POS(1,8), BTN_SIZE(2,1)
#endif
#else
#define GRID_ROWS 6
#define GRID_COLS 3
#define ZPROBE_ZOFFSET_POS BTN_POS(1,1), BTN_SIZE(1,1)
#define CASE_LIGHT_POS BTN_POS(1,4), BTN_SIZE(1,1)
#define STEPS_PER_MM_POS BTN_POS(2,1), BTN_SIZE(1,1)
#define TMC_CURRENT_POS BTN_POS(3,1), BTN_SIZE(1,1)
#define TMC_HOMING_THRS_POS BTN_POS(3,2), BTN_SIZE(1,1)
#define BACKLASH_POS BTN_POS(3,3), BTN_SIZE(1,1)
#define FILAMENT_POS BTN_POS(1,3), BTN_SIZE(1,1)
#define ENDSTOPS_POS BTN_POS(3,4), BTN_SIZE(1,1)
#define DISPLAY_POS BTN_POS(3,5), BTN_SIZE(1,1)
#define INTERFACE_POS BTN_POS(1,5), BTN_SIZE(2,1)
#define RESTORE_DEFAULTS_POS BTN_POS(1,6), BTN_SIZE(2,1)
#define VELOCITY_POS BTN_POS(2,2), BTN_SIZE(1,1)
#define ACCELERATION_POS BTN_POS(2,3), BTN_SIZE(1,1)
#define JERK_POS BTN_POS(2,4), BTN_SIZE(1,1)
#define OFFSETS_POS BTN_POS(1,2), BTN_SIZE(1,1)
#define BACK_POS BTN_POS(3,6), BTN_SIZE(1,1)
#endif
if (what & FOREGROUND) { if (what & FOREGROUND) {
CommandProcessor cmd; CommandProcessor cmd;
cmd.colors(normal_btn) cmd.colors(normal_btn)
.font(Theme::font_medium) .font(Theme::font_medium)
#ifdef TOUCH_UI_PORTRAIT
#define GRID_ROWS 10
#define GRID_COLS 2
.enabled( .enabled(
#if HAS_BED_PROBE #if HAS_BED_PROBE
1 1
#endif #endif
) )
.tag(2) .button( BTN_POS(1,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_ZPROBE_ZOFFSET)) .tag(2) .button( ZPROBE_ZOFFSET_POS, GET_TEXT_F(MSG_ZPROBE_ZOFFSET))
.enabled( .enabled(
#if HAS_CASE_LIGHT #if HAS_CASE_LIGHT
1 1
#endif #endif
) )
.tag(16).button( BTN_POS(1,6), BTN_SIZE(1,1), GET_TEXT_F(MSG_CASE_LIGHT)) .tag(16).button( CASE_LIGHT_POS, GET_TEXT_F(MSG_CASE_LIGHT))
.tag(3) .button( BTN_POS(2,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_STEPS_PER_MM)) .tag(3) .button( STEPS_PER_MM_POS, GET_TEXT_F(MSG_STEPS_PER_MM))
.enabled( .enabled(
#if HAS_TRINAMIC_CONFIG #if HAS_TRINAMIC_CONFIG
1 1
#endif #endif
) )
.tag(13).button( BTN_POS(1,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_TMC_CURRENT)) .tag(13).button( TMC_CURRENT_POS, GET_TEXT_F(MSG_TMC_CURRENT))
.enabled( .enabled(
#if HAS_TRINAMIC_CONFIG #if ENABLED(SENSORLESS_HOMING)
1 1
#endif #endif
) )
.tag(14).button( BTN_POS(1,7), BTN_SIZE(2,1), GET_TEXT_F(MSG_TMC_HOMING_THRS)) .tag(14).button( TMC_HOMING_THRS_POS, GET_TEXT_F(MSG_TMC_HOMING_THRS))
.enabled( .enabled(
#if HOTENDS > 1 #if HOTENDS > 1
1 1
#endif #endif
) )
.tag(4) .button( BTN_POS(1,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_OFFSETS_MENU)) .tag(4) .button( OFFSETS_POS, GET_TEXT_F(MSG_OFFSETS_MENU))
.enabled( .enabled(
#if EITHER(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR) #if EITHER(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR)
1 1
#endif #endif
) )
.tag(11).button( BTN_POS(1,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_FILAMENT)) .tag(11).button( FILAMENT_POS, GET_TEXT_F(MSG_FILAMENT))
.tag(12).button( BTN_POS(1,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_LCD_ENDSTOPS)) .tag(12).button( ENDSTOPS_POS, GET_TEXT_F(MSG_LCD_ENDSTOPS))
.tag(15).button( BTN_POS(2,6), BTN_SIZE(1,1), GET_TEXT_F(MSG_DISPLAY_MENU)) .tag(15).button( DISPLAY_POS, GET_TEXT_F(MSG_DISPLAY_MENU))
.tag(9) .button( BTN_POS(1,8), BTN_SIZE(2,1), GET_TEXT_F(MSG_INTERFACE_SETTINGS)) .tag(9) .button( INTERFACE_POS, GET_TEXT_F(MSG_INTERFACE))
.tag(10).button( BTN_POS(1,9), BTN_SIZE(2,1), GET_TEXT_F(MSG_RESTORE_DEFAULTS)) .tag(10).button( RESTORE_DEFAULTS_POS, GET_TEXT_F(MSG_RESTORE_DEFAULTS))
.tag(5) .button( BTN_POS(2,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_VELOCITY)) .tag(5) .button( VELOCITY_POS, GET_TEXT_F(MSG_VELOCITY))
.tag(6) .button( BTN_POS(2,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_ACCELERATION)) .tag(6) .button( ACCELERATION_POS, GET_TEXT_F(MSG_ACCELERATION))
#if DISABLED(CLASSIC_JERK) .tag(7) .button( JERK_POS, GET_TEXT_F(
.tag(7) .button( BTN_POS(2,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_JUNCTION_DEVIATION)) #if DISABLED(CLASSIC_JERK)
#else MSG_JUNCTION_DEVIATION
.tag(7) .button( BTN_POS(2,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_JERK)) #else
#endif JERK_POS
#endif
))
.enabled( .enabled(
#if ENABLED(BACKLASH_GCODE) #if ENABLED(BACKLASH_GCODE)
1 1
#endif #endif
) )
.tag(8).button( BTN_POS(2,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_BACKLASH)) .tag(8).button( BACKLASH_POS, GET_TEXT_F(MSG_BACKLASH))
.colors(action_btn) .colors(action_btn)
.tag(1) .button( BTN_POS(1,10), BTN_SIZE(2,1), GET_TEXT_F(MSG_BACK)); .tag(1).button( BACK_POS, GET_TEXT_F(MSG_BACK));
#undef GRID_COLS
#undef GRID_ROWS
#else
#define GRID_ROWS 6
#define GRID_COLS 3
.enabled(
#if HAS_BED_PROBE
1
#endif
)
.tag(2) .button( BTN_POS(1,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_ZPROBE_ZOFFSET))
.enabled(
#if HAS_CASE_LIGHT
1
#endif
)
.tag(16).button( BTN_POS(1,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_CASE_LIGHT))
.enabled(1)
.tag(3) .button( BTN_POS(2,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_STEPS_PER_MM))
.enabled(
#if HAS_TRINAMIC_CONFIG
1
#endif
)
.tag(13).button( BTN_POS(3,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_TMC_CURRENT))
.enabled(
#if HAS_TRINAMIC_CONFIG
1
#endif
)
.tag(14).button( BTN_POS(3,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_TMC_HOMING_THRS))
.enabled(
#if ENABLED(BACKLASH_GCODE)
1
#endif
)
.tag(8).button( BTN_POS(3,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_BACKLASH))
.enabled(
#if HOTENDS > 1
1
#endif
)
.tag(4) .button( BTN_POS(1,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_OFFSETS_MENU))
.tag(12).button( BTN_POS(3,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_LCD_ENDSTOPS))
.tag(5) .button( BTN_POS(2,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_VELOCITY))
.tag(6) .button( BTN_POS(2,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_ACCELERATION))
#if DISABLED(CLASSIC_JERK)
.tag(7) .button( BTN_POS(2,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_JUNCTION_DEVIATION))
#else
.tag(7) .button( BTN_POS(2,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_JERK))
#endif
.tag(11).button( BTN_POS(1,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_FILAMENT))
.tag(15).button( BTN_POS(3,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_DISPLAY_MENU))
.tag(9) .button( BTN_POS(1,5), BTN_SIZE(2,1), GET_TEXT_F(MSG_INTERFACE_SETTINGS))
.tag(10).button( BTN_POS(1,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_RESTORE_DEFAULTS))
.colors(action_btn)
.tag(1) .button( BTN_POS(3,6), BTN_SIZE(1,1), GET_TEXT_F(MSG_BACK));
#endif
} }
} }
@ -191,6 +180,8 @@ bool AdvancedSettingsMenu::onTouchEnd(uint8_t tag) {
case 12: GOTO_SCREEN(EndstopStatesScreen); break; case 12: GOTO_SCREEN(EndstopStatesScreen); break;
#if HAS_TRINAMIC_CONFIG #if HAS_TRINAMIC_CONFIG
case 13: GOTO_SCREEN(StepperCurrentScreen); break; case 13: GOTO_SCREEN(StepperCurrentScreen); break;
#endif
#if ENABLED(SENSORLESS_HOMING)
case 14: GOTO_SCREEN(StepperBumpSensitivityScreen); break; case 14: GOTO_SCREEN(StepperBumpSensitivityScreen); break;
#endif #endif
case 15: GOTO_SCREEN(DisplayTuningScreen); break; case 15: GOTO_SCREEN(DisplayTuningScreen); break;
@ -201,5 +192,4 @@ bool AdvancedSettingsMenu::onTouchEnd(uint8_t tag) {
} }
return true; return true;
} }
#endif // TOUCH_UI_FTDI_EVE #endif // TOUCH_UI_FTDI_EVE

View File

@ -345,10 +345,14 @@ void BaseNumericAdjustmentScreen::widgets_t::home_buttons(uint8_t tag) {
} }
cmd.font(LAYOUT_FONT); cmd.font(LAYOUT_FONT);
_button(cmd, tag+0, BTN_POS(5,_line), BTN_SIZE(2,1), GET_TEXT_F(MSG_AXIS_X)); _button(cmd, tag+0, BTN_POS(5,_line), BTN_SIZE(2,1), GET_TEXT_F(MSG_AXIS_X));
_button(cmd, tag+1, BTN_POS(7,_line), BTN_SIZE(2,1), GET_TEXT_F(MSG_AXIS_Y)); _button(cmd, tag+1, BTN_POS(7,_line), BTN_SIZE(2,1), GET_TEXT_F(MSG_AXIS_Y));
_button(cmd, tag+2, BTN_POS(9,_line), BTN_SIZE(2,1), GET_TEXT_F(MSG_AXIS_Z)); #if DISABLED(Z_SAFE_HOMING)
_button(cmd, tag+3, BTN_POS(11,_line), BTN_SIZE(3,1), GET_TEXT_F(MSG_AXIS_ALL)); _button(cmd, tag+2, BTN_POS(9,_line), BTN_SIZE(2,1), GET_TEXT_F(MSG_AXIS_Z));
_button(cmd, tag+3, BTN_POS(11,_line), BTN_SIZE(3,1), GET_TEXT_F(MSG_AXIS_ALL));
#else
_button(cmd, tag+3, BTN_POS(9,_line), BTN_SIZE(3,1), GET_TEXT_F(MSG_AXIS_ALL));
#endif
_line++; _line++;
} }

View File

@ -46,7 +46,7 @@ bool BaseScreen::buttonStyleCallback(CommandProcessor &cmd, uint8_t tag, uint8_t
return false; return false;
} }
#ifdef LCD_TIMEOUT_TO_STATUS #if LCD_TIMEOUT_TO_STATUS
if (EventLoop::get_pressed_tag() != 0) { if (EventLoop::get_pressed_tag() != 0) {
reset_menu_timeout(); reset_menu_timeout();
} }
@ -66,7 +66,7 @@ bool BaseScreen::buttonStyleCallback(CommandProcessor &cmd, uint8_t tag, uint8_t
} }
void BaseScreen::onIdle() { void BaseScreen::onIdle() {
#ifdef LCD_TIMEOUT_TO_STATUS #if LCD_TIMEOUT_TO_STATUS
if ((millis() - last_interaction) > LCD_TIMEOUT_TO_STATUS) { if ((millis() - last_interaction) > LCD_TIMEOUT_TO_STATUS) {
reset_menu_timeout(); reset_menu_timeout();
#if ENABLED(TOUCH_UI_DEBUG) #if ENABLED(TOUCH_UI_DEBUG)
@ -78,12 +78,12 @@ void BaseScreen::onIdle() {
} }
void BaseScreen::reset_menu_timeout() { void BaseScreen::reset_menu_timeout() {
#ifdef LCD_TIMEOUT_TO_STATUS #if LCD_TIMEOUT_TO_STATUS
last_interaction = millis(); last_interaction = millis();
#endif #endif
} }
#ifdef LCD_TIMEOUT_TO_STATUS #if LCD_TIMEOUT_TO_STATUS
uint32_t BaseScreen::last_interaction; uint32_t BaseScreen::last_interaction;
#endif #endif

View File

@ -85,7 +85,7 @@ void AdvancedSettingsMenu::onRedraw(draw_mode_t what) {
#endif #endif
) )
.tag(12) .button( BTN_POS(1,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_LINEAR_ADVANCE)) .tag(12) .button( BTN_POS(1,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_LINEAR_ADVANCE))
.tag(13) .button( BTN_POS(1,7), BTN_SIZE(2,1), GET_TEXT_F(MSG_INTERFACE_SETTINGS)) .tag(13) .button( BTN_POS(1,7), BTN_SIZE(2,1), GET_TEXT_F(MSG_INTERFACE))
.tag(14) .button( BTN_POS(1,8), BTN_SIZE(2,1), GET_TEXT_F(MSG_RESTORE_DEFAULTS)) .tag(14) .button( BTN_POS(1,8), BTN_SIZE(2,1), GET_TEXT_F(MSG_RESTORE_DEFAULTS))
.colors(action_btn) .colors(action_btn)
.tag(1). button( BTN_POS(1,9), BTN_SIZE(2,1), GET_TEXT_F(MSG_BACK)); .tag(1). button( BTN_POS(1,9), BTN_SIZE(2,1), GET_TEXT_F(MSG_BACK));

View File

@ -36,11 +36,13 @@ void BioConfirmHomeE::onRedraw(draw_mode_t) {
bool BioConfirmHomeE::onTouchEnd(uint8_t tag) { bool BioConfirmHomeE::onTouchEnd(uint8_t tag) {
switch (tag) { switch (tag) {
case 1: case 1:
SpinnerDialogBox::enqueueAndWait_P(F( #if defined(AXIS_LEVELING_COMMANDS) && defined(PARK_AND_RELEASE_COMMANDS)
"G28 E\n" SpinnerDialogBox::enqueueAndWait_P(F(
AXIS_LEVELING_COMMANDS "\n" "G28 E\n"
PARK_AND_RELEASE_COMMANDS AXIS_LEVELING_COMMANDS "\n"
)); PARK_AND_RELEASE_COMMANDS
));
#endif
current_screen.forget(); current_screen.forget();
break; break;
case 2: case 2:

View File

@ -36,10 +36,12 @@ void BioConfirmHomeXYZ::onRedraw(draw_mode_t) {
bool BioConfirmHomeXYZ::onTouchEnd(uint8_t tag) { bool BioConfirmHomeXYZ::onTouchEnd(uint8_t tag) {
switch (tag) { switch (tag) {
case 1: case 1:
SpinnerDialogBox::enqueueAndWait_P(F( #ifdef PARK_AND_RELEASE_COMMANDS
"G28\n" SpinnerDialogBox::enqueueAndWait_P(F(
PARK_AND_RELEASE_COMMANDS "G28\n"
)); PARK_AND_RELEASE_COMMANDS
));
#endif
current_screen.forget(); current_screen.forget();
break; break;
case 2: case 2:

View File

@ -51,7 +51,7 @@ void MainMenu::onRedraw(draw_mode_t what) {
.tag(4).button( BTN_POS(1,4), BTN_SIZE(2,1), GET_TEXT_F(MSG_RELEASE_XY_AXIS)) .tag(4).button( BTN_POS(1,4), BTN_SIZE(2,1), GET_TEXT_F(MSG_RELEASE_XY_AXIS))
.tag(5).button( BTN_POS(1,5), BTN_SIZE(2,1), GET_TEXT_F(MSG_AUTOLEVEL_X_AXIS)) .tag(5).button( BTN_POS(1,5), BTN_SIZE(2,1), GET_TEXT_F(MSG_AUTOLEVEL_X_AXIS))
.tag(6).button( BTN_POS(1,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_BED_TEMPERATURE)) .tag(6).button( BTN_POS(1,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_BED_TEMPERATURE))
.tag(7).button( BTN_POS(1,7), BTN_SIZE(2,1), GET_TEXT_F(MSG_INTERFACE_SETTINGS)) .tag(7).button( BTN_POS(1,7), BTN_SIZE(2,1), GET_TEXT_F(MSG_INTERFACE))
.tag(8).button( BTN_POS(1,8), BTN_SIZE(2,1), GET_TEXT_F(MSG_ADVANCED_SETTINGS)) .tag(8).button( BTN_POS(1,8), BTN_SIZE(2,1), GET_TEXT_F(MSG_ADVANCED_SETTINGS))
.tag(9).button( BTN_POS(1,9), BTN_SIZE(2,1), GET_TEXT_F(MSG_INFO_MENU)) .tag(9).button( BTN_POS(1,9), BTN_SIZE(2,1), GET_TEXT_F(MSG_INFO_MENU))
.colors(action_btn) .colors(action_btn)
@ -72,7 +72,9 @@ bool MainMenu::onTouchEnd(uint8_t tag) {
case 2: GOTO_SCREEN(BioConfirmHomeXYZ); break; case 2: GOTO_SCREEN(BioConfirmHomeXYZ); break;
case 3: SpinnerDialogBox::enqueueAndWait_P(e_homed ? F("G0 E0 F120") : F("G112")); break; case 3: SpinnerDialogBox::enqueueAndWait_P(e_homed ? F("G0 E0 F120") : F("G112")); break;
case 4: StatusScreen::unlockMotors(); break; case 4: StatusScreen::unlockMotors(); break;
#ifdef AXIS_LEVELING_COMMANDS
case 5: SpinnerDialogBox::enqueueAndWait_P(F(AXIS_LEVELING_COMMANDS)); break; case 5: SpinnerDialogBox::enqueueAndWait_P(F(AXIS_LEVELING_COMMANDS)); break;
#endif
case 6: GOTO_SCREEN(TemperatureScreen); break; case 6: GOTO_SCREEN(TemperatureScreen); break;
case 7: GOTO_SCREEN(InterfaceSettingsScreen); break; case 7: GOTO_SCREEN(InterfaceSettingsScreen); break;
case 8: GOTO_SCREEN(AdvancedSettingsMenu); break; case 8: GOTO_SCREEN(AdvancedSettingsMenu); break;

View File

@ -80,12 +80,14 @@ void BootScreen::onIdle() {
SpinnerDialogBox::hide(); SpinnerDialogBox::hide();
} }
if (UIData::animations_enabled()) { #if DISABLED(TOUCH_UI_NO_BOOTSCREEN)
// If there is a startup video in the flash SPI, play if (UIData::animations_enabled()) {
// that, otherwise show a static splash screen. // If there is a startup video in the flash SPI, play
if (!MediaPlayerScreen::playBootMedia()) // that, otherwise show a static splash screen.
showSplashScreen(); if (!MediaPlayerScreen::playBootMedia())
} showSplashScreen();
}
#endif
StatusScreen::loadBitmaps(); StatusScreen::loadBitmaps();

View File

@ -111,6 +111,7 @@ void ChangeFilamentScreen::onRedraw(draw_mode_t what) {
if (what & BACKGROUND) { if (what & BACKGROUND) {
cmd.cmd(CLEAR_COLOR_RGB(bg_color)) cmd.cmd(CLEAR_COLOR_RGB(bg_color))
.cmd(CLEAR(true,true,true)) .cmd(CLEAR(true,true,true))
.cmd(COLOR_RGB(bg_text_enabled))
.tag(0) .tag(0)
#ifdef TOUCH_UI_PORTRAIT #ifdef TOUCH_UI_PORTRAIT
.font(font_large) .font(font_large)
@ -119,7 +120,7 @@ void ChangeFilamentScreen::onRedraw(draw_mode_t what) {
#endif #endif
.text(BTN_POS(1,1), BTN_SIZE(2,1), GET_TEXT_F(MSG_EXTRUDER_SELECTION)) .text(BTN_POS(1,1), BTN_SIZE(2,1), GET_TEXT_F(MSG_EXTRUDER_SELECTION))
#ifdef TOUCH_UI_PORTRAIT #ifdef TOUCH_UI_PORTRAIT
.text(BTN_POS(1,7), BTN_SIZE(1,1), F("")) .text(BTN_POS(1,7), BTN_SIZE(1,1), GET_TEXT_F(MSG_CURRENT_TEMPERATURE))
#else #else
.text(BTN_POS(3,1), BTN_SIZE(2,1), GET_TEXT_F(MSG_CURRENT_TEMPERATURE)) .text(BTN_POS(3,1), BTN_SIZE(2,1), GET_TEXT_F(MSG_CURRENT_TEMPERATURE))
.font(font_small) .font(font_small)

View File

@ -69,7 +69,7 @@ void InterfaceSettingsScreen::onRedraw(draw_mode_t what) {
.cmd(COLOR_RGB(bg_text_enabled)) .cmd(COLOR_RGB(bg_text_enabled))
.tag(0) .tag(0)
.font(font_medium) .font(font_medium)
.text(BTN_POS(1,1), BTN_SIZE(4,1), GET_TEXT_F(MSG_INTERFACE_SETTINGS)) .text(BTN_POS(1,1), BTN_SIZE(4,1), GET_TEXT_F(MSG_INTERFACE))
#undef EDGE_R #undef EDGE_R
#define EDGE_R 30 #define EDGE_R 30
.font(font_small) .font(font_small)
@ -77,7 +77,9 @@ void InterfaceSettingsScreen::onRedraw(draw_mode_t what) {
.text(BTN_POS(1,2), BTN_SIZE(2,1), GET_TEXT_F(MSG_LCD_BRIGHTNESS), OPT_RIGHTX | OPT_CENTERY) .text(BTN_POS(1,2), BTN_SIZE(2,1), GET_TEXT_F(MSG_LCD_BRIGHTNESS), OPT_RIGHTX | OPT_CENTERY)
.text(BTN_POS(1,3), BTN_SIZE(2,1), GET_TEXT_F(MSG_SOUND_VOLUME), OPT_RIGHTX | OPT_CENTERY) .text(BTN_POS(1,3), BTN_SIZE(2,1), GET_TEXT_F(MSG_SOUND_VOLUME), OPT_RIGHTX | OPT_CENTERY)
.text(BTN_POS(1,4), BTN_SIZE(2,1), GET_TEXT_F(MSG_SCREEN_LOCK), OPT_RIGHTX | OPT_CENTERY); .text(BTN_POS(1,4), BTN_SIZE(2,1), GET_TEXT_F(MSG_SCREEN_LOCK), OPT_RIGHTX | OPT_CENTERY);
#if DISABLED(TOUCH_UI_NO_BOOTSCREEN)
cmd.text(BTN_POS(1,5), BTN_SIZE(2,1), GET_TEXT_F(MSG_BOOT_SCREEN), OPT_RIGHTX | OPT_CENTERY); cmd.text(BTN_POS(1,5), BTN_SIZE(2,1), GET_TEXT_F(MSG_BOOT_SCREEN), OPT_RIGHTX | OPT_CENTERY);
#endif
#undef EDGE_R #undef EDGE_R
} }
@ -95,16 +97,18 @@ void InterfaceSettingsScreen::onRedraw(draw_mode_t what) {
.tag(3).slider(BTN_POS(3,3), BTN_SIZE(2,1), screen_data.InterfaceSettingsScreen.volume, 0xFF) .tag(3).slider(BTN_POS(3,3), BTN_SIZE(2,1), screen_data.InterfaceSettingsScreen.volume, 0xFF)
.colors(ui_toggle) .colors(ui_toggle)
.tag(4).toggle2(BTN_POS(3,4), BTN_SIZE(w,1), GET_TEXT_F(MSG_NO), GET_TEXT_F(MSG_YES), LockScreen::is_enabled()) .tag(4).toggle2(BTN_POS(3,4), BTN_SIZE(w,1), GET_TEXT_F(MSG_NO), GET_TEXT_F(MSG_YES), LockScreen::is_enabled())
#if DISABLED(TOUCH_UI_NO_BOOTSCREEN)
.tag(5).toggle2(BTN_POS(3,5), BTN_SIZE(w,1), GET_TEXT_F(MSG_NO), GET_TEXT_F(MSG_YES), UIData::animations_enabled()) .tag(5).toggle2(BTN_POS(3,5), BTN_SIZE(w,1), GET_TEXT_F(MSG_NO), GET_TEXT_F(MSG_YES), UIData::animations_enabled())
#endif
#undef EDGE_R #undef EDGE_R
#define EDGE_R 0 #define EDGE_R 0
#ifdef TOUCH_UI_PORTRAIT #ifdef TOUCH_UI_PORTRAIT
.colors(normal_btn) .colors(normal_btn)
.tag(6).button (BTN_POS(1,6), BTN_SIZE(4,1), GET_TEXT_F(MSG_INTERFACE_SOUNDS)) .tag(6).button (BTN_POS(1,6), BTN_SIZE(4,1), GET_TEXT_F(MSG_SOUNDS))
.colors(action_btn) .colors(action_btn)
.tag(1).button (BTN_POS(1,7), BTN_SIZE(4,1), GET_TEXT_F(MSG_BACK)); .tag(1).button (BTN_POS(1,7), BTN_SIZE(4,1), GET_TEXT_F(MSG_BACK));
#else #else
.tag(6).button (BTN_POS(1,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_INTERFACE_SOUNDS)) .tag(6).button (BTN_POS(1,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_SOUNDS))
.colors(action_btn) .colors(action_btn)
.tag(1).button (BTN_POS(3,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_BACK)); .tag(1).button (BTN_POS(3,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_BACK));
#endif #endif
@ -252,7 +256,7 @@ void InterfaceSettingsScreen::loadSettings(const char *buff) {
} }
#ifdef ARCHIM2_SPI_FLASH_EEPROM_BACKUP_SIZE #ifdef ARCHIM2_SPI_FLASH_EEPROM_BACKUP_SIZE
#include "../../../../../HAL/shared/persistent_store_api.h" #include "../../../../../HAL/shared/eeprom_api.h"
bool restoreEEPROM() { bool restoreEEPROM() {
uint8_t data[ARCHIM2_SPI_FLASH_EEPROM_BACKUP_SIZE]; uint8_t data[ARCHIM2_SPI_FLASH_EEPROM_BACKUP_SIZE];

View File

@ -71,7 +71,7 @@ void InterfaceSoundsScreen::onRedraw(draw_mode_t what) {
#define GRID_ROWS 9 #define GRID_ROWS 9
.font(font_medium) .font(font_medium)
.text(BTN_POS(1,1), BTN_SIZE(4,1), GET_TEXT_F(MSG_INTERFACE_SOUNDS)) .text(BTN_POS(1,1), BTN_SIZE(4,1), GET_TEXT_F(MSG_SOUNDS))
#undef EDGE_R #undef EDGE_R
#define EDGE_R 30 #define EDGE_R 30
.font(font_small) .font(font_small)

View File

@ -37,81 +37,89 @@ void MainMenu::onRedraw(draw_mode_t what) {
.cmd(CLEAR(true,true,true)); .cmd(CLEAR(true,true,true));
} }
#ifdef TOUCH_UI_PORTRAIT
#define GRID_ROWS 8
#define GRID_COLS 2
#define ABOUT_PRINTER_POS BTN_POS(1,1), BTN_SIZE(2,1)
#define ADVANCED_SETTINGS_POS BTN_POS(1,2), BTN_SIZE(2,1)
#define FILAMENTCHANGE_POS BTN_POS(1,3), BTN_SIZE(2,1)
#define TEMPERATURE_POS BTN_POS(1,4), BTN_SIZE(2,1)
#define MOVE_AXIS_POS BTN_POS(1,5), BTN_SIZE(1,1)
#define DISABLE_STEPPERS_POS BTN_POS(2,5), BTN_SIZE(1,1)
#define AUTO_HOME_POS BTN_POS(1,6), BTN_SIZE(1,1)
#define CLEAN_NOZZLE_POS BTN_POS(2,6), BTN_SIZE(1,1)
#define LEVEL_BED_POS BTN_POS(1,7), BTN_SIZE(1,1)
#define LEVEL_AXIS_POS BTN_POS(2,7), BTN_SIZE(1,1)
#define BACK_POS BTN_POS(1,8), BTN_SIZE(2,1)
#else
#define GRID_ROWS 6
#define GRID_COLS 2
#define ADVANCED_SETTINGS_POS BTN_POS(1,1), BTN_SIZE(1,1)
#define ABOUT_PRINTER_POS BTN_POS(2,1), BTN_SIZE(1,1)
#define AUTO_HOME_POS BTN_POS(1,2), BTN_SIZE(1,1)
#define CLEAN_NOZZLE_POS BTN_POS(2,2), BTN_SIZE(1,1)
#define MOVE_AXIS_POS BTN_POS(1,3), BTN_SIZE(1,1)
#define DISABLE_STEPPERS_POS BTN_POS(2,3), BTN_SIZE(1,1)
#define TEMPERATURE_POS BTN_POS(1,4), BTN_SIZE(1,1)
#define FILAMENTCHANGE_POS BTN_POS(2,4), BTN_SIZE(1,1)
#define LEVEL_BED_POS BTN_POS(1,5), BTN_SIZE(1,1)
#define LEVEL_AXIS_POS BTN_POS(2,5), BTN_SIZE(1,1)
#define BACK_POS BTN_POS(1,6), BTN_SIZE(2,1)
#endif
if (what & FOREGROUND) { if (what & FOREGROUND) {
CommandProcessor cmd; CommandProcessor cmd;
cmd.colors(normal_btn) cmd.colors(normal_btn)
.font(Theme::font_medium) .font(Theme::font_medium)
#ifdef TOUCH_UI_PORTRAIT .tag(2).button( AUTO_HOME_POS, GET_TEXT_F(MSG_AUTO_HOME))
#define GRID_ROWS 8 .enabled(
#define GRID_COLS 2 #if ANY(NOZZLE_CLEAN_FEATURE, TOUCH_UI_COCOA_PRESS)
.tag(2).button( BTN_POS(1,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_AUTO_HOME)) 1
.enabled( #endif
#if ENABLED(NOZZLE_CLEAN_FEATURE) )
1 .tag(3).button( CLEAN_NOZZLE_POS, GET_TEXT_F(
#endif #if ENABLED(TOUCH_UI_COCOA_PRESS)
MSG_PREHEAT_1
#else
MSG_CLEAN_NOZZLE
#endif
))
.tag(4).button( MOVE_AXIS_POS, GET_TEXT_F(MSG_MOVE_AXIS))
.tag(5).button( DISABLE_STEPPERS_POS, GET_TEXT_F(MSG_DISABLE_STEPPERS))
.tag(6).button( TEMPERATURE_POS, GET_TEXT_F(MSG_TEMPERATURE))
.enabled(
#if DISABLED(TOUCH_UI_LULZBOT_BIO)
1
#endif
)
.tag(7).button( FILAMENTCHANGE_POS, GET_TEXT_F(
#if ENABLED(TOUCH_UI_COCOA_PRESS)
MSG_CASE_LIGHT
#else
MSG_FILAMENTCHANGE
#endif
))
.tag(8).button( ADVANCED_SETTINGS_POS, GET_TEXT_F(MSG_ADVANCED_SETTINGS))
.enabled(
#ifdef PRINTCOUNTER
1
#endif
) )
.tag(3).button( BTN_POS(2,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_CLEAN_NOZZLE)) .enabled(
.tag(4).button( BTN_POS(1,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_MOVE_AXIS)) #ifdef AXIS_LEVELING_COMMANDS
.tag(5).button( BTN_POS(2,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_DISABLE_STEPPERS)) 1
.tag(6).button( BTN_POS(1,3), BTN_SIZE(2,1), GET_TEXT_F(MSG_TEMPERATURE)) #endif
.enabled(
#if NONE(TOUCH_UI_LULZBOT_BIO, TOUCH_UI_COCOA_PRESS)
1
#endif
) )
.tag(7).button( BTN_POS(1,4), BTN_SIZE(2,1), GET_TEXT_F(MSG_FILAMENTCHANGE)) .tag(9).button( LEVEL_AXIS_POS, GET_TEXT_F(MSG_AUTOLEVEL_X_AXIS))
.tag(8).button( BTN_POS(1,5), BTN_SIZE(2,1), GET_TEXT_F(MSG_ADVANCED_SETTINGS)) .enabled(
.enabled( #ifdef HAS_LEVELING
#ifdef PRINTCOUNTER 1
1 #endif
#endif
) )
.tag(9).button( BTN_POS(1,7), BTN_SIZE(2,1), GET_TEXT_F(MSG_INFO_STATS_MENU)) .tag(10).button( LEVEL_BED_POS, GET_TEXT_F(MSG_LEVEL_BED))
.tag(10).button( BTN_POS(1,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_INFO_MENU)) .tag(11).button( ABOUT_PRINTER_POS, GET_TEXT_F(MSG_INFO_MENU))
.colors(action_btn) .colors(action_btn)
.tag(1).button( BTN_POS(1,8), BTN_SIZE(2,1), GET_TEXT_F(MSG_BACK)); .tag(1).button( BACK_POS, GET_TEXT_F(MSG_BACK));
#undef GRID_COLS
#undef GRID_ROWS
#else
#define GRID_ROWS 5
#define GRID_COLS 2
.tag(2).button( BTN_POS(1,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_AUTO_HOME))
#if ENABLED(TOUCH_UI_COCOA_PRESS)
.tag(3).button( BTN_POS(2,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_PREHEAT_1))
#else
.enabled(
#if ENABLED(NOZZLE_CLEAN_FEATURE)
1
#endif
)
.tag(3).button( BTN_POS(2,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_CLEAN_NOZZLE))
#endif
.tag(4).button( BTN_POS(1,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_MOVE_AXIS))
.tag(5).button( BTN_POS(2,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_DISABLE_STEPPERS))
.tag(6).button( BTN_POS(1,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_TEMPERATURE))
#if ENABLED(TOUCH_UI_COCOA_PRESS)
.tag(7).button( BTN_POS(2,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_CASE_LIGHT))
#else
.enabled(
#if DISABLED(TOUCH_UI_LULZBOT_BIO)
1
#endif
)
.tag(7).button( BTN_POS(2,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_FILAMENTCHANGE))
#endif
.tag(8).button( BTN_POS(1,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_ADVANCED_SETTINGS))
.enabled(
#ifdef PRINTCOUNTER
1
#endif
)
.tag(9).button( BTN_POS(2,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_INFO_STATS_MENU))
.tag(10).button( BTN_POS(1,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_INFO_MENU))
.colors(action_btn)
.tag(1).button( BTN_POS(2,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_BACK));
#undef GRID_COLS
#undef GRID_ROWS
#endif
} }
} }
@ -122,23 +130,32 @@ bool MainMenu::onTouchEnd(uint8_t tag) {
case 1: SaveSettingsDialogBox::promptToSaveSettings(); break; case 1: SaveSettingsDialogBox::promptToSaveSettings(); break;
case 2: SpinnerDialogBox::enqueueAndWait_P(F("G28")); break; case 2: SpinnerDialogBox::enqueueAndWait_P(F("G28")); break;
#if ENABLED(TOUCH_UI_COCOA_PRESS) #if ENABLED(TOUCH_UI_COCOA_PRESS)
case 3: GOTO_SCREEN(PreheatTimerScreen); break; case 3: GOTO_SCREEN(PreheatMenu); break;
#elif ENABLED(NOZZLE_CLEAN_FEATURE) #elif ENABLED(NOZZLE_CLEAN_FEATURE)
case 3: injectCommands_P(PSTR("G12")); GOTO_SCREEN(StatusScreen); break; case 3: injectCommands_P(PSTR("G12")); GOTO_SCREEN(StatusScreen); break;
#endif #endif
case 4: GOTO_SCREEN(MoveAxisScreen); break; case 4: GOTO_SCREEN(MoveAxisScreen); break;
case 5: injectCommands_P(PSTR("M84")); break; case 5: injectCommands_P(PSTR("M84")); break;
case 6: GOTO_SCREEN(TemperatureScreen); break; case 6: GOTO_SCREEN(TemperatureScreen); break;
#if ENABLED(TOUCH_UI_COCOA_PRESS) #if ENABLED(TOUCH_UI_COCOA_PRESS) && HAS_CASE_LIGHT
case 7: GOTO_SCREEN(CaseLightScreen); break; case 7: GOTO_SCREEN(CaseLightScreen); break;
#else #else
case 7: GOTO_SCREEN(ChangeFilamentScreen); break; case 7: GOTO_SCREEN(ChangeFilamentScreen); break;
#endif #endif
case 8: GOTO_SCREEN(AdvancedSettingsMenu); break; case 8: GOTO_SCREEN(AdvancedSettingsMenu); break;
#if ENABLED(PRINTCOUNTER) #ifdef AXIS_LEVELING_COMMANDS
case 9: GOTO_SCREEN(StatisticsScreen); break; case 9: SpinnerDialogBox::enqueueAndWait_P(F(AXIS_LEVELING_COMMANDS)); break;
#endif #endif
case 10: GOTO_SCREEN(AboutScreen); break; #ifdef HAS_LEVELING
case 10: SpinnerDialogBox::enqueueAndWait_P(F(
#ifdef BED_LEVELING_COMMANDS
BED_LEVELING_COMMANDS
#else
"G29"
#endif
)); break;
#endif
case 11: GOTO_SCREEN(AboutScreen); break;
default: default:
return false; return false;
} }

View File

@ -0,0 +1,83 @@
/********************
* preheat_menu.cpp *
********************/
/****************************************************************************
* Written By Marcio Teixeira 2020 - Cocoa Press *
* *
* 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. *
* *
* To view a copy of the GNU General Public License, go to the following *
* location: <http://www.gnu.org/licenses/>. *
****************************************************************************/
#include "../config.h"
#if ENABLED(TOUCH_UI_FTDI_EVE) && defined(TOUCH_UI_COCOA_PRESS)
#include "screens.h"
using namespace FTDI;
using namespace ExtUI;
using namespace Theme;
void PreheatMenu::onRedraw(draw_mode_t what) {
if (what & BACKGROUND) {
CommandProcessor cmd;
cmd.cmd(CLEAR_COLOR_RGB(Theme::bg_color))
.cmd(CLEAR(true,true,true))
.tag(0);
}
#define GRID_ROWS 3
#define GRID_COLS 2
if (what & FOREGROUND) {
CommandProcessor cmd;
cmd.cmd(COLOR_RGB(bg_text_enabled))
.font(Theme::font_medium)
.text ( BTN_POS(1,1), BTN_SIZE(2,1), GET_TEXT_F(MSG_PREHEAT_1))
.colors(normal_btn)
.tag(2).button( BTN_POS(1,2), BTN_SIZE(1,1), F("Dark Chocolate"))
.tag(3).button( BTN_POS(2,2), BTN_SIZE(1,1), F("Milk Chocolate"))
.tag(4).button( BTN_POS(1,3), BTN_SIZE(1,1), F("White Chocolate"))
.colors(action_btn)
.tag(1) .button( BTN_POS(2,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_BACK));
}
}
bool PreheatMenu::onTouchEnd(uint8_t tag) {
switch (tag) {
case 1: GOTO_PREVIOUS(); break;
case 2:
#ifdef COCOA_PRESS_PREHEAT_DARK_CHOCOLATE_SCRIPT
injectCommands_P(PSTR(COCOA_PRESS_PREHEAT_DARK_CHOCOLATE_SCRIPT));
#endif
GOTO_SCREEN(PreheatTimerScreen);
break;
case 3:
#ifdef COCOA_PRESS_PREHEAT_MILK_CHOCOLATE_SCRIPT
injectCommands_P(PSTR(COCOA_PRESS_PREHEAT_MILK_CHOCOLATE_SCRIPT));
#endif
GOTO_SCREEN(PreheatTimerScreen);
break;
case 4:
#ifdef COCOA_PRESS_PREHEAT_WHITE_CHOCOLATE_SCRIPT
injectCommands_P(PSTR(COCOA_PRESS_PREHEAT_WHITE_CHOCOLATE_SCRIPT));
#endif
GOTO_SCREEN(PreheatTimerScreen);
break;
default: return false;
}
return true;
}
#endif // TOUCH_UI_FTDI_EVE

View File

@ -77,9 +77,6 @@ void PreheatTimerScreen::draw_interaction_buttons(draw_mode_t what) {
void PreheatTimerScreen::onEntry() { void PreheatTimerScreen::onEntry() {
screen_data.PreheatTimerScreen.start_ms = millis(); screen_data.PreheatTimerScreen.start_ms = millis();
#ifdef COCOA_PRESS_PREHEAT_SCRIPT
injectCommands_P(PSTR(COCOA_PRESS_PREHEAT_SCRIPT));
#endif
} }
void PreheatTimerScreen::onRedraw(draw_mode_t what) { void PreheatTimerScreen::onRedraw(draw_mode_t what) {

View File

@ -105,6 +105,7 @@ SCREEN_TABLE {
DECL_SCREEN(BioConfirmHomeE), DECL_SCREEN(BioConfirmHomeE),
#endif #endif
#if ENABLED(TOUCH_UI_COCOA_PRESS) #if ENABLED(TOUCH_UI_COCOA_PRESS)
DECL_SCREEN(PreheatMenu),
DECL_SCREEN(PreheatTimerScreen), DECL_SCREEN(PreheatTimerScreen),
#endif #endif
#if ENABLED(TOUCH_UI_DEVELOPER_MENU) #if ENABLED(TOUCH_UI_DEVELOPER_MENU)

View File

@ -76,6 +76,7 @@ enum {
PRINTING_SCREEN_CACHE, PRINTING_SCREEN_CACHE,
#endif #endif
#if ENABLED(TOUCH_UI_COCOA_PRESS) #if ENABLED(TOUCH_UI_COCOA_PRESS)
PREHEAT_MENU_CACHE,
PREHEAT_TIMER_SCREEN_CACHE, PREHEAT_TIMER_SCREEN_CACHE,
#endif #endif
CHANGE_FILAMENT_SCREEN_CACHE, CHANGE_FILAMENT_SCREEN_CACHE,
@ -99,7 +100,7 @@ enum {
class BaseScreen : public UIScreen { class BaseScreen : public UIScreen {
protected: protected:
#ifdef LCD_TIMEOUT_TO_STATUS #if LCD_TIMEOUT_TO_STATUS
static uint32_t last_interaction; static uint32_t last_interaction;
#endif #endif
@ -314,6 +315,12 @@ class StatusScreen : public BaseScreen, public CachedScreen<STATUS_SCREEN_CACHE,
#endif #endif
#if ENABLED(TOUCH_UI_COCOA_PRESS) #if ENABLED(TOUCH_UI_COCOA_PRESS)
class PreheatMenu : public BaseScreen, public CachedScreen<PREHEAT_MENU_CACHE> {
public:
static void onRedraw(draw_mode_t);
static bool onTouchEnd(uint8_t tag);
};
class PreheatTimerScreen : public BaseScreen, public CachedScreen<PREHEAT_TIMER_SCREEN_CACHE> { class PreheatTimerScreen : public BaseScreen, public CachedScreen<PREHEAT_TIMER_SCREEN_CACHE> {
private: private:
static uint16_t secondsRemaining(); static uint16_t secondsRemaining();

View File

@ -33,9 +33,9 @@ using namespace FTDI;
using namespace Theme; using namespace Theme;
#ifdef TOUCH_UI_PORTRAIT #ifdef TOUCH_UI_PORTRAIT
#define GRID_ROWS 8 #define GRID_ROWS 8
#else #else
#define GRID_ROWS 8 #define GRID_ROWS 8
#endif #endif
void StatusScreen::draw_axis_position(draw_mode_t what) { void StatusScreen::draw_axis_position(draw_mode_t what) {
@ -43,41 +43,41 @@ void StatusScreen::draw_axis_position(draw_mode_t what) {
#define GRID_COLS 3 #define GRID_COLS 3
#ifdef TOUCH_UI_PORTRAIT
#define X_LBL_POS BTN_POS(1,5), BTN_SIZE(1,1)
#define Y_LBL_POS BTN_POS(1,6), BTN_SIZE(1,1)
#define Z_LBL_POS BTN_POS(1,7), BTN_SIZE(1,1)
#define X_VAL_POS BTN_POS(2,5), BTN_SIZE(2,1)
#define Y_VAL_POS BTN_POS(2,6), BTN_SIZE(2,1)
#define Z_VAL_POS BTN_POS(2,7), BTN_SIZE(2,1)
#else
#define X_LBL_POS BTN_POS(1,5), BTN_SIZE(1,1)
#define Y_LBL_POS BTN_POS(2,5), BTN_SIZE(1,1)
#define Z_LBL_POS BTN_POS(3,5), BTN_SIZE(1,1)
#define X_VAL_POS BTN_POS(1,6), BTN_SIZE(1,1)
#define Y_VAL_POS BTN_POS(2,6), BTN_SIZE(1,1)
#define Z_VAL_POS BTN_POS(3,6), BTN_SIZE(1,1)
#endif
#define _UNION_POS(x1,y1,w1,h1,x2,y2,w2,h2) x1,y1,max(x1+w1,x2+w2)-x1,max(y1+h1,y2+h2)-y1
#define UNION_POS(p1, p2) _UNION_POS(p1, p2)
if (what & BACKGROUND) { if (what & BACKGROUND) {
cmd.tag(6) cmd.tag(6)
#ifdef TOUCH_UI_PORTRAIT .fgcolor(Theme::axis_label)
.fgcolor(Theme::axis_label) .font(Theme::font_large)
.font(Theme::font_large) .button( UNION_POS(X_LBL_POS, X_VAL_POS), F(""), OPT_FLAT)
.button( BTN_POS(1,5), BTN_SIZE(2,1), F(""), OPT_FLAT) .button( UNION_POS(Y_LBL_POS, Y_VAL_POS), F(""), OPT_FLAT)
.button( BTN_POS(1,6), BTN_SIZE(2,1), F(""), OPT_FLAT) .button( UNION_POS(Z_LBL_POS, Z_VAL_POS), F(""), OPT_FLAT)
.button( BTN_POS(1,7), BTN_SIZE(2,1), F(""), OPT_FLAT) .font(Theme::font_medium)
.fgcolor(Theme::x_axis) .button( X_VAL_POS, F(""), OPT_FLAT)
.font(Theme::font_small) .fgcolor(Theme::y_axis) .button( Y_VAL_POS, F(""), OPT_FLAT)
.text ( BTN_POS(1,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_AXIS_X)) .fgcolor(Theme::z_axis) .button( Z_VAL_POS, F(""), OPT_FLAT)
.text ( BTN_POS(1,6), BTN_SIZE(1,1), GET_TEXT_F(MSG_AXIS_Y)) .font(Theme::font_small)
.text ( BTN_POS(1,7), BTN_SIZE(1,1), GET_TEXT_F(MSG_AXIS_Z)) .text ( X_LBL_POS, GET_TEXT_F(MSG_AXIS_X))
.text ( Y_LBL_POS, GET_TEXT_F(MSG_AXIS_Y))
.font(Theme::font_medium) .text ( Z_LBL_POS, GET_TEXT_F(MSG_AXIS_Z))
.fgcolor(Theme::x_axis) .button( BTN_POS(2,5), BTN_SIZE(2,1), F(""), OPT_FLAT) .colors(normal_btn);
.fgcolor(Theme::y_axis) .button( BTN_POS(2,6), BTN_SIZE(2,1), F(""), OPT_FLAT)
.fgcolor(Theme::z_axis) .button( BTN_POS(2,7), BTN_SIZE(2,1), F(""), OPT_FLAT);
#else
.fgcolor(Theme::axis_label)
.font(Theme::font_large)
.button( BTN_POS(1,5), BTN_SIZE(1,2), F(""), OPT_FLAT)
.button( BTN_POS(2,5), BTN_SIZE(1,2), F(""), OPT_FLAT)
.button( BTN_POS(3,5), BTN_SIZE(1,2), F(""), OPT_FLAT)
.font(Theme::font_small)
.text ( BTN_POS(1,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_AXIS_X))
.text ( BTN_POS(2,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_AXIS_Y))
.text ( BTN_POS(3,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_AXIS_Z))
.font(Theme::font_medium)
.fgcolor(Theme::x_axis) .button( BTN_POS(1,6), BTN_SIZE(1,1), F(""), OPT_FLAT)
.fgcolor(Theme::y_axis) .button( BTN_POS(2,6), BTN_SIZE(1,1), F(""), OPT_FLAT)
.fgcolor(Theme::z_axis) .button( BTN_POS(3,6), BTN_SIZE(1,1), F(""), OPT_FLAT);
#endif
} }
if (what & FOREGROUND) { if (what & FOREGROUND) {
@ -101,16 +101,11 @@ void StatusScreen::draw_axis_position(draw_mode_t what) {
else else
strcpy_P(z_str, PSTR("?")); strcpy_P(z_str, PSTR("?"));
cmd.tag(6).font(Theme::font_medium) cmd.tag(6)
#ifdef TOUCH_UI_PORTRAIT .font(Theme::font_medium)
.text ( BTN_POS(2,5), BTN_SIZE(2,1), x_str) .text ( X_VAL_POS, x_str)
.text ( BTN_POS(2,6), BTN_SIZE(2,1), y_str) .text ( Y_VAL_POS, y_str)
.text ( BTN_POS(2,7), BTN_SIZE(2,1), z_str); .text ( Z_VAL_POS, z_str);
#else
.text ( BTN_POS(1,6), BTN_SIZE(1,1), x_str)
.text ( BTN_POS(2,6), BTN_SIZE(1,1), y_str)
.text ( BTN_POS(3,6), BTN_SIZE(1,1), z_str);
#endif
} }
#undef GRID_COLS #undef GRID_COLS
@ -125,49 +120,49 @@ void StatusScreen::draw_axis_position(draw_mode_t what) {
void StatusScreen::draw_temperature(draw_mode_t what) { void StatusScreen::draw_temperature(draw_mode_t what) {
using namespace Theme; using namespace Theme;
#define TEMP_RECT_1 BTN_POS(1,1), BTN_SIZE(4,2)
#define TEMP_RECT_2 BTN_POS(1,1), BTN_SIZE(8,1)
#define NOZ_1_POS BTN_POS(1,1), BTN_SIZE(4,1)
#define NOZ_2_POS BTN_POS(5,1), BTN_SIZE(4,1)
#define BED_POS BTN_POS(1,2), BTN_SIZE(4,1)
#define FAN_POS BTN_POS(5,2), BTN_SIZE(4,1)
#define _ICON_POS(x,y,w,h) x, y, w/4, h
#define _TEXT_POS(x,y,w,h) x + w/4, y, w - w/4, h
#define ICON_POS(pos) _ICON_POS(pos)
#define TEXT_POS(pos) _TEXT_POS(pos)
CommandProcessor cmd; CommandProcessor cmd;
if (what & BACKGROUND) { if (what & BACKGROUND) {
cmd.font(Theme::font_small) cmd.font(Theme::font_small)
#ifdef TOUCH_UI_PORTRAIT
.tag(5) .tag(5)
.fgcolor(temp) .button( BTN_POS(1,1), BTN_SIZE(4,2), F(""), OPT_FLAT) .fgcolor(temp) .button( TEMP_RECT_1, F(""), OPT_FLAT)
.button( BTN_POS(1,1), BTN_SIZE(8,1), F(""), OPT_FLAT) .button( TEMP_RECT_2, F(""), OPT_FLAT)
.fgcolor(fan_speed) .button( BTN_POS(5,2), BTN_SIZE(4,1), F(""), OPT_FLAT) .fgcolor(fan_speed).button( FAN_POS, F(""), OPT_FLAT)
.tag(0) .tag(0);
.fgcolor(progress) .button( BTN_POS(1,3), BTN_SIZE(4,1), F(""), OPT_FLAT)
.button( BTN_POS(5,3), BTN_SIZE(4,1), F(""), OPT_FLAT);
#else
.tag(5)
.fgcolor(temp) .button( BTN_POS(1,1), BTN_SIZE(4,2), F(""), OPT_FLAT)
.button( BTN_POS(1,1), BTN_SIZE(8,1), F(""), OPT_FLAT)
.fgcolor(fan_speed) .button( BTN_POS(5,2), BTN_SIZE(4,1), F(""), OPT_FLAT)
.tag(0)
.fgcolor(progress) .button( BTN_POS(9,1), BTN_SIZE(4,1), F(""), OPT_FLAT)
.button( BTN_POS(9,2), BTN_SIZE(4,1), F(""), OPT_FLAT);
#endif
// Draw Extruder Bitmap on Extruder Temperature Button // Draw Extruder Bitmap on Extruder Temperature Button
cmd.tag(5) cmd.tag(5)
.cmd(BITMAP_SOURCE(Extruder_Icon_Info)) .cmd (BITMAP_SOURCE(Extruder_Icon_Info))
.cmd(BITMAP_LAYOUT(Extruder_Icon_Info)) .cmd (BITMAP_LAYOUT(Extruder_Icon_Info))
.cmd(BITMAP_SIZE (Extruder_Icon_Info)) .cmd (BITMAP_SIZE (Extruder_Icon_Info))
.icon (BTN_POS(1,1), BTN_SIZE(1,1), Extruder_Icon_Info, icon_scale) .icon(ICON_POS(NOZ_1_POS), Extruder_Icon_Info, icon_scale)
.icon (BTN_POS(5,1), BTN_SIZE(1,1), Extruder_Icon_Info, icon_scale); .icon(ICON_POS(NOZ_2_POS), Extruder_Icon_Info, icon_scale);
// Draw Bed Heat Bitmap on Bed Heat Button // Draw Bed Heat Bitmap on Bed Heat Button
cmd.cmd(BITMAP_SOURCE(Bed_Heat_Icon_Info)) cmd.cmd (BITMAP_SOURCE(Bed_Heat_Icon_Info))
.cmd(BITMAP_LAYOUT(Bed_Heat_Icon_Info)) .cmd (BITMAP_LAYOUT(Bed_Heat_Icon_Info))
.cmd(BITMAP_SIZE (Bed_Heat_Icon_Info)) .cmd (BITMAP_SIZE (Bed_Heat_Icon_Info))
.icon (BTN_POS(1,2), BTN_SIZE(1,1), Bed_Heat_Icon_Info, icon_scale); .icon(ICON_POS(BED_POS), Bed_Heat_Icon_Info, icon_scale);
// Draw Fan Percent Bitmap on Bed Heat Button // Draw Fan Percent Bitmap on Bed Heat Button
cmd.cmd(BITMAP_SOURCE(Fan_Icon_Info)) cmd.cmd (BITMAP_SOURCE(Fan_Icon_Info))
.cmd(BITMAP_LAYOUT(Fan_Icon_Info)) .cmd (BITMAP_LAYOUT(Fan_Icon_Info))
.cmd(BITMAP_SIZE (Fan_Icon_Info)) .cmd (BITMAP_SIZE (Fan_Icon_Info))
.icon (BTN_POS(5,2), BTN_SIZE(1,1), Fan_Icon_Info, icon_scale); .icon(ICON_POS(FAN_POS), Fan_Icon_Info, icon_scale);
#ifdef TOUCH_UI_USE_UTF8 #ifdef TOUCH_UI_USE_UTF8
load_utf8_bitmaps(cmd); // Restore font bitmap handles load_utf8_bitmaps(cmd); // Restore font bitmap handles
@ -212,10 +207,10 @@ void StatusScreen::draw_temperature(draw_mode_t what) {
cmd.tag(5) cmd.tag(5)
.font(font_medium) .font(font_medium)
.text(BTN_POS(2,1), BTN_SIZE(3,1), e0_str) .text(TEXT_POS(NOZ_1_POS), e0_str)
.text(BTN_POS(6,1), BTN_SIZE(3,1), e1_str) .text(TEXT_POS(NOZ_2_POS), e1_str)
.text(BTN_POS(2,2), BTN_SIZE(3,1), bed_str) .text(TEXT_POS(BED_POS), bed_str)
.text(BTN_POS(6,2), BTN_SIZE(3,1), fan_str); .text(TEXT_POS(FAN_POS), fan_str);
} }
} }
@ -225,15 +220,18 @@ void StatusScreen::draw_progress(draw_mode_t what) {
CommandProcessor cmd; CommandProcessor cmd;
#if ENABLED(TOUCH_UI_PORTRAIT)
#define TIME_POS BTN_POS(1,3), BTN_SIZE(4,1)
#define PROGRESS_POS BTN_POS(5,3), BTN_SIZE(4,1)
#else
#define TIME_POS BTN_POS(9,1), BTN_SIZE(4,1)
#define PROGRESS_POS BTN_POS(9,2), BTN_SIZE(4,1)
#endif
if (what & BACKGROUND) { if (what & BACKGROUND) {
cmd.tag(0).font(font_medium) cmd.tag(0).font(font_medium)
#ifdef TOUCH_UI_PORTRAIT .fgcolor(progress).button(TIME_POS, F(""), OPT_FLAT)
.fgcolor(progress) .button(BTN_POS(1,3), BTN_SIZE(4,1), F(""), OPT_FLAT) .button(PROGRESS_POS, F(""), OPT_FLAT);
.button(BTN_POS(5,3), BTN_SIZE(4,1), F(""), OPT_FLAT);
#else
.fgcolor(progress) .button(BTN_POS(9,1), BTN_SIZE(4,1), F(""), OPT_FLAT)
.button(BTN_POS(9,2), BTN_SIZE(4,1), F(""), OPT_FLAT);
#endif
} }
if (what & FOREGROUND) { if (what & FOREGROUND) {
@ -248,13 +246,8 @@ void StatusScreen::draw_progress(draw_mode_t what) {
sprintf_P(progress_str, PSTR("%-3d %%"), getProgress_percent() ); sprintf_P(progress_str, PSTR("%-3d %%"), getProgress_percent() );
cmd.font(font_medium) cmd.font(font_medium)
#ifdef TOUCH_UI_PORTRAIT .tag(0).text(TIME_POS, time_str)
.tag(0).text(BTN_POS(1,3), BTN_SIZE(4,1), time_str) .text(PROGRESS_POS, progress_str);
.text(BTN_POS(5,3), BTN_SIZE(4,1), progress_str);
#else
.tag(0).text(BTN_POS(9,1), BTN_SIZE(4,1), time_str)
.text(BTN_POS(9,2), BTN_SIZE(4,1), progress_str);
#endif
} }
} }
@ -266,6 +259,14 @@ void StatusScreen::draw_interaction_buttons(draw_mode_t what) {
if (what & FOREGROUND) { if (what & FOREGROUND) {
using namespace ExtUI; using namespace ExtUI;
#if ENABLED(TOUCH_UI_PORTRAIT)
#define MEDIA_BTN_POS BTN_POS(1,8), BTN_SIZE(2,1)
#define MENU_BTN_POS BTN_POS(3,8), BTN_SIZE(2,1)
#else
#define MEDIA_BTN_POS BTN_POS(1,7), BTN_SIZE(2,2)
#define MENU_BTN_POS BTN_POS(3,7), BTN_SIZE(2,2)
#endif
const bool has_media = isMediaInserted() && !isPrintingFromMedia(); const bool has_media = isMediaInserted() && !isPrintingFromMedia();
CommandProcessor cmd; CommandProcessor cmd;
@ -273,42 +274,29 @@ void StatusScreen::draw_interaction_buttons(draw_mode_t what) {
.font(Theme::font_medium) .font(Theme::font_medium)
.enabled(has_media) .enabled(has_media)
.colors(has_media ? action_btn : normal_btn) .colors(has_media ? action_btn : normal_btn)
.tag(3).button( .tag(3).button(MEDIA_BTN_POS, isPrintingFromMedia() ? GET_TEXT_F(MSG_PRINTING) : GET_TEXT_F(MSG_BUTTON_MEDIA))
#ifdef TOUCH_UI_PORTRAIT .colors(!has_media ? action_btn : normal_btn)
BTN_POS(1,8), BTN_SIZE(2,1), .tag(4).button( MENU_BTN_POS, GET_TEXT_F(MSG_BUTTON_MENU));
#else
BTN_POS(1,7), BTN_SIZE(2,2),
#endif
isPrintingFromMedia() ? GET_TEXT_F(MSG_PRINTING) : GET_TEXT_F(MSG_BUTTON_MEDIA)
).colors(!has_media ? action_btn : normal_btn)
#ifdef TOUCH_UI_PORTRAIT
.tag(4).button( BTN_POS(3,8), BTN_SIZE(2,1), GET_TEXT_F(MSG_BUTTON_MENU));
#else
.tag(4).button( BTN_POS(3,7), BTN_SIZE(2,2), GET_TEXT_F(MSG_BUTTON_MENU));
#endif
} }
#undef GRID_COLS #undef GRID_COLS
} }
void StatusScreen::draw_status_message(draw_mode_t what, const char* message) { void StatusScreen::draw_status_message(draw_mode_t what, const char* message) {
#define GRID_COLS 1 #define GRID_COLS 1
#if ENABLED(TOUCH_UI_PORTRAIT)
#define STATUS_POS BTN_POS(1,4), BTN_SIZE(1,1)
#else
#define STATUS_POS BTN_POS(1,3), BTN_SIZE(1,2)
#endif
if (what & BACKGROUND) { if (what & BACKGROUND) {
CommandProcessor cmd; CommandProcessor cmd;
cmd.fgcolor(Theme::status_msg) cmd.fgcolor(Theme::status_msg)
.tag(0) .tag(0)
#ifdef TOUCH_UI_PORTRAIT .button( STATUS_POS, F(""), OPT_FLAT);
.button( BTN_POS(1,4), BTN_SIZE(1,1), F(""), OPT_FLAT);
#else
.button( BTN_POS(1,3), BTN_SIZE(1,2), F(""), OPT_FLAT);
#endif
draw_text_box(cmd, draw_text_box(cmd, STATUS_POS, message, OPT_CENTER, font_large);
#ifdef TOUCH_UI_PORTRAIT
BTN_POS(1,4), BTN_SIZE(1,1),
#else
BTN_POS(1,3), BTN_SIZE(1,2),
#endif
message, OPT_CENTER, font_large);
} }
#undef GRID_COLS #undef GRID_COLS
} }
@ -326,10 +314,10 @@ void StatusScreen::setStatusMessage(const char* message) {
.cmd(CLEAR(true,true,true)); .cmd(CLEAR(true,true,true));
draw_temperature(BACKGROUND); draw_temperature(BACKGROUND);
draw_progress(BACKGROUND);
draw_axis_position(BACKGROUND);
draw_status_message(BACKGROUND, message); draw_status_message(BACKGROUND, message);
draw_interaction_buttons(BACKGROUND); draw_interaction_buttons(BACKGROUND);
draw_progress(BACKGROUND);
draw_axis_position(BACKGROUND);
storeBackground(); storeBackground();

View File

@ -24,121 +24,149 @@
#pragma once #pragma once
namespace Theme { namespace Theme {
#ifdef TOUCH_UI_LULZBOT_BIO #if ENABLED(TOUCH_UI_COCOA_THEME)
// The Lulzbot Bio uses the color PANTONE 2175C on the case silkscreen. constexpr int accent_hue = 23;
// This translates to HSL(208°, 100%, 39%) as an accent color on the GUI.
constexpr int accent_hue = 208; // Browns and Oranges
constexpr float accent_sat = 0.5; constexpr uint32_t accent_color_1 = hsl_to_rgb(12.8,0.597,0.263); // Darkest
constexpr uint32_t accent_color_2 = hsl_to_rgb(12.8,0.597,0.263);
constexpr uint32_t logo_bg_rgb = 0xffffff; constexpr uint32_t accent_color_3 = hsl_to_rgb( 9.6,0.664,0.443);
constexpr uint32_t logo_fill_rgb = 0xffffff; constexpr uint32_t accent_color_4 = hsl_to_rgb(16.3,0.873,0.537);
constexpr uint32_t logo_stroke_rgb = hsl_to_rgb(accent_hue, 1.0, 0.39); constexpr uint32_t accent_color_5 = hsl_to_rgb(23.0,0.889,0.539);
constexpr uint32_t accent_color_6 = hsl_to_rgb(23.0,0.889,0.539); // Lightest
#else #else
// The Lulzbot logo uses the color PANTONE 382c. // Use linear accent colors
// This translates to HSL(68°, 68%, 52%) as an accent color on the GUI.
constexpr int accent_hue = 68; #if ANY(TOUCH_UI_ROYAL_THEME, TOUCH_UI_FROZEN_THEME)
constexpr float accent_sat = 0.68; // Dark blue accent colors
constexpr int accent_hue = 216;
constexpr float accent_sat = 0.7;
#else
// Green accent colors
constexpr int accent_hue = 68;
constexpr float accent_sat = 0.68;
#endif
constexpr uint32_t logo_bg_rgb = hsl_to_rgb(accent_hue, 0.77, 0.64); // Shades of accent color
constexpr uint32_t logo_fill_rgb = hsl_to_rgb(accent_hue, 0.68, 0.52); // Lulzbot Green constexpr uint32_t accent_color_0 = hsl_to_rgb(accent_hue, accent_sat, 0.15); // Darkest
constexpr uint32_t logo_stroke_rgb = 0x000000; constexpr uint32_t accent_color_1 = hsl_to_rgb(accent_hue, accent_sat, 0.26);
#endif constexpr uint32_t accent_color_2 = hsl_to_rgb(accent_hue, accent_sat, 0.39);
constexpr uint32_t accent_color_3 = hsl_to_rgb(accent_hue, accent_sat, 0.52);
// Shades of accent color constexpr uint32_t accent_color_4 = hsl_to_rgb(accent_hue, accent_sat, 0.65);
constexpr uint32_t accent_color_5 = hsl_to_rgb(accent_hue, accent_sat, 0.78);
#ifdef TOUCH_UI_COCOA_PRESS constexpr uint32_t accent_color_6 = hsl_to_rgb(accent_hue, accent_sat, 0.91); // Lightest
constexpr uint32_t accent_color_1 = hsl_to_rgb(12.8,0.597,0.263); // Darkest
constexpr uint32_t accent_color_2 = hsl_to_rgb(12.8,0.597,0.263);
constexpr uint32_t accent_color_3 = hsl_to_rgb( 9.6,0.664,0.443);
constexpr uint32_t accent_color_4 = hsl_to_rgb(16.3,0.873,0.537);
constexpr uint32_t accent_color_5 = hsl_to_rgb(23.0,0.889,0.539);
constexpr uint32_t accent_color_6 = hsl_to_rgb(23.0,0.889,0.539); // Lightest
#else
constexpr uint32_t accent_color_1 = hsl_to_rgb(accent_hue, accent_sat, 0.26); // Darkest
constexpr uint32_t accent_color_2 = hsl_to_rgb(accent_hue, accent_sat, 0.39);
constexpr uint32_t accent_color_3 = hsl_to_rgb(accent_hue, accent_sat, 0.52);
constexpr uint32_t accent_color_4 = hsl_to_rgb(accent_hue, accent_sat, 0.65);
constexpr uint32_t accent_color_5 = hsl_to_rgb(accent_hue, accent_sat, 0.78);
constexpr uint32_t accent_color_6 = hsl_to_rgb(accent_hue, accent_sat, 0.91); // Lightest
#endif #endif
// Shades of gray // Shades of gray
constexpr float gray_sat = 0.14; constexpr float gray_sat = 0.14;
constexpr uint32_t gray_color_0 = hsl_to_rgb(accent_hue, gray_sat, 0.15); // Darkest
constexpr uint32_t gray_color_1 = hsl_to_rgb(accent_hue, gray_sat, 0.26);
constexpr uint32_t gray_color_2 = hsl_to_rgb(accent_hue, gray_sat, 0.39);
constexpr uint32_t gray_color_3 = hsl_to_rgb(accent_hue, gray_sat, 0.52);
constexpr uint32_t gray_color_4 = hsl_to_rgb(accent_hue, gray_sat, 0.65);
constexpr uint32_t gray_color_5 = hsl_to_rgb(accent_hue, gray_sat, 0.78);
constexpr uint32_t gray_color_6 = hsl_to_rgb(accent_hue, gray_sat, 0.91); // Lightest
constexpr uint32_t gray_color_1 = hsl_to_rgb(accent_hue, gray_sat, 0.26); // Darkest #if ENABLED(TOUCH_UI_ROYAL_THEME)
constexpr uint32_t gray_color_2 = hsl_to_rgb(accent_hue, gray_sat, 0.39); constexpr uint32_t theme_darkest = accent_color_1;
constexpr uint32_t gray_color_3 = hsl_to_rgb(accent_hue, gray_sat, 0.52); constexpr uint32_t theme_dark = accent_color_4;
constexpr uint32_t gray_color_4 = hsl_to_rgb(accent_hue, gray_sat, 0.65);
constexpr uint32_t gray_color_5 = hsl_to_rgb(accent_hue, gray_sat, 0.78);
constexpr uint32_t gray_color_6 = hsl_to_rgb(accent_hue, gray_sat, 0.91); // Lightest
#if NONE(TOUCH_UI_LULZBOT_BIO, TOUCH_UI_COCOA_PRESS) constexpr uint32_t bg_color = gray_color_0;
// Lulzbot TAZ Pro constexpr uint32_t axis_label = gray_color_1;
constexpr uint32_t theme_darkest = gray_color_1;
constexpr uint32_t theme_dark = gray_color_2;
constexpr uint32_t bg_color = theme_darkest; constexpr uint32_t bg_text_enabled = accent_color_6;
constexpr uint32_t bg_text_disabled = theme_dark; constexpr uint32_t bg_text_disabled = gray_color_0;
constexpr uint32_t bg_text_enabled = 0xFFFFFF; constexpr uint32_t bg_normal = accent_color_4;
constexpr uint32_t bg_normal = theme_darkest; constexpr uint32_t fg_disabled = gray_color_0;
constexpr uint32_t fg_normal = accent_color_0;
constexpr uint32_t fg_action = accent_color_1;
constexpr uint32_t fg_normal = theme_dark; constexpr uint32_t logo_bg_rgb = accent_color_1;
constexpr uint32_t fg_action = accent_color_2; constexpr uint32_t logo_fill_rgb = accent_color_0;
constexpr uint32_t fg_disabled = theme_darkest; constexpr uint32_t logo_stroke_rgb = accent_color_4;
#elif ANY(TOUCH_UI_COCOA_THEME, TOUCH_UI_FROZEN_THEME)
constexpr uint32_t theme_darkest = accent_color_1;
constexpr uint32_t theme_dark = accent_color_4;
constexpr uint32_t bg_color = 0xFFFFFF;
constexpr uint32_t axis_label = gray_color_5;
constexpr uint32_t bg_text_enabled = accent_color_1;
constexpr uint32_t bg_text_disabled = gray_color_1;
constexpr uint32_t bg_normal = accent_color_4;
constexpr uint32_t fg_disabled = gray_color_6;
constexpr uint32_t fg_normal = accent_color_1;
constexpr uint32_t fg_action = accent_color_4;
constexpr uint32_t logo_bg_rgb = accent_color_5;
constexpr uint32_t logo_fill_rgb = accent_color_6;
constexpr uint32_t logo_stroke_rgb = accent_color_2;
#else #else
// Lulzbot Bio constexpr uint32_t theme_darkest = gray_color_1;
constexpr uint32_t theme_darkest = accent_color_1; constexpr uint32_t theme_dark = gray_color_2;
constexpr uint32_t theme_dark = accent_color_4;
constexpr uint32_t bg_color = 0xFFFFFF; constexpr uint32_t bg_color = gray_color_1;
constexpr uint32_t bg_text_disabled = gray_color_1; constexpr uint32_t axis_label = gray_color_2;
constexpr uint32_t bg_text_enabled = accent_color_1;
constexpr uint32_t bg_normal = accent_color_4;
constexpr uint32_t fg_normal = accent_color_1; constexpr uint32_t bg_text_enabled = 0xFFFFFF;
constexpr uint32_t fg_action = accent_color_4; constexpr uint32_t bg_text_disabled = gray_color_2;
constexpr uint32_t fg_disabled = gray_color_6; constexpr uint32_t bg_normal = gray_color_1;
constexpr uint32_t fg_disabled = gray_color_1;
constexpr uint32_t fg_normal = gray_color_2;
constexpr uint32_t fg_action = accent_color_2;
constexpr uint32_t shadow_rgb = gray_color_6; constexpr uint32_t logo_bg_rgb = accent_color_4;
constexpr uint32_t stroke_rgb = accent_color_1; constexpr uint32_t logo_fill_rgb = accent_color_3;
constexpr uint32_t fill_rgb = accent_color_3; constexpr uint32_t logo_stroke_rgb = 0x000000;
constexpr uint32_t syringe_rgb = accent_color_5;
#endif #endif
constexpr uint32_t x_axis = 0xFF0000; constexpr uint32_t shadow_rgb = gray_color_6;
constexpr uint32_t y_axis = 0x00BB00; constexpr uint32_t stroke_rgb = accent_color_1;
constexpr uint32_t z_axis = 0x0000BF; constexpr uint32_t fill_rgb = accent_color_3;
constexpr uint32_t e_axis = gray_color_2; constexpr uint32_t syringe_rgb = accent_color_5;
constexpr uint32_t feedrate = gray_color_2;
constexpr uint32_t other = gray_color_2; #if ENABLED(TOUCH_UI_ROYAL_THEME)
constexpr uint32_t x_axis = hsl_to_rgb(0, 1.00, 0.26);
constexpr uint32_t y_axis = hsl_to_rgb(120, 1.00, 0.13);
constexpr uint32_t z_axis = hsl_to_rgb(240, 1.00, 0.10);
#else
constexpr uint32_t x_axis = hsl_to_rgb(0, 1.00, 0.5);
constexpr uint32_t y_axis = hsl_to_rgb(120, 1.00, 0.37);
constexpr uint32_t z_axis = hsl_to_rgb(240, 1.00, 0.37);
#endif
constexpr uint32_t e_axis = axis_label;
constexpr uint32_t feedrate = axis_label;
constexpr uint32_t other = axis_label;
// Status screen // Status screen
constexpr uint32_t progress = gray_color_2; constexpr uint32_t progress = axis_label;
constexpr uint32_t status_msg = gray_color_2; constexpr uint32_t status_msg = axis_label;
constexpr uint32_t fan_speed = 0x377198; #if ENABLED(TOUCH_UI_ROYAL_THEME)
constexpr uint32_t temp = 0x892c78; constexpr uint32_t fan_speed = hsl_to_rgb(240, 0.5, 0.13);
constexpr uint32_t axis_label = gray_color_2; constexpr uint32_t temp = hsl_to_rgb(343, 1.0, 0.23);
#else
constexpr uint32_t fan_speed = hsl_to_rgb(204, 0.47, 0.41);
constexpr uint32_t temp = hsl_to_rgb(311, 0.51, 0.35);
#endif
constexpr uint32_t disabled_icon = gray_color_1; constexpr uint32_t disabled_icon = gray_color_1;
// Calibration Registers Screen // Calibration Registers Screen
constexpr uint32_t transformA = 0x3010D0; constexpr uint32_t transformA = 0x3010D0;
constexpr uint32_t transformB = 0x4010D0; constexpr uint32_t transformB = 0x4010D0;
constexpr uint32_t transformC = 0x5010D0; constexpr uint32_t transformC = 0x5010D0;
constexpr uint32_t transformD = 0x6010D0; constexpr uint32_t transformD = 0x6010D0;
constexpr uint32_t transformE = 0x7010D0; constexpr uint32_t transformE = 0x7010D0;
constexpr uint32_t transformF = 0x8010D0; constexpr uint32_t transformF = 0x8010D0;
constexpr uint32_t transformVal = 0x104010; constexpr uint32_t transformVal = 0x104010;
constexpr btn_colors disabled_btn = {.bg = bg_color, .grad = fg_disabled, .fg = fg_disabled, .rgb = fg_disabled }; constexpr btn_colors disabled_btn = {.bg = bg_color, .grad = fg_disabled, .fg = fg_disabled, .rgb = fg_disabled };
constexpr btn_colors normal_btn = {.bg = fg_action, .grad = 0xFFFFFF, .fg = fg_normal, .rgb = 0xFFFFFF }; constexpr btn_colors normal_btn = {.bg = fg_action, .grad = 0xFFFFFF, .fg = fg_normal, .rgb = 0xFFFFFF };
constexpr btn_colors action_btn = {.bg = bg_color, .grad = 0xFFFFFF, .fg = fg_action, .rgb = 0xFFFFFF }; constexpr btn_colors action_btn = {.bg = bg_color, .grad = 0xFFFFFF, .fg = fg_action, .rgb = 0xFFFFFF };
constexpr btn_colors red_btn = {.bg = 0xFF5555, .grad = 0xFFFFFF, .fg = 0xFF0000, .rgb = 0xFFFFFF }; constexpr btn_colors red_btn = {.bg = 0xFF5555, .grad = 0xFFFFFF, .fg = 0xFF0000, .rgb = 0xFFFFFF };
constexpr btn_colors ui_slider = {.bg = theme_darkest, .grad = 0xFFFFFF, .fg = theme_dark, .rgb = accent_color_3 }; constexpr btn_colors ui_slider = {.bg = theme_darkest, .grad = 0xFFFFFF, .fg = theme_dark, .rgb = accent_color_3 };
constexpr btn_colors ui_toggle = {.bg = theme_darkest, .grad = 0xFFFFFF, .fg = theme_dark, .rgb = 0xFFFFFF }; constexpr btn_colors ui_toggle = {.bg = theme_darkest, .grad = 0xFFFFFF, .fg = theme_dark, .rgb = 0xFFFFFF };
// Temperature color scale // Temperature color scale

View File

@ -35,5 +35,5 @@ const PROGMEM uint16_t logo_stroke[] = {0xADF3, 0x546C, 0x419D, 0x546F, 0x3D05,
#define LOGO_BACKGROUND logo_bg_rgb #define LOGO_BACKGROUND logo_bg_rgb
#define LOGO_PAINT_PATHS \ #define LOGO_PAINT_PATHS \
LOGO_PAINT_PATH(logo_stroke_rgb, logo_stroke) \ LOGO_PAINT_PATH(logo_fill_rgb, logo_fill) \
LOGO_PAINT_PATH(logo_fill_rgb, logo_fill) LOGO_PAINT_PATH(logo_stroke_rgb, logo_stroke)

View File

@ -35,5 +35,5 @@ const PROGMEM uint16_t logo_stroke[] = {0x3C19, 0x70C5, 0x371A, 0x7159, 0x3302,
#define LOGO_BACKGROUND logo_bg_rgb #define LOGO_BACKGROUND logo_bg_rgb
#define LOGO_PAINT_PATHS \ #define LOGO_PAINT_PATHS \
LOGO_PAINT_PATH(logo_stroke_rgb, logo_stroke) \ LOGO_PAINT_PATH(logo_fill_rgb, logo_fill) \
LOGO_PAINT_PATH(logo_fill_rgb, logo_fill) LOGO_PAINT_PATH(logo_stroke_rgb, logo_stroke)

View File

@ -341,10 +341,10 @@ namespace ExtUI {
void onConfigurationStoreWritten(bool success); void onConfigurationStoreWritten(bool success);
void onConfigurationStoreRead(bool success); void onConfigurationStoreRead(bool success);
#if ENABLED(POWER_LOSS_RECOVERY) #if ENABLED(POWER_LOSS_RECOVERY)
void OnPowerLossResume(); void onPowerLossResume();
#endif #endif
#if HAS_PID_HEATING #if HAS_PID_HEATING
void OnPidTuning(const result_t rst); void onPidTuning(const result_t rst);
#endif #endif
}; };

Some files were not shown because too many files have changed in this diff Show More