Merge branch 'bugfix-2.0.x' of https://github.com/MarlinFirmware/Marlin into bugfix-2.0.x
This commit is contained in:
commit
9dd4252b39
|
@ -249,13 +249,27 @@
|
|||
* the E3D Tool Changer. Toolheads are locked with a servo.
|
||||
*/
|
||||
//#define SWITCHING_TOOLHEAD
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
|
||||
/**
|
||||
* Magnetic Switching Toolhead
|
||||
*
|
||||
* Support swappable and dockable toolheads with a magnetic
|
||||
* docking mechanism using movement and no servo.
|
||||
*/
|
||||
//#define MAGNETIC_SWITCHING_TOOLHEAD
|
||||
|
||||
#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_POS 235 // (mm) Y position of the toolhead dock
|
||||
#define SWITCHING_TOOLHEAD_Y_SECURITY 10 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_Y_CLEAR 60 // (mm) Minimum distance from dock for unobstructed X axis
|
||||
#define SWITCHING_TOOLHEAD_X_POS { 215, 0 } // (mm) X positions for parking the extruders
|
||||
#if ENABLED(SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_SERVO_NR 2 // Index of the servo connector
|
||||
#define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 } // (degrees) Angles for Lock, Unlock
|
||||
#elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
|
||||
#define SWITCHING_TOOLHEAD_Y_RELEASE 5 // (mm) Security distance Y axis
|
||||
#define SWITCHING_TOOLHEAD_X_SECURITY -35 // (mm) Security distance X axis
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -377,7 +391,6 @@
|
|||
#define TEMP_SENSOR_5 0
|
||||
#define TEMP_SENSOR_BED 0
|
||||
#define TEMP_SENSOR_CHAMBER 0
|
||||
#define CHAMBER_HEATER_PIN -1 // On/off pin for enclosure heating system
|
||||
|
||||
// Dummy thermistor constant temperature readings, for use with 998 and 999
|
||||
#define DUMMY_THERMISTOR_998_VALUE 25
|
||||
|
@ -396,8 +409,6 @@
|
|||
#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
|
||||
#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
|
||||
|
||||
// Below this temperature the heater will be switched off
|
||||
// because it probably indicates a broken thermistor wire.
|
||||
#define HEATER_0_MINTEMP 5
|
||||
|
@ -407,7 +418,6 @@
|
|||
#define HEATER_4_MINTEMP 5
|
||||
#define HEATER_5_MINTEMP 5
|
||||
#define BED_MINTEMP 5
|
||||
#define CHAMBER_MINTEMP 5
|
||||
|
||||
// Above this temperature the heater will be switched off.
|
||||
// This can protect components from overheating, but NOT from shorts and failures.
|
||||
|
@ -419,7 +429,6 @@
|
|||
#define HEATER_4_MAXTEMP 275
|
||||
#define HEATER_5_MAXTEMP 275
|
||||
#define BED_MAXTEMP 150
|
||||
#define CHAMBER_MAXTEMP 100
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID Settings ================================
|
||||
|
@ -462,7 +471,7 @@
|
|||
#endif // PIDTEMP
|
||||
|
||||
//===========================================================================
|
||||
//============================= PID > Bed Temperature Control ===============
|
||||
//====================== PID > Bed Temperature Control ======================
|
||||
//===========================================================================
|
||||
|
||||
/**
|
||||
|
@ -1413,7 +1422,7 @@
|
|||
//#define NOZZLE_PARK_FEATURE
|
||||
|
||||
#if ENABLED(NOZZLE_PARK_FEATURE)
|
||||
// Specify a park position as { X, Y, Z }
|
||||
// Specify a park position as { X, Y, Z_raise }
|
||||
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
|
||||
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
|
||||
#define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
|
||||
|
@ -1893,6 +1902,12 @@
|
|||
//
|
||||
//#define MKS_MINI_12864
|
||||
|
||||
//
|
||||
// FYSETC variant of the MINI12864 graphic controller with SD support
|
||||
// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
|
||||
//
|
||||
//#define FYSETC_MINI_12864
|
||||
|
||||
//
|
||||
// Factory display for Creality CR-10
|
||||
// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
|
||||
|
@ -2050,10 +2065,10 @@
|
|||
//#define RGBW_LED
|
||||
|
||||
#if EITHER(RGB_LED, RGBW_LED)
|
||||
#define RGB_LED_R_PIN 34
|
||||
#define RGB_LED_G_PIN 43
|
||||
#define RGB_LED_B_PIN 35
|
||||
#define RGB_LED_W_PIN -1
|
||||
//#define RGB_LED_R_PIN 34
|
||||
//#define RGB_LED_G_PIN 43
|
||||
//#define RGB_LED_B_PIN 35
|
||||
//#define RGB_LED_W_PIN -1
|
||||
#endif
|
||||
|
||||
// Support for Adafruit Neopixel LED driver
|
||||
|
|
|
@ -50,6 +50,19 @@
|
|||
#define HEATER_BED_INVERTING true
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Heated Chamber settings
|
||||
*/
|
||||
#if TEMP_SENSOR_CHAMBER
|
||||
#define CHAMBER_MINTEMP 5
|
||||
#define CHAMBER_MAXTEMP 60
|
||||
#define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
|
||||
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
|
||||
//#define CHAMBER_LIMIT_SWITCHING
|
||||
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
|
||||
//#define HEATER_CHAMBER_INVERTING false
|
||||
#endif
|
||||
|
||||
#if DISABLED(PIDTEMPBED)
|
||||
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||
|
@ -127,8 +140,8 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMP)
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
|
||||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||
|
@ -456,6 +469,7 @@
|
|||
#define Z_HOME_BUMP_MM 2
|
||||
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
|
||||
//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
|
||||
|
||||
// When G28 is called, this option will make Y home before X
|
||||
//#define HOME_Y_BEFORE_X
|
||||
|
@ -678,6 +692,7 @@
|
|||
* A (A shifted) B (B shifted) IC
|
||||
* Smoothie 0x2C (0x58) 0x2D (0x5A) MCP4451
|
||||
* AZTEEG_X3_PRO 0x2C (0x58) 0x2E (0x5C) MCP4451
|
||||
* AZTEEG_X5_MINI 0x2C (0x58) 0x2E (0x5C) MCP4451
|
||||
* AZTEEG_X5_MINI_WIFI 0x58 0x5C MCP4451
|
||||
* MIGHTYBOARD_REVE 0x2F (0x5E) MCP4018
|
||||
*/
|
||||
|
@ -770,8 +785,11 @@
|
|||
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||
#define SDCARD_RATHERRECENTFIRST
|
||||
|
||||
// Add an option in the menu to run all auto#.g files
|
||||
//#define MENU_ADDAUTOSTART
|
||||
#define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing
|
||||
|
||||
//#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files
|
||||
|
||||
#define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27")
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
|
@ -959,6 +977,12 @@
|
|||
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
|
||||
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
|
||||
//#define STATUS_HEAT_PERCENT // Show heating in a progress bar
|
||||
//#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
//#define MARLIN_INVADERS
|
||||
//#define MARLIN_SNAKE
|
||||
|
||||
// Frivolous Game Options
|
||||
//#define MARLIN_BRICKOUT
|
||||
|
@ -1000,13 +1024,15 @@
|
|||
#if ENABLED(DOUBLECLICK_FOR_Z_BABYSTEPPING)
|
||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||
// Note: Extra time may be added to mitigate controller latency.
|
||||
//#define BABYSTEP_ALWAYS_AVAILABLE // Allow babystepping at all times (not just during movement).
|
||||
#define BABYSTEP_ALWAYS_AVAILABLE // Allow babystepping at all times (not just during movement).
|
||||
//#define MOVE_Z_WHEN_IDLE // Jump to the move Z menu on doubleclick when printer is idle.
|
||||
#if ENABLED(MOVE_Z_WHEN_IDLE)
|
||||
#define MOVE_Z_IDLE_MULTIPLICATOR 1 // Multiply 1mm by this factor for the move step size.
|
||||
#endif
|
||||
#endif
|
||||
|
||||
//#define BABYSTEP_DISPLAY_TOTAL // Display total babysteps since last G28
|
||||
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
//#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets
|
||||
|
|
|
@ -739,24 +739,24 @@
|
|||
|
||||
#endif // !USBCON && (UBRRH || UBRR0H || UBRR1H || UBRR2H || UBRR3H)
|
||||
|
||||
#ifdef INTERNAL_SERIAL_PORT
|
||||
|
||||
#if defined(INTERNAL_SERIAL_PORT)
|
||||
ISR(SERIAL_REGNAME(USART,INTERNAL_SERIAL_PORT,_RX_vect)) {
|
||||
MarlinSerial<MarlinInternalSerialCfg<INTERNAL_SERIAL_PORT>>::store_rxd_char();
|
||||
}
|
||||
|
||||
ISR(SERIAL_REGNAME(USART,INTERNAL_SERIAL_PORT,_RX_vect)) {
|
||||
MarlinSerial<MarlinInternalSerialCfg<INTERNAL_SERIAL_PORT>>::store_rxd_char();
|
||||
}
|
||||
ISR(SERIAL_REGNAME(USART,INTERNAL_SERIAL_PORT,_UDRE_vect)) {
|
||||
MarlinSerial<MarlinInternalSerialCfg<INTERNAL_SERIAL_PORT>>::_tx_udr_empty_irq();
|
||||
}
|
||||
|
||||
ISR(SERIAL_REGNAME(USART,INTERNAL_SERIAL_PORT,_UDRE_vect)) {
|
||||
MarlinSerial<MarlinInternalSerialCfg<INTERNAL_SERIAL_PORT>>::_tx_udr_empty_irq();
|
||||
}
|
||||
// Preinstantiate
|
||||
template class MarlinSerial<MarlinInternalSerialCfg<INTERNAL_SERIAL_PORT>>;
|
||||
|
||||
// Preinstantiate
|
||||
template class MarlinSerial<MarlinInternalSerialCfg<INTERNAL_SERIAL_PORT>>;
|
||||
|
||||
// Instantiate
|
||||
MarlinSerial<MarlinInternalSerialCfg<INTERNAL_SERIAL_PORT>> internalSerial;
|
||||
// Instantiate
|
||||
MarlinSerial<MarlinInternalSerialCfg<INTERNAL_SERIAL_PORT>> internalSerial;
|
||||
|
||||
#endif
|
||||
|
||||
// For AT90USB targets use the UART for BT interfacing
|
||||
#if defined(USBCON) && ENABLED(BLUETOOTH)
|
||||
HardwareSerial bluetoothSerial;
|
||||
|
|
|
@ -276,7 +276,7 @@
|
|||
#endif // !USBCON
|
||||
|
||||
|
||||
#if defined(INTERNAL_SERIAL_PORT)
|
||||
#ifdef INTERNAL_SERIAL_PORT
|
||||
template <uint8_t serial>
|
||||
struct MarlinInternalSerialCfg {
|
||||
static constexpr int PORT = serial;
|
||||
|
|
|
@ -46,8 +46,8 @@
|
|||
* Sanity checks for Spindle / Laser
|
||||
*/
|
||||
#if ENABLED(SPINDLE_LASER_ENABLE)
|
||||
#if !PIN_EXISTS(SPINDLE_LASER_ENABLE)
|
||||
#error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENABLE_PIN."
|
||||
#if !PIN_EXISTS(SPINDLE_LASER_ENA)
|
||||
#error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENA_PIN."
|
||||
#elif SPINDLE_DIR_CHANGE && !PIN_EXISTS(SPINDLE_DIR)
|
||||
#error "SPINDLE_DIR_PIN not defined."
|
||||
#elif ENABLED(SPINDLE_LASER_PWM) && PIN_EXISTS(SPINDLE_LASER_PWM)
|
||||
|
|
33
Marlin/src/HAL/HAL_ESP32/FlushableHardwareSerial.cpp
Normal file
33
Marlin/src/HAL/HAL_ESP32/FlushableHardwareSerial.cpp
Normal file
|
@ -0,0 +1,33 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#include "FlushableHardwareSerial.h"
|
||||
|
||||
#ifdef ARDUINO_ARCH_ESP32
|
||||
|
||||
FlushableHardwareSerial::FlushableHardwareSerial(int uart_nr)
|
||||
: HardwareSerial(uart_nr)
|
||||
{}
|
||||
|
||||
FlushableHardwareSerial flushableSerial(0);
|
||||
|
||||
#endif // ARDUINO_ARCH_ESP32
|
36
Marlin/src/HAL/HAL_ESP32/FlushableHardwareSerial.h
Normal file
36
Marlin/src/HAL/HAL_ESP32/FlushableHardwareSerial.h
Normal file
|
@ -0,0 +1,36 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifdef ARDUINO_ARCH_ESP32
|
||||
|
||||
#include <HardwareSerial.h>
|
||||
|
||||
class FlushableHardwareSerial : public HardwareSerial {
|
||||
public:
|
||||
FlushableHardwareSerial(int uart_nr);
|
||||
|
||||
inline void flushTX(void) { /* No need to flush the hardware serial, but defined here for compatibility. */ }
|
||||
};
|
||||
|
||||
extern FlushableHardwareSerial flushableSerial;
|
||||
|
||||
#endif // ARDUINO_ARCH_ESP32
|
|
@ -41,7 +41,10 @@
|
|||
#endif
|
||||
#if ENABLED(WEBSUPPORT)
|
||||
#include "web.h"
|
||||
#include "spiffs.h"
|
||||
#endif
|
||||
#elif ENABLED(EEPROM_SETTINGS)
|
||||
#include "spiffs.h"
|
||||
#endif
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
|
@ -95,9 +98,12 @@ void HAL_init(void) {
|
|||
OTA_init();
|
||||
#endif
|
||||
#if ENABLED(WEBSUPPORT)
|
||||
spiffs_init();
|
||||
web_init();
|
||||
#endif
|
||||
server.begin();
|
||||
#elif ENABLED(EEPROM_SETTINGS)
|
||||
spiffs_init();
|
||||
#endif
|
||||
|
||||
i2s_init();
|
||||
|
@ -111,7 +117,7 @@ void HAL_idletask(void) {
|
|||
|
||||
void HAL_clear_reset_source(void) { }
|
||||
|
||||
uint8_t HAL_get_reset_source (void) {
|
||||
uint8_t HAL_get_reset_source(void) {
|
||||
return rtc_get_reset_reason(1);
|
||||
}
|
||||
|
||||
|
@ -148,7 +154,7 @@ void HAL_adc_init() {
|
|||
esp_adc_cal_characterize(ADC_UNIT_1, ADC_ATTEN_DB_11, ADC_WIDTH_BIT_12, V_REF, &characteristics);
|
||||
}
|
||||
|
||||
void HAL_adc_start_conversion (uint8_t adc_pin) {
|
||||
void HAL_adc_start_conversion(uint8_t adc_pin) {
|
||||
uint32_t mv;
|
||||
esp_adc_cal_get_voltage((adc_channel_t)get_channel(adc_pin), &characteristics, &mv);
|
||||
|
||||
|
|
|
@ -48,6 +48,7 @@
|
|||
#include "HAL_timers_ESP32.h"
|
||||
|
||||
#include "WebSocketSerial.h"
|
||||
#include "FlushableHardwareSerial.h"
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Defines
|
||||
|
@ -55,7 +56,7 @@
|
|||
|
||||
extern portMUX_TYPE spinlock;
|
||||
|
||||
#define MYSERIAL0 Serial
|
||||
#define MYSERIAL0 flushableSerial
|
||||
|
||||
#if ENABLED(WIFISUPPORT)
|
||||
#define NUM_SERIAL 2
|
||||
|
@ -96,7 +97,7 @@ extern uint16_t HAL_adc_result;
|
|||
void HAL_clear_reset_source (void);
|
||||
|
||||
// reset reason
|
||||
uint8_t HAL_get_reset_source (void);
|
||||
uint8_t HAL_get_reset_source(void);
|
||||
|
||||
void _delay_ms(int delay);
|
||||
|
||||
|
@ -119,7 +120,7 @@ void HAL_adc_init(void);
|
|||
#define HAL_READ_ADC() HAL_adc_result
|
||||
#define HAL_ADC_READY() true
|
||||
|
||||
void HAL_adc_start_conversion (uint8_t adc_pin);
|
||||
void HAL_adc_start_conversion(uint8_t adc_pin);
|
||||
|
||||
#define GET_PIN_MAP_PIN(index) index
|
||||
#define GET_PIN_MAP_INDEX(pin) pin
|
||||
|
|
|
@ -44,6 +44,15 @@ static SPISettings spiConfig;
|
|||
// Public functions
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
#if ENABLED(SOFTWARE_SPI)
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Software SPI
|
||||
// --------------------------------------------------------------------------
|
||||
#error "Software SPI not supported for ESP32. Use Hardware SPI."
|
||||
|
||||
#else
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Hardware SPI
|
||||
// --------------------------------------------------------------------------
|
||||
|
@ -61,13 +70,14 @@ void spiInit(uint8_t spiRate) {
|
|||
uint32_t clock;
|
||||
|
||||
switch (spiRate) {
|
||||
case SPI_FULL_SPEED: clock = SPI_CLOCK_DIV2; break;
|
||||
case SPI_HALF_SPEED: clock = SPI_CLOCK_DIV4; break;
|
||||
case SPI_QUARTER_SPEED: clock = SPI_CLOCK_DIV8; break;
|
||||
case SPI_EIGHTH_SPEED: clock = SPI_CLOCK_DIV16; break;
|
||||
case SPI_SPEED_5: clock = SPI_CLOCK_DIV32; break;
|
||||
case SPI_SPEED_6: clock = SPI_CLOCK_DIV64; break;
|
||||
default: clock = SPI_CLOCK_DIV2; // Default from the SPI library
|
||||
case SPI_FULL_SPEED: clock = 16000000; break;
|
||||
case SPI_HALF_SPEED: clock = 8000000; break;
|
||||
case SPI_QUARTER_SPEED: clock = 4000000; break;
|
||||
case SPI_EIGHTH_SPEED: clock = 2000000; break;
|
||||
case SPI_SIXTEENTH_SPEED: clock = 1000000; break;
|
||||
case SPI_SPEED_5: clock = 500000; break;
|
||||
case SPI_SPEED_6: clock = 250000; break;
|
||||
default: clock = 1000000; // Default from the SPI library
|
||||
}
|
||||
|
||||
spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0);
|
||||
|
@ -106,4 +116,6 @@ void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode)
|
|||
SPI.beginTransaction(spiConfig);
|
||||
}
|
||||
|
||||
#endif // !SOFTWARE_SPI
|
||||
|
||||
#endif // ARDUINO_ARCH_ESP32
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
|
|
|
@ -64,6 +64,9 @@
|
|||
#define PWM_PIN(P) true
|
||||
#define USEABLE_HARDWARE_PWM(P) PWM_PIN(P)
|
||||
|
||||
// Toggle pin value
|
||||
#define TOGGLE(IO) WRITE(IO, !READ(IO))
|
||||
|
||||
//
|
||||
// Ports and functions
|
||||
//
|
||||
|
|
93
Marlin/src/HAL/HAL_ESP32/persistent_store_spiffs.cpp
Normal file
93
Marlin/src/HAL/HAL_ESP32/persistent_store_spiffs.cpp
Normal file
|
@ -0,0 +1,93 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifdef ARDUINO_ARCH_ESP32
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#if ENABLED(EEPROM_SETTINGS) && DISABLED(FLASH_EEPROM_EMULATION)
|
||||
|
||||
#include "../shared/persistent_store_api.h"
|
||||
|
||||
#include "SPIFFS.h"
|
||||
#include "FS.h"
|
||||
#include "spiffs.h"
|
||||
|
||||
#define HAL_ESP32_EEPROM_SIZE 4096
|
||||
|
||||
File eeprom_file;
|
||||
|
||||
bool PersistentStore::access_start() {
|
||||
if (spiffs_initialized) {
|
||||
eeprom_file = SPIFFS.open("/eeprom.dat", "r+");
|
||||
|
||||
size_t file_size = eeprom_file.size();
|
||||
if (file_size < HAL_ESP32_EEPROM_SIZE) {
|
||||
bool write_ok = eeprom_file.seek(file_size);
|
||||
|
||||
while (write_ok && file_size < HAL_ESP32_EEPROM_SIZE) {
|
||||
write_ok = eeprom_file.write(0xFF) == 1;
|
||||
file_size++;
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
bool PersistentStore::access_finish() {
|
||||
eeprom_file.close();
|
||||
return true;
|
||||
}
|
||||
|
||||
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
|
||||
if (!eeprom_file.seek(pos)) return true; // return true for any error
|
||||
if (eeprom_file.write(value, size) != size) return true;
|
||||
|
||||
crc16(crc, value, size);
|
||||
pos += size;
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
|
||||
if (!eeprom_file.seek(pos)) return true; // return true for any error
|
||||
|
||||
if (writing) {
|
||||
if (eeprom_file.read(value, size) != size) return true;
|
||||
crc16(crc, value, size);
|
||||
}
|
||||
else {
|
||||
uint8_t tmp[size];
|
||||
if (eeprom_file.read(tmp, size) != size) return true;
|
||||
crc16(crc, tmp, size);
|
||||
}
|
||||
|
||||
pos += size;
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
size_t PersistentStore::capacity() { return HAL_ESP32_EEPROM_SIZE; }
|
||||
|
||||
#endif // EEPROM_SETTINGS
|
||||
#endif // ARDUINO_ARCH_ESP32
|
|
@ -20,21 +20,25 @@
|
|||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* M49.cpp - Toggle the G26 debug flag
|
||||
*/
|
||||
#ifdef ARDUINO_ARCH_ESP32
|
||||
|
||||
#include "../../../inc/MarlinConfig.h"
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if ENABLED(G26_MESH_VALIDATION)
|
||||
#if EITHER(WEBSUPPORT, EEPROM_SETTINGS)
|
||||
|
||||
#include "../../gcode.h"
|
||||
#include "../../../feature/bedlevel/bedlevel.h"
|
||||
#include "../../core/serial.h"
|
||||
|
||||
void GcodeSuite::M49() {
|
||||
g26_debug_flag ^= true;
|
||||
SERIAL_ECHOPGM("G26 Debug: ");
|
||||
serialprintPGM(g26_debug_flag ? PSTR("On\n") : PSTR("Off\n"));
|
||||
#include "FS.h"
|
||||
#include "SPIFFS.h"
|
||||
|
||||
bool spiffs_initialized;
|
||||
|
||||
void spiffs_init() {
|
||||
if (SPIFFS.begin())
|
||||
spiffs_initialized = true;
|
||||
else
|
||||
SERIAL_ECHO_MSG("SPIFFS mount failed");
|
||||
}
|
||||
|
||||
#endif // G26_MESH_VALIDATION
|
||||
#endif // WEBSUPPORT
|
||||
#endif // ARDUINO_ARCH_ESP32
|
26
Marlin/src/HAL/HAL_ESP32/spiffs.h
Normal file
26
Marlin/src/HAL/HAL_ESP32/spiffs.h
Normal file
|
@ -0,0 +1,26 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
extern bool spiffs_initialized;
|
||||
|
||||
void spiffs_init();
|
|
@ -1,7 +1,9 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
|
||||
* Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
|
@ -15,6 +17,7 @@
|
|||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifdef ARDUINO_ARCH_ESP32
|
||||
|
@ -23,9 +26,6 @@
|
|||
|
||||
#if ENABLED(WEBSUPPORT)
|
||||
|
||||
#include "../../core/serial.h"
|
||||
|
||||
#include "FS.h"
|
||||
#include "SPIFFS.h"
|
||||
#include "wifi.h"
|
||||
|
||||
|
@ -37,12 +37,8 @@ void onNotFound(AsyncWebServerRequest *request){
|
|||
|
||||
void web_init() {
|
||||
server.addHandler(&events); // attach AsyncEventSource
|
||||
if (SPIFFS.begin()) {
|
||||
server.serveStatic("/", SPIFFS, "/www").setDefaultFile("index.html");
|
||||
server.onNotFound(onNotFound);
|
||||
}
|
||||
else
|
||||
SERIAL_ECHO_MSG("SPIFFS Mount Failed");
|
||||
server.serveStatic("/", SPIFFS, "/www").setDefaultFile("index.html");
|
||||
server.onNotFound(onNotFound);
|
||||
}
|
||||
|
||||
#endif // WEBSUPPORT
|
||||
|
|
|
@ -1,7 +1,9 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
|
||||
* Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
|
@ -15,6 +17,7 @@
|
|||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
|
|
|
@ -1,7 +1,9 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
|
||||
* Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
|
@ -15,6 +17,7 @@
|
|||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifdef ARDUINO_ARCH_ESP32
|
||||
|
|
|
@ -1,7 +1,9 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
|
||||
* Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
|
@ -15,6 +17,7 @@
|
|||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
|
|
|
@ -25,8 +25,8 @@
|
|||
*/
|
||||
|
||||
#if ENABLED(SPINDLE_LASER_ENABLE)
|
||||
#if !PIN_EXISTS(SPINDLE_LASER_ENABLE)
|
||||
#error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENABLE_PIN."
|
||||
#if !PIN_EXISTS(SPINDLE_LASER_ENA)
|
||||
#error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENA_PIN."
|
||||
#elif SPINDLE_DIR_CHANGE && !PIN_EXISTS(SPINDLE_DIR)
|
||||
#error "SPINDLE_DIR_PIN not defined."
|
||||
#elif ENABLED(SPINDLE_LASER_PWM) && PIN_EXISTS(SPINDLE_LASER_PWM)
|
||||
|
|
|
@ -52,11 +52,13 @@ int freeMemory() {
|
|||
return result;
|
||||
}
|
||||
|
||||
// scan command line for code
|
||||
// return index into pin map array if found and the pin is valid.
|
||||
// return dval if not found or not a valid pin.
|
||||
int16_t PARSED_PIN_INDEX(const char code, const int16_t dval) {
|
||||
const uint16_t val = (uint16_t)parser.intval(code), port = val / 100, pin = val % 100;
|
||||
const int16_t ind = (port < (NUM_DIGITAL_PINS >> 5) && (pin < 32))
|
||||
? GET_PIN_MAP_INDEX(port << 5 | pin) : -2;
|
||||
return ind > -2 ? ind : dval;
|
||||
const uint16_t val = (uint16_t)parser.intval(code, -1), port = val / 100, pin = val % 100;
|
||||
const int16_t ind = (port < ((NUM_DIGITAL_PINS) >> 5) && pin < 32) ? GET_PIN_MAP_INDEX((port << 5) | pin) : -2;
|
||||
return ind > -1 ? ind : dval;
|
||||
}
|
||||
|
||||
void flashFirmware(int16_t value) {
|
||||
|
|
|
@ -25,8 +25,8 @@
|
|||
*/
|
||||
|
||||
#if ENABLED(SPINDLE_LASER_ENABLE)
|
||||
#if !PIN_EXISTS(SPINDLE_LASER_ENABLE)
|
||||
#error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENABLE_PIN."
|
||||
#if !PIN_EXISTS(SPINDLE_LASER_ENA)
|
||||
#error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENA_PIN."
|
||||
#elif SPINDLE_DIR_CHANGE && !PIN_EXISTS(SPINDLE_DIR)
|
||||
#error "SPINDLE_DIR_PIN not defined."
|
||||
#elif ENABLED(SPINDLE_LASER_PWM) && PIN_EXISTS(SPINDLE_LASER_PWM)
|
||||
|
|
|
@ -40,6 +40,12 @@
|
|||
#define PRINT_PIN(p) do {sprintf_P(buffer, PSTR("%d.%02d"), LPC1768_PIN_PORT(p), LPC1768_PIN_PIN(p)); SERIAL_ECHO(buffer);} while (0)
|
||||
#define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin
|
||||
|
||||
// pins that will cause hang/reset/disconnect in M43 Toggle and Watch utilities
|
||||
// uses pin index
|
||||
#ifndef M43_NEVER_TOUCH
|
||||
#define M43_NEVER_TOUCH(Q) ((Q) == 29 || (Q) == 30 || (Q) == 73) // USB pins
|
||||
#endif
|
||||
|
||||
// active ADC function/mode/code values for PINSEL registers
|
||||
constexpr int8_t ADC_pin_mode(pin_t pin) {
|
||||
return (LPC1768_PIN_PORT(pin) == 0 && LPC1768_PIN_PIN(pin) == 2 ? 2 :
|
||||
|
|
|
@ -74,8 +74,10 @@ void watchdog_reset() {
|
|||
|
||||
#else
|
||||
|
||||
void HAL_clear_reset_source(void) {}
|
||||
uint8_t HAL_get_reset_source(void) { return RST_POWER_ON; }
|
||||
void watchdog_init(void) {}
|
||||
void watchdog_reset(void) {}
|
||||
void HAL_clear_reset_source(void) {}
|
||||
uint8_t HAL_get_reset_source(void) { return RST_POWER_ON; }
|
||||
|
||||
#endif // USE_WATCHDOG
|
||||
|
||||
|
|
|
@ -36,8 +36,10 @@
|
|||
#if ENABLED(EEPROM_EMULATED_WITH_SRAM)
|
||||
#if STM32F7xx
|
||||
#include "stm32f7xx_ll_pwr.h"
|
||||
#elif STM32F4xx
|
||||
#include "stm32f4xx_ll_pwr.h"
|
||||
#else
|
||||
#error "EEPROM_EMULATED_WITH_SRAM is currently only supported for STM32F7xx"
|
||||
#error "EEPROM_EMULATED_WITH_SRAM is currently only supported for STM32F4xx and STM32F7xx"
|
||||
#endif
|
||||
#endif // EEPROM_EMULATED_WITH_SRAM
|
||||
|
||||
|
@ -118,7 +120,7 @@ void HAL_init(void) {
|
|||
|
||||
void HAL_clear_reset_source(void) { __HAL_RCC_CLEAR_RESET_FLAGS(); }
|
||||
|
||||
uint8_t HAL_get_reset_source (void) {
|
||||
uint8_t HAL_get_reset_source(void) {
|
||||
if (__HAL_RCC_GET_FLAG(RCC_FLAG_IWDGRST) != RESET) return RST_WATCHDOG;
|
||||
if (__HAL_RCC_GET_FLAG(RCC_FLAG_SFTRST) != RESET) return RST_SOFTWARE;
|
||||
if (__HAL_RCC_GET_FLAG(RCC_FLAG_PINRST) != RESET) return RST_EXTERNAL;
|
||||
|
|
|
@ -165,7 +165,7 @@ void HAL_init(void);
|
|||
void HAL_clear_reset_source (void);
|
||||
|
||||
/** reset reason */
|
||||
uint8_t HAL_get_reset_source (void);
|
||||
uint8_t HAL_get_reset_source(void);
|
||||
|
||||
void _delay_ms(const int delay);
|
||||
|
||||
|
|
|
@ -25,8 +25,8 @@
|
|||
* Test Re-ARM specific configuration values for errors at compile-time.
|
||||
*/
|
||||
#if ENABLED(SPINDLE_LASER_ENABLE)
|
||||
#if !PIN_EXISTS(SPINDLE_LASER_ENABLE)
|
||||
#error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENABLE_PIN."
|
||||
#if !PIN_EXISTS(SPINDLE_LASER_ENA)
|
||||
#error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENA_PIN."
|
||||
#elif SPINDLE_DIR_CHANGE && !PIN_EXISTS(SPINDLE_DIR)
|
||||
#error "SPINDLE_DIR_PIN not defined."
|
||||
#elif ENABLED(SPINDLE_LASER_PWM) && PIN_EXISTS(SPINDLE_LASER_PWM)
|
||||
|
|
|
@ -28,8 +28,8 @@
|
|||
* Test Re-ARM specific configuration values for errors at compile-time.
|
||||
*/
|
||||
#if ENABLED(SPINDLE_LASER_ENABLE)
|
||||
#if !PIN_EXISTS(SPINDLE_LASER_ENABLE)
|
||||
#error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENABLE_PIN."
|
||||
#if !PIN_EXISTS(SPINDLE_LASER_ENA)
|
||||
#error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENA_PIN."
|
||||
#elif SPINDLE_DIR_CHANGE && !PIN_EXISTS(SPINDLE_DIR)
|
||||
#error "SPINDLE_DIR_PIN not defined."
|
||||
#elif ENABLED(SPINDLE_LASER_PWM) && PIN_EXISTS(SPINDLE_LASER_PWM)
|
||||
|
|
|
@ -1,50 +1,48 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file EEPROM/EEPROM_Emulation/inc/eeprom.h
|
||||
* @author MCD Application Team
|
||||
* @version V1.2.6
|
||||
* @date 04-November-2016
|
||||
* @brief This file contains all the functions prototypes for the EEPROM
|
||||
* emulation firmware library.
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© Copyright <EFBFBD> 2016 STMicroelectronics International N.V.
|
||||
* All rights reserved.</center></h2>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted, provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistribution of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
* 3. Neither the name of STMicroelectronics nor the names of other
|
||||
* contributors to this software may be used to endorse or promote products
|
||||
* derived from this software without specific written permission.
|
||||
* 4. This software, including modifications and/or derivative works of this
|
||||
* software, must execute solely and exclusively on microcontroller or
|
||||
* microprocessor devices manufactured by or for STMicroelectronics.
|
||||
* 5. Redistribution and use of this software other than as permitted under
|
||||
* this license is void and will automatically terminate your rights under
|
||||
* this license.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
|
||||
* AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
|
||||
* PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY
|
||||
* RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
|
||||
* SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
|
||||
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
|
||||
* OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
|
||||
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
|
||||
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
|
||||
* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
******************************************************************************
|
||||
*/
|
||||
/******************************************************************************
|
||||
* @file eeprom_emul.h
|
||||
* @author MCD Application Team
|
||||
* @version V1.2.6
|
||||
* @date 04-November-2016
|
||||
* @brief This file contains all the functions prototypes for the EEPROM
|
||||
* emulation firmware library.
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© Copyright <EFBFBD> 2016 STMicroelectronics International N.V.
|
||||
* All rights reserved.</center></h2>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted, provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistribution of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
* 3. Neither the name of STMicroelectronics nor the names of other
|
||||
* contributors to this software may be used to endorse or promote products
|
||||
* derived from this software without specific written permission.
|
||||
* 4. This software, including modifications and/or derivative works of this
|
||||
* software, must execute solely and exclusively on microcontroller or
|
||||
* microprocessor devices manufactured by or for STMicroelectronics.
|
||||
* 5. Redistribution and use of this software other than as permitted under
|
||||
* this license is void and will automatically terminate your rights under
|
||||
* this license.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
|
||||
* AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
|
||||
* PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY
|
||||
* RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
|
||||
* SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
|
||||
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
|
||||
* OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
|
||||
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
|
||||
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
|
||||
* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
******************************************************************************/
|
||||
#pragma once
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
|
|
|
@ -79,7 +79,7 @@ void sei(void) { interrupts(); }
|
|||
|
||||
void HAL_clear_reset_source(void) { __HAL_RCC_CLEAR_RESET_FLAGS(); }
|
||||
|
||||
uint8_t HAL_get_reset_source (void) {
|
||||
uint8_t HAL_get_reset_source(void) {
|
||||
if (__HAL_RCC_GET_FLAG(RCC_FLAG_IWDGRST) != RESET) return RST_WATCHDOG;
|
||||
|
||||
if (__HAL_RCC_GET_FLAG(RCC_FLAG_SFTRST) != RESET) return RST_SOFTWARE;
|
||||
|
|
|
@ -170,7 +170,7 @@ extern uint16_t HAL_adc_result;
|
|||
void HAL_clear_reset_source (void);
|
||||
|
||||
/** reset reason */
|
||||
uint8_t HAL_get_reset_source (void);
|
||||
uint8_t HAL_get_reset_source(void);
|
||||
|
||||
void _delay_ms(const int delay);
|
||||
|
||||
|
|
|
@ -24,8 +24,8 @@
|
|||
* Test Re-ARM specific configuration values for errors at compile-time.
|
||||
*/
|
||||
#if ENABLED(SPINDLE_LASER_ENABLE)
|
||||
#if !PIN_EXISTS(SPINDLE_LASER_ENABLE)
|
||||
#error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENABLE_PIN."
|
||||
#if !PIN_EXISTS(SPINDLE_LASER_ENA)
|
||||
#error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENA_PIN."
|
||||
#elif SPINDLE_DIR_CHANGE && !PIN_EXISTS(SPINDLE_DIR)
|
||||
#error "SPINDLE_DIR_PIN not defined."
|
||||
#elif ENABLED(SPINDLE_LASER_PWM) && PIN_EXISTS(SPINDLE_LASER_PWM)
|
||||
|
|
|
@ -1,50 +1,48 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file EEPROM/EEPROM_Emulation/inc/eeprom.h
|
||||
* @author MCD Application Team
|
||||
* @version V1.2.6
|
||||
* @date 04-November-2016
|
||||
* @brief This file contains all the functions prototypes for the EEPROM
|
||||
* emulation firmware library.
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© Copyright © 2016 STMicroelectronics International N.V.
|
||||
* All rights reserved.</center></h2>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted, provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistribution of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
* 3. Neither the name of STMicroelectronics nor the names of other
|
||||
* contributors to this software may be used to endorse or promote products
|
||||
* derived from this software without specific written permission.
|
||||
* 4. This software, including modifications and/or derivative works of this
|
||||
* software, must execute solely and exclusively on microcontroller or
|
||||
* microprocessor devices manufactured by or for STMicroelectronics.
|
||||
* 5. Redistribution and use of this software other than as permitted under
|
||||
* this license is void and will automatically terminate your rights under
|
||||
* this license.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
|
||||
* AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
|
||||
* PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY
|
||||
* RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
|
||||
* SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
|
||||
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
|
||||
* OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
|
||||
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
|
||||
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
|
||||
* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
******************************************************************************
|
||||
*/
|
||||
/******************************************************************************
|
||||
* @file eeprom_emul.h
|
||||
* @author MCD Application Team
|
||||
* @version V1.2.6
|
||||
* @date 04-November-2016
|
||||
* @brief This file contains all the functions prototypes for the EEPROM
|
||||
* emulation firmware library.
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© Copyright © 2016 STMicroelectronics International N.V.
|
||||
* All rights reserved.</center></h2>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted, provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistribution of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
* 3. Neither the name of STMicroelectronics nor the names of other
|
||||
* contributors to this software may be used to endorse or promote products
|
||||
* derived from this software without specific written permission.
|
||||
* 4. This software, including modifications and/or derivative works of this
|
||||
* software, must execute solely and exclusively on microcontroller or
|
||||
* microprocessor devices manufactured by or for STMicroelectronics.
|
||||
* 5. Redistribution and use of this software other than as permitted under
|
||||
* this license is void and will automatically terminate your rights under
|
||||
* this license.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
|
||||
* AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
|
||||
* PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY
|
||||
* RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
|
||||
* SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
|
||||
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
|
||||
* OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
|
||||
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
|
||||
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
|
||||
* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
*****************************************************************************/
|
||||
#pragma once
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
|
|
|
@ -79,7 +79,7 @@ void sei(void) { interrupts(); }
|
|||
|
||||
void HAL_clear_reset_source(void) { __HAL_RCC_CLEAR_RESET_FLAGS(); }
|
||||
|
||||
uint8_t HAL_get_reset_source (void) {
|
||||
uint8_t HAL_get_reset_source(void) {
|
||||
if (__HAL_RCC_GET_FLAG(RCC_FLAG_IWDGRST) != RESET)
|
||||
return RST_WATCHDOG;
|
||||
|
||||
|
|
|
@ -157,7 +157,7 @@ extern uint16_t HAL_adc_result;
|
|||
void HAL_clear_reset_source (void);
|
||||
|
||||
/** reset reason */
|
||||
uint8_t HAL_get_reset_source (void);
|
||||
uint8_t HAL_get_reset_source(void);
|
||||
|
||||
void _delay_ms(const int delay);
|
||||
|
||||
|
|
|
@ -24,8 +24,8 @@
|
|||
* Test Re-ARM specific configuration values for errors at compile-time.
|
||||
*/
|
||||
#if ENABLED(SPINDLE_LASER_ENABLE)
|
||||
#if !PIN_EXISTS(SPINDLE_LASER_ENABLE)
|
||||
#error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENABLE_PIN."
|
||||
#if !PIN_EXISTS(SPINDLE_LASER_ENA)
|
||||
#error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENA_PIN."
|
||||
#elif SPINDLE_DIR_CHANGE && !PIN_EXISTS(SPINDLE_DIR)
|
||||
#error "SPINDLE_DIR_PIN not defined."
|
||||
#elif ENABLED(SPINDLE_LASER_PWM) && PIN_EXISTS(SPINDLE_LASER_PWM)
|
||||
|
|
|
@ -457,7 +457,7 @@ void manage_inactivity(const bool ignore_stepper_queue/*=false*/) {
|
|||
if (stepper_inactive_time) {
|
||||
static bool already_shutdown_steppers; // = false
|
||||
if (planner.has_blocks_queued())
|
||||
gcode.previous_move_ms = ms; // reset_stepper_timeout to keep steppers powered
|
||||
gcode.reset_stepper_timeout();
|
||||
else if (MOVE_AWAY_TEST && !ignore_stepper_queue && ELAPSED(ms, gcode.previous_move_ms + stepper_inactive_time)) {
|
||||
if (!already_shutdown_steppers) {
|
||||
already_shutdown_steppers = true; // L6470 SPI will consume 99% of free time without this
|
||||
|
@ -473,14 +473,11 @@ void manage_inactivity(const bool ignore_stepper_queue/*=false*/) {
|
|||
#if ENABLED(DISABLE_INACTIVE_E)
|
||||
disable_e_steppers();
|
||||
#endif
|
||||
#if HAS_LCD_MENU
|
||||
ui.status_screen();
|
||||
#if ENABLED(AUTO_BED_LEVELING_UBL)
|
||||
if (ubl.lcd_map_control) {
|
||||
ubl.lcd_map_control = false;
|
||||
ui.defer_status_screen(false);
|
||||
}
|
||||
#endif
|
||||
#if HAS_LCD_MENU && ENABLED(AUTO_BED_LEVELING_UBL)
|
||||
if (ubl.lcd_map_control) {
|
||||
ubl.lcd_map_control = false;
|
||||
ui.defer_status_screen(false);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
@ -617,7 +614,7 @@ void manage_inactivity(const bool ignore_stepper_queue/*=false*/) {
|
|||
}
|
||||
#endif // !SWITCHING_EXTRUDER
|
||||
|
||||
gcode.previous_move_ms = ms; // reset_stepper_timeout to keep steppers powered
|
||||
gcode.reset_stepper_timeout();
|
||||
}
|
||||
#endif // EXTRUDER_RUNOUT_PREVENT
|
||||
|
||||
|
@ -723,7 +720,7 @@ void idle(
|
|||
#endif
|
||||
|
||||
#if ENABLED(PRUSA_MMU2)
|
||||
mmu2.mmuLoop();
|
||||
mmu2.mmu_loop();
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -975,7 +972,7 @@ void setup() {
|
|||
#endif
|
||||
|
||||
#if ENABLED(SPINDLE_LASER_ENABLE)
|
||||
OUT_WRITE(SPINDLE_LASER_ENABLE_PIN, !SPINDLE_LASER_ENABLE_INVERT); // init spindle to off
|
||||
OUT_WRITE(SPINDLE_LASER_ENA_PIN, !SPINDLE_LASER_ENABLE_INVERT); // init spindle to off
|
||||
#if SPINDLE_DIR_CHANGE
|
||||
OUT_WRITE(SPINDLE_DIR_PIN, SPINDLE_INVERT_DIR ? 255 : 0); // init rotation to clockwise (M3)
|
||||
#endif
|
||||
|
@ -1045,7 +1042,7 @@ void setup() {
|
|||
ui.init();
|
||||
ui.reset_status();
|
||||
|
||||
#if ENABLED(SHOW_BOOTSCREEN)
|
||||
#if HAS_SPI_LCD && ENABLED(SHOW_BOOTSCREEN)
|
||||
ui.show_bootscreen();
|
||||
#endif
|
||||
|
||||
|
@ -1143,6 +1140,9 @@ void loop() {
|
|||
#if ENABLED(POWER_LOSS_RECOVERY)
|
||||
card.removeJobRecoveryFile();
|
||||
#endif
|
||||
#ifdef EVENT_GCODE_SD_STOP
|
||||
enqueue_and_echo_commands_P(PSTR(EVENT_GCODE_SD_STOP));
|
||||
#endif
|
||||
}
|
||||
#endif // SDSUPPORT
|
||||
|
||||
|
|
|
@ -189,10 +189,11 @@
|
|||
#define BOARD_COHESION3D_REMIX 1755 // Cohesion3D ReMix
|
||||
#define BOARD_COHESION3D_MINI 1756 // Cohesion3D Mini
|
||||
#define BOARD_SMOOTHIEBOARD 1757 // Smoothieboard
|
||||
#define BOARD_AZTEEG_X5_MINI_WIFI 1758 // Azteeg X5 Mini (Power outputs: Hotend0, Bed, Fan)
|
||||
#define BOARD_AZTEEG_X5_MINI_WIFI 1758 // Azteeg X5 Mini Wifi (Power outputs: Hotend0, Bed, Fan)
|
||||
#define BOARD_BIQU_SKR_V1_1 1759 // BIQU SKR_V1.1 (Power outputs: Hotend0,Hotend1, Fan, Bed)
|
||||
#define BOARD_BIQU_B300_V1_0 1760 // BIQU B300_V1.0 (Power outputs: Hotend0, Fan, Bed, SPI Driver)
|
||||
#define BOARD_BIGTREE_SKR_V1_3 1761 // BIGTREE SKR_V1.3 (Power outputs: Hotend0, Hotend1, Fan, Bed)
|
||||
#define BOARD_AZTEEG_X5_MINI 1762 // Azteeg X5 Mini (Power outputs: Hotend0, Bed, Fan)
|
||||
|
||||
//
|
||||
// SAM3X8E ARM Cortex M3
|
||||
|
@ -253,6 +254,8 @@
|
|||
#define BOARD_STM32F4 1804 // STM32 STM32GENERIC based STM32F4 controller
|
||||
#define BOARD_ARMED 1807 // Arm'ed STM32F4 based controller
|
||||
#define BOARD_RUMBA32 1809 // RUMBA32 STM32F4 based controller
|
||||
#define BOARD_BLACK_STM32F407VE 1810 // BLACK_STM32F407VE
|
||||
#define BOARD_BLACK_STM32F407ZE 1811 // BLACK_STM32F407ZE
|
||||
#define BOARD_STEVAL 1866 // STEVAL-3DP001V1 3D PRINTER BOARD
|
||||
|
||||
//
|
||||
|
|
|
@ -47,6 +47,7 @@
|
|||
#undef DEBUG_DELAY
|
||||
|
||||
#if DEBUG_OUT
|
||||
#define DEBUG_PRINT_P(P) serialprintPGM(P)
|
||||
#define DEBUG_ECHO_START SERIAL_ECHO_START
|
||||
#define DEBUG_ERROR_START SERIAL_ERROR_START
|
||||
#define DEBUG_CHAR SERIAL_CHAR
|
||||
|
@ -66,6 +67,7 @@
|
|||
#define DEBUG_XYZ SERIAL_XYZ
|
||||
#define DEBUG_DELAY(ms) serial_delay(ms)
|
||||
#else
|
||||
#define DEBUG_PRINT_P(P) NOOP
|
||||
#define DEBUG_ECHO_START() NOOP
|
||||
#define DEBUG_ERROR_START() NOOP
|
||||
#define DEBUG_CHAR(...) NOOP
|
||||
|
|
|
@ -65,20 +65,45 @@
|
|||
|
||||
#define AXIS_DRIVER_TYPE(A,T) AXIS_DRIVER_TYPE_##A(T)
|
||||
|
||||
#define HAS_DRIVER(T) (AXIS_DRIVER_TYPE_X(T) || AXIS_DRIVER_TYPE_X2(T) || \
|
||||
AXIS_DRIVER_TYPE_Y(T) || AXIS_DRIVER_TYPE_Y2(T) || \
|
||||
AXIS_DRIVER_TYPE_Z(T) || AXIS_DRIVER_TYPE_Z2(T) || AXIS_DRIVER_TYPE_Z3(T) || \
|
||||
AXIS_DRIVER_TYPE_E0(T) || AXIS_DRIVER_TYPE_E1(T) || \
|
||||
AXIS_DRIVER_TYPE_E2(T) || AXIS_DRIVER_TYPE_E3(T) || \
|
||||
AXIS_DRIVER_TYPE_E4(T) || AXIS_DRIVER_TYPE_E5(T) )
|
||||
#define HAS_DRIVER(T) ( AXIS_DRIVER_TYPE_X(T) || AXIS_DRIVER_TYPE_X2(T) \
|
||||
|| AXIS_DRIVER_TYPE_Y(T) || AXIS_DRIVER_TYPE_Y2(T) \
|
||||
|| AXIS_DRIVER_TYPE_Z(T) || AXIS_DRIVER_TYPE_Z2(T) || AXIS_DRIVER_TYPE_Z3(T) \
|
||||
|| AXIS_DRIVER_TYPE_E0(T) || AXIS_DRIVER_TYPE_E1(T) \
|
||||
|| AXIS_DRIVER_TYPE_E2(T) || AXIS_DRIVER_TYPE_E3(T) \
|
||||
|| AXIS_DRIVER_TYPE_E4(T) || AXIS_DRIVER_TYPE_E5(T) )
|
||||
|
||||
// Test for supported TMC drivers that require advanced configuration
|
||||
// Does not match standalone configurations
|
||||
#define HAS_TRINAMIC ( HAS_DRIVER(TMC2130) || HAS_DRIVER(TMC2160) || HAS_DRIVER(TMC2208) || HAS_DRIVER(TMC2660) || HAS_DRIVER(TMC5130) || HAS_DRIVER(TMC5160) )
|
||||
#define HAS_TRINAMIC ( HAS_DRIVER(TMC2130) \
|
||||
|| HAS_DRIVER(TMC2160) \
|
||||
|| HAS_DRIVER(TMC2208) \
|
||||
|| HAS_DRIVER(TMC2660) \
|
||||
|| HAS_DRIVER(TMC5130) \
|
||||
|| HAS_DRIVER(TMC5160) )
|
||||
|
||||
#define AXIS_IS_TMC(A) ( AXIS_DRIVER_TYPE_##A(TMC2130) || \
|
||||
AXIS_DRIVER_TYPE_##A(TMC2160) || \
|
||||
AXIS_DRIVER_TYPE_##A(TMC2208) || \
|
||||
AXIS_DRIVER_TYPE_##A(TMC2660) || \
|
||||
AXIS_DRIVER_TYPE_##A(TMC5130) || \
|
||||
AXIS_DRIVER_TYPE_##A(TMC5160))
|
||||
#define AXIS_IS_TMC(A) ( AXIS_DRIVER_TYPE(A,TMC2130) \
|
||||
|| AXIS_DRIVER_TYPE(A,TMC2160) \
|
||||
|| AXIS_DRIVER_TYPE(A,TMC2208) \
|
||||
|| AXIS_DRIVER_TYPE(A,TMC2660) \
|
||||
|| AXIS_DRIVER_TYPE(A,TMC5130) \
|
||||
|| AXIS_DRIVER_TYPE(A,TMC5160) )
|
||||
|
||||
// Test for a driver that uses SPI - this allows checking whether a _CS_ pin
|
||||
// is considered sensitive
|
||||
#define AXIS_HAS_SPI(A) ( AXIS_DRIVER_TYPE(A,TMC2130) \
|
||||
|| AXIS_DRIVER_TYPE(A,TMC2160) \
|
||||
|| AXIS_DRIVER_TYPE(A,TMC2660) \
|
||||
|| AXIS_DRIVER_TYPE(A,TMC5130) \
|
||||
|| AXIS_DRIVER_TYPE(A,TMC5160) )
|
||||
|
||||
#define AXIS_HAS_STALLGUARD(A) ( AXIS_DRIVER_TYPE(A,TMC2130) \
|
||||
|| AXIS_DRIVER_TYPE(A,TMC2160) \
|
||||
|| AXIS_DRIVER_TYPE(A,TMC2660) \
|
||||
|| AXIS_DRIVER_TYPE(A,TMC5130) \
|
||||
|| AXIS_DRIVER_TYPE(A,TMC5160) )
|
||||
|
||||
#define AXIS_HAS_STEALTHCHOP(A) ( AXIS_DRIVER_TYPE(A,TMC2130) \
|
||||
|| AXIS_DRIVER_TYPE(A,TMC2160) \
|
||||
|| AXIS_DRIVER_TYPE(A,TMC2208) \
|
||||
|| AXIS_DRIVER_TYPE(A,TMC5130) \
|
||||
|| AXIS_DRIVER_TYPE(A,TMC5160) )
|
||||
|
|
|
@ -39,6 +39,12 @@ enum AxisEnum : unsigned char {
|
|||
X_HEAD = 4,
|
||||
Y_HEAD = 5,
|
||||
Z_HEAD = 6,
|
||||
E0_AXIS = 3,
|
||||
E1_AXIS = 4,
|
||||
E2_AXIS = 5,
|
||||
E3_AXIS = 6,
|
||||
E4_AXIS = 7,
|
||||
E5_AXIS = 8,
|
||||
ALL_AXES = 0xFE,
|
||||
NO_AXIS = 0xFF
|
||||
};
|
||||
|
|
|
@ -22,6 +22,7 @@
|
|||
|
||||
#include "serial.h"
|
||||
#include "language.h"
|
||||
#include "enum.h"
|
||||
|
||||
uint8_t marlin_debug_flags = MARLIN_DEBUG_NONE;
|
||||
|
||||
|
@ -49,8 +50,14 @@ void serial_echopair_PGM(PGM_P const s_P, unsigned long v) { serialprintPGM(s_P)
|
|||
|
||||
void serial_spaces(uint8_t count) { count *= (PROPORTIONAL_FONT_RATIO); while (count--) SERIAL_CHAR(' '); }
|
||||
|
||||
void serial_ternary(const bool onoff, PGM_P const pre, PGM_P const on, PGM_P const off, PGM_P const post/*=NULL*/) {
|
||||
if (pre) serialprintPGM(pre);
|
||||
serialprintPGM(onoff ? on : off);
|
||||
if (post) serialprintPGM(post);
|
||||
}
|
||||
void serialprint_onoff(const bool onoff) { serialprintPGM(onoff ? PSTR(MSG_ON) : PSTR(MSG_OFF)); }
|
||||
void serialprintln_onoff(const bool onoff) { serialprint_onoff(onoff); SERIAL_EOL(); }
|
||||
void serialprint_truefalse(const bool tf) { serialprintPGM(tf ? PSTR("true") : PSTR("false")); }
|
||||
|
||||
void print_bin(const uint16_t val) {
|
||||
uint16_t mask = 0x8000;
|
||||
|
@ -61,21 +68,15 @@ void print_bin(const uint16_t val) {
|
|||
}
|
||||
}
|
||||
|
||||
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||
void print_xyz(PGM_P const prefix, PGM_P const suffix, const float x, const float y, const float z) {
|
||||
serialprintPGM(prefix);
|
||||
SERIAL_CHAR('(');
|
||||
SERIAL_ECHO(x);
|
||||
SERIAL_ECHOPAIR(", ", y, ", ", z);
|
||||
SERIAL_CHAR(')');
|
||||
if (suffix) serialprintPGM(suffix); else SERIAL_EOL();
|
||||
}
|
||||
|
||||
#include "enum.h"
|
||||
|
||||
void print_xyz(PGM_P const prefix, PGM_P const suffix, const float x, const float y, const float z) {
|
||||
serialprintPGM(prefix);
|
||||
SERIAL_CHAR('(');
|
||||
SERIAL_ECHO(x);
|
||||
SERIAL_ECHOPAIR(", ", y, ", ", z);
|
||||
SERIAL_CHAR(')');
|
||||
if (suffix) serialprintPGM(suffix); else SERIAL_EOL();
|
||||
}
|
||||
|
||||
void print_xyz(PGM_P const prefix, PGM_P const suffix, const float xyz[]) {
|
||||
print_xyz(prefix, suffix, xyz[X_AXIS], xyz[Y_AXIS], xyz[Z_AXIS]);
|
||||
}
|
||||
|
||||
#endif
|
||||
void print_xyz(PGM_P const prefix, PGM_P const suffix, const float xyz[]) {
|
||||
print_xyz(prefix, suffix, xyz[X_AXIS], xyz[Y_AXIS], xyz[Z_AXIS]);
|
||||
}
|
||||
|
|
|
@ -174,18 +174,15 @@ inline void serial_echopair_PGM(PGM_P const s_P, void *v) { serial_echopair_PG
|
|||
void serialprintPGM(PGM_P str);
|
||||
void serial_echo_start();
|
||||
void serial_error_start();
|
||||
void serial_ternary(const bool onoff, PGM_P const pre, PGM_P const on, PGM_P const off, PGM_P const post=NULL);
|
||||
void serialprint_onoff(const bool onoff);
|
||||
void serialprintln_onoff(const bool onoff);
|
||||
void serialprint_truefalse(const bool tf);
|
||||
void serial_spaces(uint8_t count);
|
||||
|
||||
void print_bin(const uint16_t val);
|
||||
|
||||
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||
void print_xyz(PGM_P const prefix, PGM_P const suffix, const float x, const float y, const float z);
|
||||
void print_xyz(PGM_P const prefix, PGM_P const suffix, const float xyz[]);
|
||||
#define SERIAL_POS(SUFFIX,VAR) do { print_xyz(PSTR(" " STRINGIFY(VAR) "="), PSTR(" : " SUFFIX "\n"), VAR); } while(0)
|
||||
#define SERIAL_XYZ(PREFIX,...) do { print_xyz(PSTR(PREFIX), NULL, __VA_ARGS__); } while(0)
|
||||
#else
|
||||
#define SERIAL_POS(...) NOOP
|
||||
#define SERIAL_XYZ(...) NOOP
|
||||
#endif
|
||||
void print_xyz(PGM_P const prefix, PGM_P const suffix, const float x, const float y, const float z);
|
||||
void print_xyz(PGM_P const prefix, PGM_P const suffix, const float xyz[]);
|
||||
#define SERIAL_POS(SUFFIX,VAR) do { print_xyz(PSTR(" " STRINGIFY(VAR) "="), PSTR(" : " SUFFIX "\n"), VAR); } while(0)
|
||||
#define SERIAL_XYZ(PREFIX,...) do { print_xyz(PSTR(PREFIX), NULL, __VA_ARGS__); } while(0)
|
||||
|
|
|
@ -58,11 +58,11 @@ void safe_delay(millis_t ms) {
|
|||
#define MINUSOR(n, alt) (n >= 0 ? (alt) : (n = -n, '-'))
|
||||
|
||||
// Convert a full-range unsigned 8bit int to a percentage
|
||||
char* ui8tostr_percent(const uint8_t i) {
|
||||
const uint8_t percent = ui8_to_percent(i);
|
||||
conv[3] = RJDIGIT(percent, 100);
|
||||
conv[4] = RJDIGIT(percent, 10);
|
||||
conv[5] = DIGIMOD(percent, 1);
|
||||
char* ui8tostr4pct(const uint8_t i) {
|
||||
const uint8_t n = ui8_to_percent(i);
|
||||
conv[3] = RJDIGIT(n, 100);
|
||||
conv[4] = RJDIGIT(n, 10);
|
||||
conv[5] = DIGIMOD(n, 1);
|
||||
conv[6] = '%';
|
||||
return &conv[3];
|
||||
}
|
||||
|
@ -214,6 +214,19 @@ void safe_delay(millis_t ms) {
|
|||
return &conv[1];
|
||||
}
|
||||
|
||||
// Convert signed float to string (5 digit) with -1.2345 / _0.0000 / +1.2345 format
|
||||
char* ftostr54sign(const float &f, char plus/*=' '*/) {
|
||||
long i = (f * 100000 + (f < 0 ? -5: 5)) / 10;
|
||||
conv[0] = i ? MINUSOR(i, plus) : ' ';
|
||||
conv[1] = DIGIMOD(i, 10000);
|
||||
conv[2] = '.';
|
||||
conv[3] = DIGIMOD(i, 1000);
|
||||
conv[4] = DIGIMOD(i, 100);
|
||||
conv[5] = DIGIMOD(i, 10);
|
||||
conv[6] = DIGIMOD(i, 1);
|
||||
return &conv[0];
|
||||
}
|
||||
|
||||
// Convert unsigned float to rj string with 12345 format
|
||||
char* ftostr5rj(const float &f) {
|
||||
const long i = ((f < 0 ? -f : f) * 10 + 5) / 10;
|
||||
|
|
|
@ -56,7 +56,7 @@ inline void serial_delay(const millis_t ms) {
|
|||
#if ANY(ULTRA_LCD, DEBUG_LEVELING_FEATURE, EXTENSIBLE_UI)
|
||||
|
||||
// Convert a full-range unsigned 8bit int to a percentage
|
||||
char* ui8tostr_percent(const uint8_t i);
|
||||
char* ui8tostr4pct(const uint8_t i);
|
||||
|
||||
// Convert uint8_t to string with 123 format
|
||||
char* ui8tostr3(const uint8_t x);
|
||||
|
@ -91,6 +91,9 @@ inline void serial_delay(const millis_t ms) {
|
|||
// Convert signed float to string (6 digit) with -1.234 / _0.000 / +1.234 format
|
||||
char* ftostr43sign(const float &x, char plus=' ');
|
||||
|
||||
// Convert signed float to string (5 digit) with -1.2345 / _0.0000 / +1.2345 format
|
||||
char* ftostr54sign(const float &x, char plus=' ');
|
||||
|
||||
// Convert unsigned float to rj string with 12345 format
|
||||
char* ftostr5rj(const float &x);
|
||||
|
||||
|
|
|
@ -38,6 +38,8 @@
|
|||
#include "../module/stepper.h"
|
||||
#include "../gcode/parser.h"
|
||||
|
||||
#include "../feature/babystep.h"
|
||||
|
||||
#include <Wire.h>
|
||||
|
||||
void I2CPositionEncoder::init(const uint8_t address, const AxisEnum axis) {
|
||||
|
@ -169,7 +171,7 @@ void I2CPositionEncoder::update() {
|
|||
const int32_t errorP = int32_t(sumP * (1.0f / (I2CPE_ERR_PRST_ARRAY_SIZE)));
|
||||
SERIAL_ECHO(axis_codes[encoderAxis]);
|
||||
SERIAL_ECHOLNPAIR(" - err detected: ", errorP * planner.steps_to_mm[encoderAxis], "mm; correcting!");
|
||||
thermalManager.babystepsTodo[encoderAxis] = -LROUND(errorP);
|
||||
babystep.add_steps(encoderAxis, -LROUND(errorP));
|
||||
errPrstIdx = 0;
|
||||
}
|
||||
}
|
||||
|
@ -180,7 +182,7 @@ void I2CPositionEncoder::update() {
|
|||
if (ABS(error) > threshold * planner.settings.axis_steps_per_mm[encoderAxis]) {
|
||||
//SERIAL_ECHOLN(error);
|
||||
//SERIAL_ECHOLN(position);
|
||||
thermalManager.babystepsTodo[encoderAxis] = -LROUND(error / 2);
|
||||
babystep.add_steps(encoderAxis, -LROUND(error / 2));
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -227,13 +229,11 @@ bool I2CPositionEncoder::passes_test(const bool report) {
|
|||
if (report) {
|
||||
if (H != I2CPE_MAG_SIG_GOOD) SERIAL_ECHOPGM("Warning. ");
|
||||
SERIAL_ECHO(axis_codes[encoderAxis]);
|
||||
SERIAL_ECHOPGM(" axis ");
|
||||
serialprintPGM(H == I2CPE_MAG_SIG_BAD ? PSTR("magnetic strip ") : PSTR("encoder "));
|
||||
serial_ternary(H == I2CPE_MAG_SIG_BAD, PSTR(" axis "), PSTR("magnetic strip "), PSTR("encoder "));
|
||||
switch (H) {
|
||||
case I2CPE_MAG_SIG_GOOD:
|
||||
case I2CPE_MAG_SIG_MID:
|
||||
SERIAL_ECHOLNPGM("passes test; field strength ");
|
||||
serialprintPGM(H == I2CPE_MAG_SIG_GOOD ? PSTR("good.\n") : PSTR("fair.\n"));
|
||||
serial_ternary(H == I2CPE_MAG_SIG_GOOD, PSTR("passes test; field strength "), PSTR("good"), PSTR("fair"), PSTR(".\n"));
|
||||
break;
|
||||
default:
|
||||
SERIAL_ECHOLNPGM("not detected!");
|
||||
|
|
|
@ -275,9 +275,8 @@ class I2CPositionEncodersMgr {
|
|||
static void enable_ec(const int8_t idx, const bool enabled, const AxisEnum axis) {
|
||||
CHECK_IDX();
|
||||
encoders[idx].set_ec_enabled(enabled);
|
||||
SERIAL_ECHOPAIR("Error correction on ", axis_codes[axis], " axis is ");
|
||||
serialprintPGM(encoders[idx].get_ec_enabled() ? PSTR("en") : PSTR("dis"));
|
||||
SERIAL_ECHOLNPGM("abled.");
|
||||
SERIAL_ECHOPAIR("Error correction on ", axis_codes[axis]);
|
||||
serial_ternary(encoders[idx].get_ec_enabled(), PSTR(" axis is "), PSTR("en"), PSTR("dis"), PSTR("abled.\n"));
|
||||
}
|
||||
|
||||
static void set_ec_threshold(const int8_t idx, const float newThreshold, const AxisEnum axis) {
|
||||
|
|
135
Marlin/src/feature/babystep.cpp
Normal file
135
Marlin/src/feature/babystep.cpp
Normal file
|
@ -0,0 +1,135 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#include "../inc/MarlinConfig.h"
|
||||
|
||||
#if ENABLED(BABYSTEPPING)
|
||||
|
||||
#include "babystep.h"
|
||||
#include "../Marlin.h"
|
||||
#include "../module/planner.h"
|
||||
#include "../module/stepper.h"
|
||||
|
||||
#if ENABLED(BABYSTEP_ALWAYS_AVAILABLE)
|
||||
#include "../gcode/gcode.h"
|
||||
#endif
|
||||
|
||||
Babystep babystep;
|
||||
|
||||
volatile int16_t Babystep::todo[BS_TODO_AXIS(Z_AXIS) + 1];
|
||||
|
||||
#if HAS_LCD_MENU
|
||||
int16_t Babystep::accum;
|
||||
#if ENABLED(BABYSTEP_DISPLAY_TOTAL)
|
||||
int16_t Babystep::axis_total[BS_TOTAL_AXIS(Z_AXIS) + 1];
|
||||
#endif
|
||||
#endif
|
||||
|
||||
void Babystep::step_axis(const AxisEnum axis) {
|
||||
const int16_t curTodo = todo[BS_TODO_AXIS(axis)]; // get rid of volatile for performance
|
||||
if (curTodo) {
|
||||
stepper.babystep((AxisEnum)axis, curTodo > 0);
|
||||
if (curTodo > 0) todo[BS_TODO_AXIS(axis)]--; else todo[BS_TODO_AXIS(axis)]++;
|
||||
}
|
||||
}
|
||||
|
||||
void Babystep::task() {
|
||||
#if EITHER(BABYSTEP_XY, I2C_POSITION_ENCODERS)
|
||||
LOOP_XYZ(axis) step_axis((AxisEnum)axis);
|
||||
#else
|
||||
step_axis(Z_AXIS);
|
||||
#endif
|
||||
}
|
||||
|
||||
void Babystep::add_mm(const AxisEnum axis, const float &mm) {
|
||||
add_steps(axis, mm * planner.settings.axis_steps_per_mm[axis]);
|
||||
}
|
||||
|
||||
void Babystep::add_steps(const AxisEnum axis, const int32_t distance) {
|
||||
|
||||
#if ENABLED(BABYSTEP_WITHOUT_HOMING)
|
||||
#define CAN_BABYSTEP(AXIS) true
|
||||
#else
|
||||
extern uint8_t axis_known_position;
|
||||
#define CAN_BABYSTEP(AXIS) TEST(axis_known_position, AXIS)
|
||||
#endif
|
||||
|
||||
if (!CAN_BABYSTEP(axis)) return;
|
||||
|
||||
#if HAS_LCD_MENU
|
||||
accum += distance; // Count up babysteps for the UI
|
||||
#if ENABLED(BABYSTEP_DISPLAY_TOTAL)
|
||||
axis_total[BS_TOTAL_AXIS(axis)] += distance;
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if ENABLED(BABYSTEP_ALWAYS_AVAILABLE)
|
||||
#define BSA_ENABLE(AXIS) do{ switch (AXIS) { case X_AXIS: enable_X(); break; case Y_AXIS: enable_Y(); break; case Z_AXIS: enable_Z(); } }while(0)
|
||||
#else
|
||||
#define BSA_ENABLE(AXIS) NOOP
|
||||
#endif
|
||||
|
||||
#if IS_CORE
|
||||
#if ENABLED(BABYSTEP_XY)
|
||||
switch (axis) {
|
||||
case CORE_AXIS_1: // X on CoreXY and CoreXZ, Y on CoreYZ
|
||||
BSA_ENABLE(CORE_AXIS_1);
|
||||
BSA_ENABLE(CORE_AXIS_2);
|
||||
todo[CORE_AXIS_1] += distance * 2;
|
||||
todo[CORE_AXIS_2] += distance * 2;
|
||||
break;
|
||||
case CORE_AXIS_2: // Y on CoreXY, Z on CoreXZ and CoreYZ
|
||||
BSA_ENABLE(CORE_AXIS_1);
|
||||
BSA_ENABLE(CORE_AXIS_2);
|
||||
todo[CORE_AXIS_1] += CORESIGN(distance * 2);
|
||||
todo[CORE_AXIS_2] -= CORESIGN(distance * 2);
|
||||
break;
|
||||
case NORMAL_AXIS: // Z on CoreXY, Y on CoreXZ, X on CoreYZ
|
||||
default:
|
||||
BSA_ENABLE(NORMAL_AXIS);
|
||||
todo[NORMAL_AXIS] += distance;
|
||||
break;
|
||||
}
|
||||
#elif CORE_IS_XZ || CORE_IS_YZ
|
||||
// Only Z stepping needs to be handled here
|
||||
BSA_ENABLE(CORE_AXIS_1);
|
||||
BSA_ENABLE(CORE_AXIS_2);
|
||||
todo[CORE_AXIS_1] += CORESIGN(distance * 2);
|
||||
todo[CORE_AXIS_2] -= CORESIGN(distance * 2);
|
||||
#else
|
||||
BSA_ENABLE(Z_AXIS);
|
||||
todo[Z_AXIS] += distance;
|
||||
#endif
|
||||
#else
|
||||
#if ENABLED(BABYSTEP_XY)
|
||||
BSA_ENABLE(axis);
|
||||
#else
|
||||
BSA_ENABLE(Z_AXIS);
|
||||
#endif
|
||||
todo[BS_TODO_AXIS(axis)] += distance;
|
||||
#endif
|
||||
#if ENABLED(BABYSTEP_ALWAYS_AVAILABLE)
|
||||
gcode.reset_stepper_timeout();
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif // BABYSTEPPING
|
63
Marlin/src/feature/babystep.h
Normal file
63
Marlin/src/feature/babystep.h
Normal file
|
@ -0,0 +1,63 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include "../inc/MarlinConfigPre.h"
|
||||
#include "../core/enum.h"
|
||||
|
||||
#if IS_CORE || EITHER(BABYSTEP_XY, I2C_POSITION_ENCODERS)
|
||||
#define BS_TODO_AXIS(A) A
|
||||
#else
|
||||
#define BS_TODO_AXIS(A) 0
|
||||
#endif
|
||||
|
||||
#if HAS_LCD_MENU && ENABLED(BABYSTEP_DISPLAY_TOTAL)
|
||||
#if ENABLED(BABYSTEP_XY)
|
||||
#define BS_TOTAL_AXIS(A) A
|
||||
#else
|
||||
#define BS_TOTAL_AXIS(A) 0
|
||||
#endif
|
||||
#endif
|
||||
|
||||
class Babystep {
|
||||
public:
|
||||
static volatile int16_t todo[BS_TODO_AXIS(Z_AXIS) + 1];
|
||||
#if HAS_LCD_MENU
|
||||
static int16_t accum; // Total babysteps in current edit
|
||||
#if ENABLED(BABYSTEP_DISPLAY_TOTAL)
|
||||
static int16_t axis_total[BS_TOTAL_AXIS(Z_AXIS) + 1]; // Total babysteps since G28
|
||||
static inline void reset_total(const AxisEnum axis) {
|
||||
#if ENABLED(BABYSTEP_XY)
|
||||
if (axis == Z_AXIS)
|
||||
#endif
|
||||
axis_total[BS_TOTAL_AXIS(axis)] = 0;
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
static void add_steps(const AxisEnum axis, const int32_t distance);
|
||||
static void add_mm(const AxisEnum axis, const float &mm);
|
||||
static void task();
|
||||
private:
|
||||
static void step_axis(const AxisEnum axis);
|
||||
};
|
||||
|
||||
extern Babystep babystep;
|
|
@ -42,10 +42,6 @@
|
|||
#define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE)
|
||||
#include "../../core/debug_out.h"
|
||||
|
||||
#if ENABLED(G26_MESH_VALIDATION)
|
||||
bool g26_debug_flag; // = false
|
||||
#endif
|
||||
|
||||
bool leveling_is_valid() {
|
||||
return
|
||||
#if ENABLED(MESH_BED_LEVELING)
|
||||
|
|
|
@ -28,12 +28,6 @@ typedef struct {
|
|||
float distance; // When populated, the distance from the search location
|
||||
} mesh_index_pair;
|
||||
|
||||
#if ENABLED(G26_MESH_VALIDATION)
|
||||
extern bool g26_debug_flag;
|
||||
#else
|
||||
constexpr bool g26_debug_flag = false;
|
||||
#endif
|
||||
|
||||
#if ENABLED(PROBE_MANUALLY)
|
||||
extern bool g29_in_progress;
|
||||
#else
|
||||
|
|
|
@ -49,8 +49,8 @@
|
|||
ZERO(z_values);
|
||||
#if ENABLED(EXTENSIBLE_UI)
|
||||
for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++)
|
||||
for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++)
|
||||
ExtUI::onMeshUpdate(x, y, 0);
|
||||
for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++)
|
||||
ExtUI::onMeshUpdate(x, y, 0);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
|
|
@ -35,7 +35,7 @@
|
|||
#if ENABLED(EXTENSIBLE_UI)
|
||||
#include "../../../lcd/extensible_ui/ui_api.h"
|
||||
#endif
|
||||
|
||||
|
||||
#include "math.h"
|
||||
|
||||
void unified_bed_leveling::echo_name() {
|
||||
|
@ -58,54 +58,10 @@
|
|||
|
||||
void unified_bed_leveling::report_state() {
|
||||
echo_name();
|
||||
SERIAL_ECHOPGM(" System v" UBL_VERSION " ");
|
||||
if (!planner.leveling_active) SERIAL_ECHOPGM("in");
|
||||
SERIAL_ECHOLNPGM("active.");
|
||||
serial_ternary(planner.leveling_active, PSTR(" System v" UBL_VERSION " "), PSTR(""), PSTR("in"), PSTR("active\n"));
|
||||
serial_delay(50);
|
||||
}
|
||||
|
||||
#if ENABLED(UBL_DEVEL_DEBUGGING)
|
||||
|
||||
static void debug_echo_axis(const AxisEnum axis) {
|
||||
if (current_position[axis] == destination[axis])
|
||||
SERIAL_ECHOPGM("-------------");
|
||||
else
|
||||
SERIAL_ECHO_F(destination[X_AXIS], 6);
|
||||
}
|
||||
|
||||
void debug_current_and_destination(PGM_P title) {
|
||||
|
||||
// if the title message starts with a '!' it is so important, we are going to
|
||||
// ignore the status of the g26_debug_flag
|
||||
if (*title != '!' && !g26_debug_flag) return;
|
||||
|
||||
const float de = destination[E_AXIS] - current_position[E_AXIS];
|
||||
|
||||
if (de == 0.0) return; // Printing moves only
|
||||
|
||||
const float dx = destination[X_AXIS] - current_position[X_AXIS],
|
||||
dy = destination[Y_AXIS] - current_position[Y_AXIS],
|
||||
xy_dist = HYPOT(dx, dy);
|
||||
|
||||
if (xy_dist == 0.0) return;
|
||||
|
||||
const float fpmm = de / xy_dist;
|
||||
SERIAL_ECHOPAIR_F(" fpmm=", fpmm, 6);
|
||||
SERIAL_ECHOPAIR_F(" current=( ", current_position[X_AXIS], 6);
|
||||
SERIAL_ECHOPAIR_F(", ", current_position[Y_AXIS], 6);
|
||||
SERIAL_ECHOPAIR_F(", ", current_position[Z_AXIS], 6);
|
||||
SERIAL_ECHOPAIR_F(", ", current_position[E_AXIS], 6);
|
||||
SERIAL_ECHOPGM(" ) destination=( "); debug_echo_axis(X_AXIS);
|
||||
SERIAL_ECHOPGM(", "); debug_echo_axis(Y_AXIS);
|
||||
SERIAL_ECHOPGM(", "); debug_echo_axis(Z_AXIS);
|
||||
SERIAL_ECHOPGM(", "); debug_echo_axis(E_AXIS);
|
||||
SERIAL_ECHOPGM(" ) ");
|
||||
serialprintPGM(title);
|
||||
SERIAL_EOL();
|
||||
}
|
||||
|
||||
#endif // UBL_DEVEL_DEBUGGING
|
||||
|
||||
int8_t unified_bed_leveling::storage_slot;
|
||||
|
||||
float unified_bed_leveling::z_values[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y];
|
||||
|
@ -135,8 +91,8 @@
|
|||
ZERO(z_values);
|
||||
#if ENABLED(EXTENSIBLE_UI)
|
||||
for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++)
|
||||
for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++)
|
||||
ExtUI::onMeshUpdate(x, y, 0);
|
||||
for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++)
|
||||
ExtUI::onMeshUpdate(x, y, 0);
|
||||
#endif
|
||||
if (was_enabled) report_current_position();
|
||||
}
|
||||
|
|
|
@ -39,14 +39,6 @@
|
|||
#define USE_NOZZLE_AS_REFERENCE 0
|
||||
#define USE_PROBE_AS_REFERENCE 1
|
||||
|
||||
// ubl_motion.cpp
|
||||
|
||||
#if ENABLED(UBL_DEVEL_DEBUGGING)
|
||||
void debug_current_and_destination(PGM_P const title);
|
||||
#else
|
||||
FORCE_INLINE void debug_current_and_destination(PGM_P const title) { UNUSED(title); }
|
||||
#endif
|
||||
|
||||
// ubl_G29.cpp
|
||||
|
||||
enum MeshPointType : char { INVALID, REAL, SET_IN_BITMAP };
|
||||
|
|
|
@ -24,8 +24,6 @@
|
|||
|
||||
#if ENABLED(AUTO_BED_LEVELING_UBL)
|
||||
|
||||
//#define UBL_DEVEL_DEBUGGING
|
||||
|
||||
#include "ubl.h"
|
||||
|
||||
#include "../../../Marlin.h"
|
||||
|
@ -765,14 +763,12 @@
|
|||
|
||||
if (location.x_index >= 0) { // mesh point found and is reachable by probe
|
||||
const float rawx = mesh_index_to_xpos(location.x_index),
|
||||
rawy = mesh_index_to_ypos(location.y_index);
|
||||
|
||||
const float measured_z = probe_pt(rawx, rawy, stow_probe ? PROBE_PT_STOW : PROBE_PT_RAISE, g29_verbose_level); // TODO: Needs error handling
|
||||
rawy = mesh_index_to_ypos(location.y_index),
|
||||
measured_z = probe_pt(rawx, rawy, stow_probe ? PROBE_PT_STOW : PROBE_PT_RAISE, g29_verbose_level); // TODO: Needs error handling
|
||||
z_values[location.x_index][location.y_index] = measured_z;
|
||||
#if ENABLED(EXTENSIBLE_UI)
|
||||
ExtUI::onMeshUpdate(location.x_index, location.y_index, measured_z);
|
||||
#endif
|
||||
|
||||
}
|
||||
SERIAL_FLUSH(); // Prevent host M105 buffer overrun.
|
||||
} while (location.x_index >= 0 && --count);
|
||||
|
|
|
@ -64,17 +64,6 @@
|
|||
cell_dest_xi = get_cell_index_x(end[X_AXIS]),
|
||||
cell_dest_yi = get_cell_index_y(end[Y_AXIS]);
|
||||
|
||||
if (g26_debug_flag) {
|
||||
SERIAL_ECHOLNPAIR(
|
||||
" ubl.line_to_destination_cartesian(xe=", destination[X_AXIS],
|
||||
", ye=", destination[Y_AXIS],
|
||||
", ze=", destination[Z_AXIS],
|
||||
", ee=", destination[E_AXIS],
|
||||
")"
|
||||
);
|
||||
debug_current_and_destination(PSTR("Start of ubl.line_to_destination_cartesian()"));
|
||||
}
|
||||
|
||||
// A move within the same cell needs no splitting
|
||||
if (cell_start_xi == cell_dest_xi && cell_start_yi == cell_dest_yi) {
|
||||
|
||||
|
@ -93,9 +82,6 @@
|
|||
planner.buffer_segment(end[X_AXIS], end[Y_AXIS], end[Z_AXIS] + z_raise, end[E_AXIS], feed_rate, extruder);
|
||||
set_current_from_destination();
|
||||
|
||||
if (g26_debug_flag)
|
||||
debug_current_and_destination(PSTR("out of bounds in ubl.line_to_destination_cartesian()"));
|
||||
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -119,9 +105,6 @@
|
|||
// Replace NAN corrections with 0.0 to prevent NAN propagation.
|
||||
planner.buffer_segment(end[X_AXIS], end[Y_AXIS], end[Z_AXIS] + (isnan(z0) ? 0.0 : z0), end[E_AXIS], feed_rate, extruder);
|
||||
|
||||
if (g26_debug_flag)
|
||||
debug_current_and_destination(PSTR("FINAL_MOVE in ubl.line_to_destination_cartesian()"));
|
||||
|
||||
set_current_from_destination();
|
||||
return;
|
||||
}
|
||||
|
@ -215,9 +198,6 @@
|
|||
} //else printf("FIRST MOVE PRUNED ");
|
||||
}
|
||||
|
||||
if (g26_debug_flag)
|
||||
debug_current_and_destination(PSTR("vertical move done in ubl.line_to_destination_cartesian()"));
|
||||
|
||||
// At the final destination? Usually not, but when on a Y Mesh Line it's completed.
|
||||
if (current_position[X_AXIS] != end[X_AXIS] || current_position[Y_AXIS] != end[Y_AXIS])
|
||||
goto FINAL_MOVE;
|
||||
|
@ -267,9 +247,6 @@
|
|||
} //else printf("FIRST MOVE PRUNED ");
|
||||
}
|
||||
|
||||
if (g26_debug_flag)
|
||||
debug_current_and_destination(PSTR("horizontal move done in ubl.line_to_destination_cartesian()"));
|
||||
|
||||
if (current_position[X_AXIS] != end[X_AXIS] || current_position[Y_AXIS] != end[Y_AXIS])
|
||||
goto FINAL_MOVE;
|
||||
|
||||
|
@ -353,9 +330,6 @@
|
|||
if (xi_cnt < 0 || yi_cnt < 0) break; // Too far! Exit the loop and go to FINAL_MOVE
|
||||
}
|
||||
|
||||
if (g26_debug_flag)
|
||||
debug_current_and_destination(PSTR("generic move done in ubl.line_to_destination_cartesian()"));
|
||||
|
||||
if (current_position[X_AXIS] != end[X_AXIS] || current_position[Y_AXIS] != end[Y_AXIS])
|
||||
goto FINAL_MOVE;
|
||||
|
||||
|
|
|
@ -35,6 +35,9 @@
|
|||
#if MB(5DPRINT)
|
||||
#define DIGIPOT_I2C_FACTOR 117.96
|
||||
#define DIGIPOT_I2C_MAX_CURRENT 1.736
|
||||
#elif MB(AZTEEG_X5_MINI) || MB(AZTEEG_X5_MINI_WIFI)
|
||||
#define DIGIPOT_I2C_FACTOR 113.5
|
||||
#define DIGIPOT_I2C_MAX_CURRENT 2.0
|
||||
#else
|
||||
#define DIGIPOT_I2C_FACTOR 106.7
|
||||
#define DIGIPOT_I2C_MAX_CURRENT 2.5
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
|
|
|
@ -120,19 +120,28 @@ typedef struct LEDColor {
|
|||
#else
|
||||
#define MakeLEDColor(R,G,B,W,I) LEDColor(R, G, B, W)
|
||||
#endif
|
||||
#define LEDColorWhite() LEDColor(0, 0, 0, 255)
|
||||
#else
|
||||
#define MakeLEDColor(R,G,B,W,I) LEDColor(R, G, B)
|
||||
#define LEDColorWhite() LEDColor(255, 255, 255)
|
||||
#define MakeLEDColor(R,G,B,W,I) LEDColor(R, G, B)
|
||||
#endif
|
||||
|
||||
#define LEDColorOff() LEDColor( 0, 0, 0)
|
||||
#define LEDColorRed() LEDColor(255, 0, 0)
|
||||
#if ENABLED(LED_COLORS_REDUCE_GREEN)
|
||||
#define LEDColorOrange() LEDColor(255, 25, 0)
|
||||
#define LEDColorYellow() LEDColor(255, 75, 0)
|
||||
#else
|
||||
#define LEDColorOrange() LEDColor(255, 80, 0)
|
||||
#define LEDColorYellow() LEDColor(255, 255, 0)
|
||||
#endif
|
||||
#define LEDColorGreen() LEDColor( 0, 255, 0)
|
||||
#define LEDColorBlue() LEDColor( 0, 0, 255)
|
||||
#define LEDColorIndigo() LEDColor( 0, 255, 255)
|
||||
#define LEDColorViolet() LEDColor(255, 0, 255)
|
||||
#if HAS_WHITE_LED
|
||||
#define LEDColorWhite() LEDColor( 0, 0, 0, 255)
|
||||
#else
|
||||
#define LEDColorWhite() LEDColor(255, 255, 255)
|
||||
#endif
|
||||
#define LEDColorOff() LEDColor( 0, 0, 0)
|
||||
#define LEDColorRed() LEDColor(255, 0, 0)
|
||||
#define LEDColorOrange() LEDColor(255, 80, 0)
|
||||
#define LEDColorYellow() LEDColor(255, 255, 0)
|
||||
#define LEDColorGreen() LEDColor( 0, 255, 0)
|
||||
#define LEDColorBlue() LEDColor( 0, 0, 255)
|
||||
#define LEDColorIndigo() LEDColor( 0, 255, 255)
|
||||
#define LEDColorViolet() LEDColor(255, 0, 255)
|
||||
|
||||
class LEDLights {
|
||||
public:
|
||||
|
|
|
@ -50,6 +50,9 @@ job_recovery_info_t PrintJobRecovery::info;
|
|||
#include "fwretract.h"
|
||||
#endif
|
||||
|
||||
#define DEBUG_OUT ENABLED(DEBUG_POWER_LOSS_RECOVERY)
|
||||
#include "../core/debug_out.h"
|
||||
|
||||
PrintJobRecovery recovery;
|
||||
|
||||
/**
|
||||
|
@ -110,9 +113,7 @@ void PrintJobRecovery::load() {
|
|||
(void)file.read(&info, sizeof(info));
|
||||
close();
|
||||
}
|
||||
#if ENABLED(DEBUG_POWER_LOSS_RECOVERY)
|
||||
debug(PSTR("Load"));
|
||||
#endif
|
||||
debug(PSTR("Load"));
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -125,6 +126,7 @@ void PrintJobRecovery::save(const bool force/*=false*/, const bool save_queue/*=
|
|||
millis_t ms = millis();
|
||||
#endif
|
||||
|
||||
// Did Z change since the last call?
|
||||
if (force
|
||||
#if DISABLED(SAVE_EACH_CMD_MODE) // Always save state when enabled
|
||||
#if PIN_EXISTS(POWER_LOSS) // Save if power loss pin is triggered
|
||||
|
@ -133,8 +135,8 @@ void PrintJobRecovery::save(const bool force/*=false*/, const bool save_queue/*=
|
|||
#if SAVE_INFO_INTERVAL_MS > 0 // Save if interval is elapsed
|
||||
|| ELAPSED(ms, next_save_ms)
|
||||
#endif
|
||||
// Save every time Z is higher than the last call
|
||||
|| current_position[Z_AXIS] > info.current_position[Z_AXIS]
|
||||
// Save every time Z is higher than the last call
|
||||
|| current_position[Z_AXIS] > info.current_position[Z_AXIS]
|
||||
#endif
|
||||
) {
|
||||
|
||||
|
@ -215,20 +217,14 @@ void PrintJobRecovery::save(const bool force/*=false*/, const bool save_queue/*=
|
|||
*/
|
||||
void PrintJobRecovery::write() {
|
||||
|
||||
#if ENABLED(DEBUG_POWER_LOSS_RECOVERY)
|
||||
debug(PSTR("Write"));
|
||||
#endif
|
||||
debug(PSTR("Write"));
|
||||
|
||||
open(false);
|
||||
file.seekSet(0);
|
||||
const int16_t ret = file.write(&info, sizeof(info));
|
||||
close();
|
||||
|
||||
#if ENABLED(DEBUG_POWER_LOSS_RECOVERY)
|
||||
if (ret == -1) SERIAL_ECHOLNPGM("Power-loss file write failed.");
|
||||
#else
|
||||
UNUSED(ret);
|
||||
#endif
|
||||
if (ret == -1) DEBUG_ECHOLNPGM("Power-loss file write failed.");
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -366,65 +362,65 @@ void PrintJobRecovery::resume() {
|
|||
#if ENABLED(DEBUG_POWER_LOSS_RECOVERY)
|
||||
|
||||
void PrintJobRecovery::debug(PGM_P const prefix) {
|
||||
serialprintPGM(prefix);
|
||||
SERIAL_ECHOLNPAIR(" Job Recovery Info...\nvalid_head:", int(info.valid_head), " valid_foot:", int(info.valid_foot));
|
||||
DEBUG_PRINT_P(prefix);
|
||||
DEBUG_ECHOLNPAIR(" Job Recovery Info...\nvalid_head:", int(info.valid_head), " valid_foot:", int(info.valid_foot));
|
||||
if (info.valid_head) {
|
||||
if (info.valid_head == info.valid_foot) {
|
||||
SERIAL_ECHOPGM("current_position: ");
|
||||
DEBUG_ECHOPGM("current_position: ");
|
||||
LOOP_XYZE(i) {
|
||||
SERIAL_ECHO(info.current_position[i]);
|
||||
if (i < E_AXIS) SERIAL_CHAR(',');
|
||||
if (i) DEBUG_CHAR(',');
|
||||
DEBUG_ECHO(info.current_position[i]);
|
||||
}
|
||||
SERIAL_EOL();
|
||||
SERIAL_ECHOLNPAIR("feedrate: ", info.feedrate);
|
||||
DEBUG_EOL();
|
||||
DEBUG_ECHOLNPAIR("feedrate: ", info.feedrate);
|
||||
|
||||
#if HOTENDS > 1
|
||||
SERIAL_ECHOLNPAIR("active_hotend: ", int(info.active_hotend));
|
||||
DEBUG_ECHOLNPAIR("active_hotend: ", int(info.active_hotend));
|
||||
#endif
|
||||
|
||||
SERIAL_ECHOPGM("target_temperature: ");
|
||||
DEBUG_ECHOPGM("target_temperature: ");
|
||||
HOTEND_LOOP() {
|
||||
SERIAL_ECHO(info.target_temperature[e]);
|
||||
if (e < HOTENDS - 1) SERIAL_CHAR(',');
|
||||
DEBUG_ECHO(info.target_temperature[e]);
|
||||
if (e < HOTENDS - 1) DEBUG_CHAR(',');
|
||||
}
|
||||
SERIAL_EOL();
|
||||
DEBUG_EOL();
|
||||
|
||||
#if HAS_HEATED_BED
|
||||
SERIAL_ECHOLNPAIR("target_temperature_bed: ", info.target_temperature_bed);
|
||||
DEBUG_ECHOLNPAIR("target_temperature_bed: ", info.target_temperature_bed);
|
||||
#endif
|
||||
|
||||
#if FAN_COUNT
|
||||
SERIAL_ECHOPGM("fan_speed: ");
|
||||
DEBUG_ECHOPGM("fan_speed: ");
|
||||
FANS_LOOP(i) {
|
||||
SERIAL_ECHO(int(info.fan_speed[i]));
|
||||
if (i < FAN_COUNT - 1) SERIAL_CHAR(',');
|
||||
DEBUG_ECHO(int(info.fan_speed[i]));
|
||||
if (i < FAN_COUNT - 1) DEBUG_CHAR(',');
|
||||
}
|
||||
SERIAL_EOL();
|
||||
DEBUG_EOL();
|
||||
#endif
|
||||
|
||||
#if HAS_LEVELING
|
||||
SERIAL_ECHOLNPAIR("leveling: ", int(info.leveling), "\n fade: ", int(info.fade));
|
||||
DEBUG_ECHOLNPAIR("leveling: ", int(info.leveling), "\n fade: ", int(info.fade));
|
||||
#endif
|
||||
#if ENABLED(FWRETRACT)
|
||||
SERIAL_ECHOPGM("retract: ");
|
||||
DEBUG_ECHOPGM("retract: ");
|
||||
for (int8_t e = 0; e < EXTRUDERS; e++) {
|
||||
SERIAL_ECHO(info.retract[e]);
|
||||
if (e < EXTRUDERS - 1) SERIAL_CHAR(',');
|
||||
DEBUG_ECHO(info.retract[e]);
|
||||
if (e < EXTRUDERS - 1) DEBUG_CHAR(',');
|
||||
}
|
||||
SERIAL_EOL();
|
||||
SERIAL_ECHOLNPAIR("retract_hop: ", info.retract_hop);
|
||||
DEBUG_EOL();
|
||||
DEBUG_ECHOLNPAIR("retract_hop: ", info.retract_hop);
|
||||
#endif
|
||||
SERIAL_ECHOLNPAIR("cmd_queue_index_r: ", int(info.cmd_queue_index_r));
|
||||
SERIAL_ECHOLNPAIR("commands_in_queue: ", int(info.commands_in_queue));
|
||||
for (uint8_t i = 0; i < info.commands_in_queue; i++) SERIAL_ECHOLNPAIR("> ", info.command_queue[i]);
|
||||
SERIAL_ECHOLNPAIR("sd_filename: ", info.sd_filename);
|
||||
SERIAL_ECHOLNPAIR("sdpos: ", info.sdpos);
|
||||
SERIAL_ECHOLNPAIR("print_job_elapsed: ", info.print_job_elapsed);
|
||||
DEBUG_ECHOLNPAIR("cmd_queue_index_r: ", int(info.cmd_queue_index_r));
|
||||
DEBUG_ECHOLNPAIR("commands_in_queue: ", int(info.commands_in_queue));
|
||||
for (uint8_t i = 0; i < info.commands_in_queue; i++) DEBUG_ECHOLNPAIR("> ", info.command_queue[i]);
|
||||
DEBUG_ECHOLNPAIR("sd_filename: ", info.sd_filename);
|
||||
DEBUG_ECHOLNPAIR("sdpos: ", info.sdpos);
|
||||
DEBUG_ECHOLNPAIR("print_job_elapsed: ", info.print_job_elapsed);
|
||||
}
|
||||
else
|
||||
SERIAL_ECHOLNPGM("INVALID DATA");
|
||||
DEBUG_ECHOLNPGM("INVALID DATA");
|
||||
}
|
||||
SERIAL_ECHOLNPGM("---");
|
||||
DEBUG_ECHOLNPGM("---");
|
||||
}
|
||||
|
||||
#endif // DEBUG_POWER_LOSS_RECOVERY
|
||||
|
|
|
@ -125,9 +125,11 @@ class PrintJobRecovery {
|
|||
|
||||
static inline bool valid() { return info.valid_head && info.valid_head == info.valid_foot; }
|
||||
|
||||
#if ENABLED(DEBUG_POWER_LOSS_RECOVERY)
|
||||
static void debug(PGM_P const prefix);
|
||||
#endif
|
||||
#if ENABLED(DEBUG_POWER_LOSS_RECOVERY)
|
||||
static void debug(PGM_P const prefix);
|
||||
#else
|
||||
static inline void debug(PGM_P const prefix) { UNUSED(prefix); }
|
||||
#endif
|
||||
|
||||
private:
|
||||
static void write();
|
||||
|
|
|
@ -90,7 +90,7 @@ bool MMU2::enabled, MMU2::ready, MMU2::mmu_print_saved;
|
|||
uint8_t MMU2::cmd, MMU2::cmd_arg, MMU2::last_cmd, MMU2::extruder;
|
||||
int8_t MMU2::state = 0;
|
||||
volatile int8_t MMU2::finda = 1;
|
||||
volatile bool MMU2::findaRunoutValid;
|
||||
volatile bool MMU2::finda_runout_valid;
|
||||
int16_t MMU2::version = -1, MMU2::buildnr = -1;
|
||||
millis_t MMU2::last_request, MMU2::next_P0_request;
|
||||
char MMU2::rx_buffer[16], MMU2::tx_buffer[16];
|
||||
|
@ -103,7 +103,7 @@ char MMU2::rx_buffer[16], MMU2::tx_buffer[16];
|
|||
};
|
||||
|
||||
static constexpr E_Step ramming_sequence[] PROGMEM = { MMU2_RAMMING_SEQUENCE };
|
||||
static constexpr E_Step loadToNozzle_sequence[] PROGMEM = { MMU2_LOAD_TO_NOZZLE_SEQUENCE };
|
||||
static constexpr E_Step load_to_nozzle_sequence[] PROGMEM = { MMU2_LOAD_TO_NOZZLE_SEQUENCE };
|
||||
|
||||
#endif // MMU2_MENUS
|
||||
|
||||
|
@ -142,11 +142,11 @@ void MMU2::reset() {
|
|||
#endif
|
||||
}
|
||||
|
||||
uint8_t MMU2::getCurrentTool() {
|
||||
uint8_t MMU2::get_current_tool() {
|
||||
return extruder == MMU2_NO_TOOL ? -1 : extruder;
|
||||
}
|
||||
|
||||
void MMU2::mmuLoop() {
|
||||
void MMU2::mmu_loop() {
|
||||
|
||||
switch (state) {
|
||||
|
||||
|
@ -185,7 +185,7 @@ void MMU2::mmuLoop() {
|
|||
|
||||
DEBUG_ECHOLNPAIR("MMU => ", buildnr);
|
||||
|
||||
checkVersion();
|
||||
check_version();
|
||||
|
||||
#if ENABLED(MMU2_MODE_12V)
|
||||
DEBUG_ECHOLNPGM("MMU <= 'M1'");
|
||||
|
@ -207,7 +207,7 @@ void MMU2::mmuLoop() {
|
|||
if (rx_ok()) {
|
||||
DEBUG_ECHOLNPGM("MMU => ok");
|
||||
|
||||
checkVersion();
|
||||
check_version();
|
||||
|
||||
DEBUG_ECHOLNPGM("MMU <= 'P0'");
|
||||
|
||||
|
@ -294,13 +294,13 @@ void MMU2::mmuLoop() {
|
|||
sscanf(rx_buffer, "%hhuok\n", &finda);
|
||||
|
||||
// This is super annoying. Only activate if necessary
|
||||
// if (findaRunoutValid) DEBUG_ECHOLNPAIR_F("MMU <= 'P0'\nMMU => ", finda, 6);
|
||||
// if (finda_runout_valid) DEBUG_ECHOLNPAIR_F("MMU <= 'P0'\nMMU => ", finda, 6);
|
||||
|
||||
state = 1;
|
||||
|
||||
if (cmd == 0) ready = true;
|
||||
|
||||
if (!finda && findaRunoutValid) filamentRunout();
|
||||
if (!finda && finda_runout_valid) filament_runout();
|
||||
}
|
||||
else if (ELAPSED(millis(), last_request + MMU_P0_TIMEOUT)) // Resend request after timeout (30s)
|
||||
state = 1;
|
||||
|
@ -434,7 +434,7 @@ bool MMU2::rx_ok() {
|
|||
/**
|
||||
* Check if MMU has compatible firmware
|
||||
*/
|
||||
void MMU2::checkVersion() {
|
||||
void MMU2::check_version() {
|
||||
if (buildnr < MMU_REQUIRED_FW_BUILDNR) {
|
||||
SERIAL_ERROR_START();
|
||||
SERIAL_ECHOPGM("MMU2 firmware version invalid. Required version >= ");
|
||||
|
@ -447,7 +447,7 @@ void MMU2::checkVersion() {
|
|||
/**
|
||||
* Handle tool change
|
||||
*/
|
||||
void MMU2::toolChange(uint8_t index) {
|
||||
void MMU2::tool_change(uint8_t index) {
|
||||
|
||||
if (!enabled) return;
|
||||
|
||||
|
@ -461,7 +461,7 @@ void MMU2::toolChange(uint8_t index) {
|
|||
|
||||
command(MMU_CMD_T0 + index);
|
||||
|
||||
manageResponse(true, true);
|
||||
manage_response(true, true);
|
||||
KEEPALIVE_STATE(IN_HANDLER);
|
||||
|
||||
command(MMU_CMD_C0);
|
||||
|
@ -490,7 +490,7 @@ void MMU2::toolChange(uint8_t index) {
|
|||
* Tc Load to nozzle after filament was prepared by Tx and extruder nozzle is already heated.
|
||||
*
|
||||
*/
|
||||
void MMU2::toolChange(const char* special) {
|
||||
void MMU2::tool_change(const char* special) {
|
||||
|
||||
if (!enabled) return;
|
||||
|
||||
|
@ -501,19 +501,19 @@ void MMU2::toolChange(const char* special) {
|
|||
|
||||
switch (*special) {
|
||||
case '?': {
|
||||
uint8_t index = mmu2_chooseFilament();
|
||||
uint8_t index = mmu2_choose_filament();
|
||||
while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(100);
|
||||
loadFilamentToNozzle(index);
|
||||
load_filament_to_nozzle(index);
|
||||
} break;
|
||||
|
||||
case 'x': {
|
||||
planner.synchronize();
|
||||
uint8_t index = mmu2_chooseFilament();
|
||||
uint8_t index = mmu2_choose_filament();
|
||||
disable_E0();
|
||||
command(MMU_CMD_T0 + index);
|
||||
manageResponse(true, true);
|
||||
manage_response(true, true);
|
||||
command(MMU_CMD_C0);
|
||||
mmuLoop();
|
||||
mmu_loop();
|
||||
|
||||
enable_E0();
|
||||
extruder = index;
|
||||
|
@ -522,7 +522,7 @@ void MMU2::toolChange(const char* special) {
|
|||
|
||||
case 'c': {
|
||||
while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(100);
|
||||
executeExtruderSequence((const E_Step *)loadToNozzle_sequence, COUNT(loadToNozzle_sequence));
|
||||
execute_extruder_sequence((const E_Step *)load_to_nozzle_sequence, COUNT(load_to_nozzle_sequence));
|
||||
} break;
|
||||
}
|
||||
|
||||
|
@ -547,7 +547,7 @@ void MMU2::command(const uint8_t mmu_cmd) {
|
|||
/**
|
||||
* Wait for response from MMU
|
||||
*/
|
||||
bool MMU2::getResponse(void) {
|
||||
bool MMU2::get_response(void) {
|
||||
while (cmd != MMU_CMD_NONE) idle();
|
||||
|
||||
while (!ready) {
|
||||
|
@ -565,7 +565,7 @@ bool MMU2::getResponse(void) {
|
|||
/**
|
||||
* Wait for response and deal with timeout if nexcessary
|
||||
*/
|
||||
void MMU2::manageResponse(bool move_axes, bool turn_off_nozzle) {
|
||||
void MMU2::manage_response(bool move_axes, bool turn_off_nozzle) {
|
||||
|
||||
bool response = false;
|
||||
mmu_print_saved = false;
|
||||
|
@ -575,7 +575,7 @@ void MMU2::manageResponse(bool move_axes, bool turn_off_nozzle) {
|
|||
|
||||
while (!response) {
|
||||
|
||||
response = getResponse(); //wait for "ok" from mmu
|
||||
response = get_response(); //wait for "ok" from mmu
|
||||
|
||||
if (!response) { //no "ok" was received in reserved time frame, user will fix the issue on mmu unit
|
||||
if (!mmu_print_saved) { //first occurence, we are saving current position, park print head in certain position and disable nozzle heater
|
||||
|
@ -636,7 +636,7 @@ void MMU2::manageResponse(bool move_axes, bool turn_off_nozzle) {
|
|||
}
|
||||
}
|
||||
|
||||
void MMU2::setFilamentType(uint8_t index, uint8_t filamentType) {
|
||||
void MMU2::set_filament_type(uint8_t index, uint8_t filamentType) {
|
||||
if (!enabled) return;
|
||||
|
||||
KEEPALIVE_STATE(IN_HANDLER);
|
||||
|
@ -644,12 +644,12 @@ void MMU2::setFilamentType(uint8_t index, uint8_t filamentType) {
|
|||
cmd_arg = filamentType;
|
||||
command(MMU_CMD_F0 + index);
|
||||
|
||||
manageResponse(true, true);
|
||||
manage_response(true, true);
|
||||
|
||||
KEEPALIVE_STATE(NOT_BUSY);
|
||||
}
|
||||
|
||||
void MMU2::filamentRunout() {
|
||||
void MMU2::filament_runout() {
|
||||
enqueue_and_echo_commands_P(PSTR(MMU2_FILAMENT_RUNOUT_SCRIPT));
|
||||
planner.synchronize();
|
||||
}
|
||||
|
@ -657,10 +657,10 @@ void MMU2::filamentRunout() {
|
|||
#if HAS_LCD_MENU && ENABLED(MMU2_MENUS)
|
||||
|
||||
// Load filament into MMU2
|
||||
void MMU2::loadFilament(uint8_t index) {
|
||||
void MMU2::load_filament(uint8_t index) {
|
||||
if (!enabled) return;
|
||||
command(MMU_CMD_L0 + index);
|
||||
manageResponse(false, false);
|
||||
manage_response(false, false);
|
||||
BUZZ(200, 404);
|
||||
}
|
||||
|
||||
|
@ -669,7 +669,7 @@ void MMU2::filamentRunout() {
|
|||
* Switch material and load to nozzle
|
||||
*
|
||||
*/
|
||||
bool MMU2::loadFilamentToNozzle(uint8_t index) {
|
||||
bool MMU2::load_filament_to_nozzle(uint8_t index) {
|
||||
|
||||
if (!enabled) return false;
|
||||
|
||||
|
@ -682,14 +682,14 @@ void MMU2::filamentRunout() {
|
|||
KEEPALIVE_STATE(IN_HANDLER);
|
||||
|
||||
command(MMU_CMD_T0 + index);
|
||||
manageResponse(true, true);
|
||||
manage_response(true, true);
|
||||
command(MMU_CMD_C0);
|
||||
mmuLoop();
|
||||
mmu_loop();
|
||||
|
||||
extruder = index;
|
||||
active_extruder = 0;
|
||||
|
||||
loadToNozzle();
|
||||
load_to_nozzle();
|
||||
|
||||
BUZZ(200, 404);
|
||||
|
||||
|
@ -706,12 +706,12 @@ void MMU2::filamentRunout() {
|
|||
* It is not used after T0 .. T4 command (select filament), in such case, gcode is responsible for loading
|
||||
* filament to nozzle.
|
||||
*/
|
||||
void MMU2::loadToNozzle() {
|
||||
void MMU2::load_to_nozzle() {
|
||||
if (!enabled) return;
|
||||
executeExtruderSequence((const E_Step *)loadToNozzle_sequence, COUNT(loadToNozzle_sequence));
|
||||
execute_extruder_sequence((const E_Step *)load_to_nozzle_sequence, COUNT(load_to_nozzle_sequence));
|
||||
}
|
||||
|
||||
bool MMU2::ejectFilament(uint8_t index, bool recover) {
|
||||
bool MMU2::eject_filament(uint8_t index, bool recover) {
|
||||
|
||||
if (!enabled) return false;
|
||||
|
||||
|
@ -731,7 +731,7 @@ void MMU2::filamentRunout() {
|
|||
planner.buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 2500 / 60, active_extruder);
|
||||
planner.synchronize();
|
||||
command(MMU_CMD_E0 + index);
|
||||
manageResponse(false, false);
|
||||
manage_response(false, false);
|
||||
|
||||
if (recover) {
|
||||
LCD_MESSAGEPGM(MSG_MMU2_EJECT_RECOVER);
|
||||
|
@ -745,7 +745,7 @@ void MMU2::filamentRunout() {
|
|||
BUZZ(200, 404);
|
||||
|
||||
command(MMU_CMD_R0);
|
||||
manageResponse(false, false);
|
||||
manage_response(false, false);
|
||||
}
|
||||
|
||||
ui.reset_status();
|
||||
|
@ -783,10 +783,10 @@ void MMU2::filamentRunout() {
|
|||
|
||||
KEEPALIVE_STATE(IN_HANDLER);
|
||||
|
||||
filamentRamming();
|
||||
filament_ramming();
|
||||
|
||||
command(MMU_CMD_U0);
|
||||
manageResponse(false, true);
|
||||
manage_response(false, true);
|
||||
|
||||
BUZZ(200, 404);
|
||||
|
||||
|
@ -803,11 +803,11 @@ void MMU2::filamentRunout() {
|
|||
/**
|
||||
* Unload sequence to optimize shape of the tip of the unloaded filament
|
||||
*/
|
||||
void MMU2::filamentRamming() {
|
||||
executeExtruderSequence((const E_Step *)ramming_sequence, sizeof(ramming_sequence) / sizeof(E_Step));
|
||||
void MMU2::filament_ramming() {
|
||||
execute_extruder_sequence((const E_Step *)ramming_sequence, sizeof(ramming_sequence) / sizeof(E_Step));
|
||||
}
|
||||
|
||||
void MMU2::executeExtruderSequence(const E_Step * sequence, int steps) {
|
||||
void MMU2::execute_extruder_sequence(const E_Step * sequence, int steps) {
|
||||
|
||||
planner.synchronize();
|
||||
enable_E0();
|
||||
|
|
|
@ -36,18 +36,18 @@ public:
|
|||
|
||||
static void init();
|
||||
static void reset();
|
||||
static void mmuLoop();
|
||||
static void toolChange(uint8_t index);
|
||||
static void toolChange(const char* special);
|
||||
static uint8_t getCurrentTool();
|
||||
static void setFilamentType(uint8_t index, uint8_t type);
|
||||
static void mmu_loop();
|
||||
static void tool_change(uint8_t index);
|
||||
static void tool_change(const char* special);
|
||||
static uint8_t get_current_tool();
|
||||
static void set_filament_type(uint8_t index, uint8_t type);
|
||||
|
||||
#if HAS_LCD_MENU && ENABLED(MMU2_MENUS)
|
||||
static bool unload();
|
||||
static void loadFilament(uint8_t);
|
||||
static void loadAll();
|
||||
static bool loadFilamentToNozzle(uint8_t index);
|
||||
static bool ejectFilament(uint8_t index, bool recover);
|
||||
static void load_filament(uint8_t);
|
||||
static void load_all();
|
||||
static bool load_filament_to_nozzle(uint8_t index);
|
||||
static bool eject_filament(uint8_t index, bool recover);
|
||||
#endif
|
||||
|
||||
private:
|
||||
|
@ -59,31 +59,31 @@ private:
|
|||
|
||||
static bool rx_ok();
|
||||
static bool rx_start();
|
||||
static void checkVersion();
|
||||
static void check_version();
|
||||
|
||||
static void command(const uint8_t cmd);
|
||||
static bool getResponse(void);
|
||||
static void manageResponse(bool move_axes, bool turn_off_nozzle);
|
||||
static bool get_response(void);
|
||||
static void manage_response(bool move_axes, bool turn_off_nozzle);
|
||||
|
||||
#if HAS_LCD_MENU && ENABLED(MMU2_MENUS)
|
||||
static void loadToNozzle();
|
||||
static void filamentRamming();
|
||||
static void executeExtruderSequence(const E_Step * sequence, int steps);
|
||||
static void load_to_nozzle();
|
||||
static void filament_ramming();
|
||||
static void execute_extruder_sequence(const E_Step * sequence, int steps);
|
||||
#endif
|
||||
|
||||
static void filamentRunout();
|
||||
static void filament_runout();
|
||||
|
||||
static bool enabled, ready, mmu_print_saved;
|
||||
static uint8_t cmd, cmd_arg, last_cmd, extruder;
|
||||
static int8_t state;
|
||||
static volatile int8_t finda;
|
||||
static volatile bool findaRunoutValid;
|
||||
static volatile bool finda_runout_valid;
|
||||
static int16_t version, buildnr;
|
||||
static millis_t last_request, next_P0_request;
|
||||
static char rx_buffer[16], tx_buffer[16];
|
||||
|
||||
static inline void set_runout_valid(const bool valid) {
|
||||
findaRunoutValid = valid;
|
||||
finda_runout_valid = valid;
|
||||
#if HAS_FILAMENT_SENSOR
|
||||
if (valid) runout.reset();
|
||||
#endif
|
||||
|
|
|
@ -49,7 +49,7 @@ class FilamentMonitorBase {
|
|||
#if ENABLED(HOST_ACTION_COMMANDS)
|
||||
static bool host_handling;
|
||||
#else
|
||||
constexpr static bool host_handling = false;
|
||||
static constexpr bool host_handling = false;
|
||||
#endif
|
||||
};
|
||||
|
||||
|
|
|
@ -474,7 +474,7 @@
|
|||
switch (i) {
|
||||
case TMC_PWM_SCALE: SERIAL_PRINT(st.PWM_SCALE(), DEC); break;
|
||||
case TMC_SGT: SERIAL_PRINT(st.sgt(), DEC); break;
|
||||
case TMC_STEALTHCHOP: serialprintPGM(st.en_pwm_mode() ? PSTR("true") : PSTR("false")); break;
|
||||
case TMC_STEALTHCHOP: serialprint_truefalse(st.en_pwm_mode()); break;
|
||||
default: break;
|
||||
}
|
||||
}
|
||||
|
@ -497,7 +497,7 @@
|
|||
switch (i) {
|
||||
case TMC_PWM_SCALE: SERIAL_PRINT(st.PWM_SCALE(), DEC); break;
|
||||
case TMC_SGT: SERIAL_PRINT(st.sgt(), DEC); break;
|
||||
case TMC_STEALTHCHOP: serialprintPGM(st.en_pwm_mode() ? PSTR("true") : PSTR("false")); break;
|
||||
case TMC_STEALTHCHOP: serialprint_truefalse(st.en_pwm_mode()); break;
|
||||
case TMC_GLOBAL_SCALER:
|
||||
{
|
||||
uint16_t value = st.GLOBAL_SCALER();
|
||||
|
@ -514,7 +514,7 @@
|
|||
static void tmc_status(TMC2208Stepper &st, const TMC_debug_enum i) {
|
||||
switch (i) {
|
||||
case TMC_PWM_SCALE: SERIAL_PRINT(st.pwm_scale_sum(), DEC); break;
|
||||
case TMC_STEALTHCHOP: serialprintPGM(st.stealth() ? PSTR("true") : PSTR("false")); break;
|
||||
case TMC_STEALTHCHOP: serialprint_truefalse(st.stealth()); break;
|
||||
case TMC_S2VSA: if (st.s2vsa()) SERIAL_CHAR('X'); break;
|
||||
case TMC_S2VSB: if (st.s2vsb()) SERIAL_CHAR('X'); break;
|
||||
default: break;
|
||||
|
@ -541,7 +541,7 @@
|
|||
SERIAL_CHAR('\t');
|
||||
switch (i) {
|
||||
case TMC_CODES: st.printLabel(); break;
|
||||
case TMC_ENABLED: serialprintPGM(st.isEnabled() ? PSTR("true") : PSTR("false")); break;
|
||||
case TMC_ENABLED: serialprint_truefalse(st.isEnabled()); break;
|
||||
case TMC_CURRENT: SERIAL_ECHO(st.getMilliamps()); break;
|
||||
case TMC_RMS_CURRENT: SERIAL_ECHO(st.rms_current()); break;
|
||||
case TMC_MAX_CURRENT: SERIAL_PRINT((float)st.rms_current() * 1.41, 0); break;
|
||||
|
@ -578,9 +578,9 @@
|
|||
SERIAL_CHAR('-');
|
||||
}
|
||||
break;
|
||||
case TMC_OTPW: serialprintPGM(st.otpw() ? PSTR("true") : PSTR("false")); break;
|
||||
case TMC_OTPW: serialprint_truefalse(st.otpw()); break;
|
||||
#if ENABLED(MONITOR_DRIVER_STATUS)
|
||||
case TMC_OTPW_TRIGGERED: serialprintPGM(st.getOTPW() ? PSTR("true") : PSTR("false")); break;
|
||||
case TMC_OTPW_TRIGGERED: serialprint_truefalse(st.getOTPW()); break;
|
||||
#endif
|
||||
case TMC_TOFF: SERIAL_PRINT(st.toff(), DEC); break;
|
||||
case TMC_TBL: SERIAL_PRINT(st.blank_time(), DEC); break;
|
||||
|
@ -596,7 +596,7 @@
|
|||
SERIAL_CHAR('\t');
|
||||
switch (i) {
|
||||
case TMC_CODES: st.printLabel(); break;
|
||||
case TMC_ENABLED: serialprintPGM(st.isEnabled() ? PSTR("true") : PSTR("false")); break;
|
||||
case TMC_ENABLED: serialprint_truefalse(st.isEnabled()); break;
|
||||
case TMC_CURRENT: SERIAL_ECHO(st.getMilliamps()); break;
|
||||
case TMC_RMS_CURRENT: SERIAL_ECHO(st.rms_current()); break;
|
||||
case TMC_MAX_CURRENT: SERIAL_PRINT((float)st.rms_current() * 1.41, 0); break;
|
||||
|
@ -606,8 +606,8 @@
|
|||
break;
|
||||
case TMC_VSENSE: serialprintPGM(st.vsense() ? PSTR("1=.165") : PSTR("0=.310")); break;
|
||||
case TMC_MICROSTEPS: SERIAL_ECHO(st.microsteps()); break;
|
||||
//case TMC_OTPW: serialprintPGM(st.otpw() ? PSTR("true") : PSTR("false")); break;
|
||||
//case TMC_OTPW_TRIGGERED: serialprintPGM(st.getOTPW() ? PSTR("true") : PSTR("false")); break;
|
||||
//case TMC_OTPW: serialprint_truefalse(st.otpw()); break;
|
||||
//case TMC_OTPW_TRIGGERED: serialprint_truefalse(st.getOTPW()); break;
|
||||
case TMC_SGT: SERIAL_PRINT(st.sgt(), DEC); break;
|
||||
case TMC_TOFF: SERIAL_PRINT(st.toff(), DEC); break;
|
||||
case TMC_TBL: SERIAL_PRINT(st.blank_time(), DEC); break;
|
||||
|
|
|
@ -227,7 +227,7 @@ void tmc_set_current(TMC &st, const int mA) {
|
|||
void tmc_report_otpw(TMC &st) {
|
||||
st.printLabel();
|
||||
SERIAL_ECHOPGM(" temperature prewarn triggered: ");
|
||||
serialprintPGM(st.getOTPW() ? PSTR("true") : PSTR("false"));
|
||||
serialprint_truefalse(st.getOTPW());
|
||||
SERIAL_EOL();
|
||||
}
|
||||
template<typename TMC>
|
||||
|
|
|
@ -246,8 +246,6 @@ void move_to(const float &rx, const float &ry, const float &z, const float &e_de
|
|||
// Yes: a 'normal' movement. No: a retract() or recover()
|
||||
feed_value = has_xy_component ? G26_XY_FEEDRATE : planner.settings.max_feedrate_mm_s[E_AXIS] / 1.5;
|
||||
|
||||
if (g26_debug_flag) SERIAL_ECHOLNPAIR("in move_to() feed_value for XY:", feed_value);
|
||||
|
||||
destination[X_AXIS] = rx;
|
||||
destination[Y_AXIS] = ry;
|
||||
destination[E_AXIS] += e_delta;
|
||||
|
@ -327,19 +325,15 @@ inline bool look_for_lines_to_connect() {
|
|||
for (uint8_t j = 0; j < GRID_MAX_POINTS_Y; j++) {
|
||||
|
||||
#if HAS_LCD_MENU
|
||||
if (user_canceled()) return true; // Check if the user wants to stop the Mesh Validation
|
||||
if (user_canceled()) return true;
|
||||
#endif
|
||||
|
||||
if (i < GRID_MAX_POINTS_X) { // We can't connect to anything to the right than GRID_MAX_POINTS_X.
|
||||
// This is already a half circle because we are at the edge of the bed.
|
||||
if (i < GRID_MAX_POINTS_X) { // Can't connect to anything to the right than GRID_MAX_POINTS_X.
|
||||
// Already a half circle at the edge of the bed.
|
||||
|
||||
if (is_bitmap_set(circle_flags, i, j) && is_bitmap_set(circle_flags, i + 1, j)) { // check if we can do a line to the left
|
||||
if (!is_bitmap_set(horizontal_mesh_line_flags, i, j)) {
|
||||
|
||||
//
|
||||
// We found two circles that need a horizontal line to connect them
|
||||
// Print it!
|
||||
//
|
||||
// Two circles need a horizontal line to connect them
|
||||
sx = _GET_MESH_X( i ) + (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)); // right edge
|
||||
ex = _GET_MESH_X(i + 1) - (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)); // left edge
|
||||
|
||||
|
@ -347,27 +341,19 @@ inline bool look_for_lines_to_connect() {
|
|||
sy = ey = constrain(_GET_MESH_Y(j), Y_MIN_POS + 1, Y_MAX_POS - 1);
|
||||
ex = constrain(ex, X_MIN_POS + 1, X_MAX_POS - 1);
|
||||
|
||||
if (position_is_reachable(sx, sy) && position_is_reachable(ex, ey)) {
|
||||
|
||||
if (g26_debug_flag) {
|
||||
SERIAL_ECHOLNPAIR(" Connecting with horizontal line (sx=", sx, ", sy=", sy, ") -> (ex=", ex, ", ey=", ey, ")");
|
||||
//debug_current_and_destination(PSTR("Connecting horizontal line."));
|
||||
}
|
||||
if (position_is_reachable(sx, sy) && position_is_reachable(ex, ey))
|
||||
print_line_from_here_to_there(sx, sy, g26_layer_height, ex, ey, g26_layer_height);
|
||||
}
|
||||
bitmap_set(horizontal_mesh_line_flags, i, j); // Mark it as done so we don't do it again, even if we skipped it
|
||||
|
||||
bitmap_set(horizontal_mesh_line_flags, i, j); // Mark done, even if skipped
|
||||
}
|
||||
}
|
||||
|
||||
if (j < GRID_MAX_POINTS_Y) { // We can't connect to anything further back than GRID_MAX_POINTS_Y.
|
||||
// This is already a half circle because we are at the edge of the bed.
|
||||
if (j < GRID_MAX_POINTS_Y) { // Can't connect to anything further back than GRID_MAX_POINTS_Y.
|
||||
// Already a half circle at the edge of the bed.
|
||||
|
||||
if (is_bitmap_set(circle_flags, i, j) && is_bitmap_set(circle_flags, i, j + 1)) { // check if we can do a line straight down
|
||||
if (!is_bitmap_set( vertical_mesh_line_flags, i, j)) {
|
||||
//
|
||||
// We found two circles that need a vertical line to connect them
|
||||
// Print it!
|
||||
//
|
||||
// Two circles that need a vertical line to connect them
|
||||
sy = _GET_MESH_Y( j ) + (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)); // top edge
|
||||
ey = _GET_MESH_Y(j + 1) - (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)); // bottom edge
|
||||
|
||||
|
@ -375,23 +361,10 @@ inline bool look_for_lines_to_connect() {
|
|||
sy = constrain(sy, Y_MIN_POS + 1, Y_MAX_POS - 1);
|
||||
ey = constrain(ey, Y_MIN_POS + 1, Y_MAX_POS - 1);
|
||||
|
||||
if (position_is_reachable(sx, sy) && position_is_reachable(ex, ey)) {
|
||||
|
||||
if (g26_debug_flag) {
|
||||
SERIAL_ECHOPAIR(" Connecting with vertical line (sx=", sx);
|
||||
SERIAL_ECHOPAIR(", sy=", sy);
|
||||
SERIAL_ECHOPAIR(") -> (ex=", ex);
|
||||
SERIAL_ECHOPAIR(", ey=", ey);
|
||||
SERIAL_CHAR(')');
|
||||
SERIAL_EOL();
|
||||
|
||||
#if ENABLED(AUTO_BED_LEVELING_UBL)
|
||||
debug_current_and_destination(PSTR("Connecting vertical line."));
|
||||
#endif
|
||||
}
|
||||
if (position_is_reachable(sx, sy) && position_is_reachable(ex, ey))
|
||||
print_line_from_here_to_there(sx, sy, g26_layer_height, ex, ey, g26_layer_height);
|
||||
}
|
||||
bitmap_set(vertical_mesh_line_flags, i, j); // Mark it as done so we don't do it again, even if skipped
|
||||
|
||||
bitmap_set(vertical_mesh_line_flags, i, j); // Mark done, even if skipped
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -725,8 +698,6 @@ void GcodeSuite::G26() {
|
|||
ui.capture();
|
||||
#endif
|
||||
|
||||
//debug_current_and_destination(PSTR("Starting G26 Mesh Validation Pattern."));
|
||||
|
||||
#if DISABLED(ARC_SUPPORT)
|
||||
|
||||
/**
|
||||
|
@ -768,6 +739,7 @@ void GcodeSuite::G26() {
|
|||
#if ENABLED(ARC_SUPPORT)
|
||||
|
||||
#define ARC_LENGTH(quarters) (INTERSECTION_CIRCLE_RADIUS * M_PI * (quarters) / 2)
|
||||
#define INTERSECTION_CIRCLE_DIAM ((INTERSECTION_CIRCLE_RADIUS) * 2)
|
||||
float sx = circle_x + INTERSECTION_CIRCLE_RADIUS, // default to full circle
|
||||
ex = circle_x + INTERSECTION_CIRCLE_RADIUS,
|
||||
sy = circle_y, ey = circle_y,
|
||||
|
@ -775,14 +747,8 @@ void GcodeSuite::G26() {
|
|||
|
||||
// Figure out where to start and end the arc - we always print counterclockwise
|
||||
if (xi == 0) { // left edge
|
||||
if (!f) {
|
||||
sx = circle_x;
|
||||
sy -= (INTERSECTION_CIRCLE_RADIUS);
|
||||
}
|
||||
if (!b) {
|
||||
ex = circle_x;
|
||||
ey += INTERSECTION_CIRCLE_RADIUS;
|
||||
}
|
||||
if (!f) { sx = circle_x; sy -= INTERSECTION_CIRCLE_RADIUS; }
|
||||
if (!b) { ex = circle_x; ey += INTERSECTION_CIRCLE_RADIUS; }
|
||||
arc_length = (f || b) ? ARC_LENGTH(1) : ARC_LENGTH(2);
|
||||
}
|
||||
else if (r) { // right edge
|
||||
|
@ -793,26 +759,23 @@ void GcodeSuite::G26() {
|
|||
arc_length = (f || b) ? ARC_LENGTH(1) : ARC_LENGTH(2);
|
||||
}
|
||||
else if (f) {
|
||||
ex = circle_x - (INTERSECTION_CIRCLE_RADIUS);
|
||||
ex -= INTERSECTION_CIRCLE_DIAM;
|
||||
arc_length = ARC_LENGTH(2);
|
||||
}
|
||||
else if (b) {
|
||||
sx = circle_x - (INTERSECTION_CIRCLE_RADIUS);
|
||||
sx -= INTERSECTION_CIRCLE_DIAM;
|
||||
arc_length = ARC_LENGTH(2);
|
||||
}
|
||||
const float arc_offset[2] = {
|
||||
circle_x - sx,
|
||||
circle_y - sy
|
||||
};
|
||||
|
||||
const float dx_s = current_position[X_AXIS] - sx, // find our distance from the start of the actual circle
|
||||
const float arc_offset[2] = { circle_x - sx, circle_y - sy },
|
||||
dx_s = current_position[X_AXIS] - sx, // find our distance from the start of the actual circle
|
||||
dy_s = current_position[Y_AXIS] - sy,
|
||||
dist_start = HYPOT2(dx_s, dy_s);
|
||||
const float endpoint[XYZE] = {
|
||||
ex, ey,
|
||||
g26_layer_height,
|
||||
current_position[E_AXIS] + (arc_length * g26_e_axis_feedrate * g26_extrusion_multiplier)
|
||||
};
|
||||
dist_start = HYPOT2(dx_s, dy_s),
|
||||
endpoint[XYZE] = {
|
||||
ex, ey,
|
||||
g26_layer_height,
|
||||
current_position[E_AXIS] + (arc_length * g26_e_axis_feedrate * g26_extrusion_multiplier)
|
||||
};
|
||||
|
||||
if (dist_start > 2.0) {
|
||||
retract_filament(destination);
|
||||
|
@ -827,18 +790,6 @@ void GcodeSuite::G26() {
|
|||
const float save_feedrate = feedrate_mm_s;
|
||||
feedrate_mm_s = PLANNER_XY_FEEDRATE() / 10.0;
|
||||
|
||||
if (g26_debug_flag) {
|
||||
SERIAL_ECHOPAIR(" plan_arc(ex=", endpoint[X_AXIS]);
|
||||
SERIAL_ECHOPAIR(", ey=", endpoint[Y_AXIS]);
|
||||
SERIAL_ECHOPAIR(", ez=", endpoint[Z_AXIS]);
|
||||
SERIAL_ECHOPAIR(", len=", arc_length);
|
||||
SERIAL_ECHOPAIR(") -> (ex=", current_position[X_AXIS]);
|
||||
SERIAL_ECHOPAIR(", ey=", current_position[Y_AXIS]);
|
||||
SERIAL_ECHOPAIR(", ez=", current_position[Z_AXIS]);
|
||||
SERIAL_CHAR(')');
|
||||
SERIAL_EOL();
|
||||
}
|
||||
|
||||
plan_arc(endpoint, arc_offset, false); // Draw a counter-clockwise arc
|
||||
feedrate_mm_s = save_feedrate;
|
||||
set_destination_from_current();
|
||||
|
@ -906,16 +857,13 @@ void GcodeSuite::G26() {
|
|||
retract_filament(destination);
|
||||
destination[Z_AXIS] = Z_CLEARANCE_BETWEEN_PROBES;
|
||||
|
||||
//debug_current_and_destination(PSTR("ready to do Z-Raise."));
|
||||
move_to(destination, 0); // Raise the nozzle
|
||||
//debug_current_and_destination(PSTR("done doing Z-Raise."));
|
||||
|
||||
destination[X_AXIS] = g26_x_pos; // Move back to the starting position
|
||||
destination[Y_AXIS] = g26_y_pos;
|
||||
//destination[Z_AXIS] = Z_CLEARANCE_BETWEEN_PROBES; // Keep the nozzle where it is
|
||||
|
||||
move_to(destination, 0); // Move back to the starting position
|
||||
//debug_current_and_destination(PSTR("done doing X/Y move."));
|
||||
|
||||
#if DISABLED(NO_VOLUMETRICS)
|
||||
parser.volumetric_enabled = volumetric_was_enabled;
|
||||
|
|
|
@ -182,7 +182,6 @@
|
|||
*
|
||||
*/
|
||||
void GcodeSuite::G28(const bool always_home_all) {
|
||||
|
||||
if (DEBUGGING(LEVELING)) {
|
||||
DEBUG_ECHOLNPGM(">>> G28");
|
||||
log_machine_info();
|
||||
|
@ -268,13 +267,16 @@ void GcodeSuite::G28(const bool always_home_all) {
|
|||
const bool homeX = always_home_all || parser.seen('X'),
|
||||
homeY = always_home_all || parser.seen('Y'),
|
||||
homeZ = always_home_all || parser.seen('Z'),
|
||||
home_all = (!homeX && !homeY && !homeZ) || (homeX && homeY && homeZ);
|
||||
home_all = (!homeX && !homeY && !homeZ) || (homeX && homeY && homeZ),
|
||||
doX = home_all || homeX,
|
||||
doY = home_all || homeY,
|
||||
doZ = home_all || homeZ;
|
||||
|
||||
set_destination_from_current();
|
||||
|
||||
#if Z_HOME_DIR > 0 // If homing away from BED do Z first
|
||||
|
||||
if (home_all || homeZ) homeaxis(Z_AXIS);
|
||||
if (doZ) homeaxis(Z_AXIS);
|
||||
|
||||
#endif
|
||||
|
||||
|
@ -285,7 +287,7 @@ void GcodeSuite::G28(const bool always_home_all) {
|
|||
(parser.seenval('R') ? parser.value_linear_units() : Z_HOMING_HEIGHT)
|
||||
);
|
||||
|
||||
if (z_homing_height && (home_all || homeX || homeY)) {
|
||||
if (z_homing_height && (doX || doY)) {
|
||||
// Raise Z before homing any other axes and z is not already high enough (never lower z)
|
||||
destination[Z_AXIS] = z_homing_height;
|
||||
if (destination[Z_AXIS] > current_position[Z_AXIS]) {
|
||||
|
@ -296,25 +298,25 @@ void GcodeSuite::G28(const bool always_home_all) {
|
|||
|
||||
#if ENABLED(QUICK_HOME)
|
||||
|
||||
if (home_all || (homeX && homeY)) quick_home_xy();
|
||||
if (doX && doY) quick_home_xy();
|
||||
|
||||
#endif
|
||||
|
||||
// Home Y (before X)
|
||||
#if ENABLED(HOME_Y_BEFORE_X)
|
||||
|
||||
if (home_all || homeY
|
||||
if (doY
|
||||
#if ENABLED(CODEPENDENT_XY_HOMING)
|
||||
|| homeX
|
||||
|| doX
|
||||
#endif
|
||||
) homeaxis(Y_AXIS);
|
||||
|
||||
#endif
|
||||
|
||||
// Home X
|
||||
if (home_all || homeX
|
||||
if (doX
|
||||
#if ENABLED(CODEPENDENT_XY_HOMING) && DISABLED(HOME_Y_BEFORE_X)
|
||||
|| homeY
|
||||
|| doY
|
||||
#endif
|
||||
) {
|
||||
|
||||
|
@ -345,12 +347,12 @@ void GcodeSuite::G28(const bool always_home_all) {
|
|||
|
||||
// Home Y (after X)
|
||||
#if DISABLED(HOME_Y_BEFORE_X)
|
||||
if (home_all || homeY) homeaxis(Y_AXIS);
|
||||
if (doY) homeaxis(Y_AXIS);
|
||||
#endif
|
||||
|
||||
// Home Z last if homing towards the bed
|
||||
#if Z_HOME_DIR < 0
|
||||
if (home_all || homeZ) {
|
||||
if (doZ) {
|
||||
#if ENABLED(Z_SAFE_HOMING)
|
||||
home_z_safely();
|
||||
#else
|
||||
|
@ -361,7 +363,7 @@ void GcodeSuite::G28(const bool always_home_all) {
|
|||
move_z_after_probing();
|
||||
#endif
|
||||
|
||||
} // home_all || homeZ
|
||||
} // doZ
|
||||
#endif // Z_HOME_DIR < 0
|
||||
|
||||
sync_plan_position();
|
||||
|
@ -402,6 +404,15 @@ void GcodeSuite::G28(const bool always_home_all) {
|
|||
|
||||
#endif // DUAL_X_CARRIAGE
|
||||
|
||||
#ifdef HOMING_BACKOFF_MM
|
||||
endstops.enable(false);
|
||||
constexpr float endstop_backoff[XYZ] = HOMING_BACKOFF_MM;
|
||||
const float backoff_x = doX ? ABS(endstop_backoff[X_AXIS]) * (X_HOME_DIR) : 0,
|
||||
backoff_y = doY ? ABS(endstop_backoff[Y_AXIS]) * (Y_HOME_DIR) : 0,
|
||||
backoff_z = doZ ? ABS(endstop_backoff[Z_AXIS]) * (Z_HOME_DIR) : 0;
|
||||
if (backoff_z) do_blocking_move_to_z(current_position[Z_AXIS] - backoff_z);
|
||||
if (backoff_x || backoff_y) do_blocking_move_to_xy(current_position[X_AXIS] - backoff_x, current_position[Y_AXIS] - backoff_y);
|
||||
#endif
|
||||
endstops.not_homing();
|
||||
|
||||
#if BOTH(DELTA, DELTA_HOME_TO_SAFE_ZONE)
|
||||
|
@ -417,7 +428,7 @@ void GcodeSuite::G28(const bool always_home_all) {
|
|||
|
||||
// Restore the active tool after homing
|
||||
#if HOTENDS > 1 && (DISABLED(DELTA) || ENABLED(DELTA_HOME_TO_SAFE_ZONE))
|
||||
#if ENABLED(PARKING_EXTRUDER) || ENABLED(DUAL_X_CARRIAGE)
|
||||
#if EITHER(PARKING_EXTRUDER, DUAL_X_CARRIAGE)
|
||||
#define NO_FETCH false // fetch the previous toolhead
|
||||
#else
|
||||
#define NO_FETCH true
|
||||
|
@ -430,9 +441,9 @@ void GcodeSuite::G28(const bool always_home_all) {
|
|||
report_current_position();
|
||||
#if ENABLED(NANODLP_Z_SYNC)
|
||||
#if ENABLED(NANODLP_ALL_AXIS)
|
||||
#define _HOME_SYNC true // For any axis, output sync text.
|
||||
#define _HOME_SYNC true // For any axis, output sync text.
|
||||
#else
|
||||
#define _HOME_SYNC (home_all || homeZ) // Only for Z-axis
|
||||
#define _HOME_SYNC doZ // Only for Z-axis
|
||||
#endif
|
||||
if (_HOME_SYNC)
|
||||
SERIAL_ECHOLNPGM(MSG_Z_MOVE_COMP);
|
||||
|
|
|
@ -30,7 +30,7 @@
|
|||
void M217_report(const bool eeprom=false) {
|
||||
|
||||
#if ENABLED(TOOLCHANGE_FILAMENT_SWAP)
|
||||
serialprintPGM(eeprom ? PSTR(" M217") : PSTR("Singlenozzle:"));
|
||||
serialprintPGM(eeprom ? PSTR(" M217") : PSTR("Toolchange:"));
|
||||
SERIAL_ECHOPAIR(" S", LINEAR_UNIT(toolchange_settings.swap_length));
|
||||
SERIAL_ECHOPAIR(" P", LINEAR_UNIT(toolchange_settings.prime_speed));
|
||||
SERIAL_ECHOPAIR(" R", LINEAR_UNIT(toolchange_settings.retract_speed));
|
||||
|
|
|
@ -47,13 +47,13 @@ inline void toggle_pins() {
|
|||
|
||||
for (uint8_t i = start; i <= end; i++) {
|
||||
pin_t pin = GET_PIN_MAP_PIN(i);
|
||||
//report_pin_state_extended(pin, ignore_protection, false);
|
||||
if (!VALID_PIN(pin)) continue;
|
||||
if (!ignore_protection && pin_is_protected(pin)) {
|
||||
if (M43_NEVER_TOUCH(i) || (!ignore_protection && pin_is_protected(pin))) {
|
||||
report_pin_state_extended(pin, ignore_protection, true, "Untouched ");
|
||||
SERIAL_EOL();
|
||||
}
|
||||
else {
|
||||
watchdog_reset();
|
||||
report_pin_state_extended(pin, ignore_protection, true, "Pulsing ");
|
||||
#if AVR_AT90USB1286_FAMILY // Teensy IDEs don't know about these pins so must use FASTIO
|
||||
if (pin == TEENSY_E2) {
|
||||
|
@ -77,12 +77,12 @@ inline void toggle_pins() {
|
|||
{
|
||||
pinMode(pin, OUTPUT);
|
||||
for (int16_t j = 0; j < repeat; j++) {
|
||||
extDigitalWrite(pin, 0); safe_delay(wait);
|
||||
extDigitalWrite(pin, 1); safe_delay(wait);
|
||||
extDigitalWrite(pin, 0); safe_delay(wait);
|
||||
watchdog_reset(); extDigitalWrite(pin, 0); safe_delay(wait);
|
||||
watchdog_reset(); extDigitalWrite(pin, 1); safe_delay(wait);
|
||||
watchdog_reset(); extDigitalWrite(pin, 0); safe_delay(wait);
|
||||
watchdog_reset();
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
SERIAL_EOL();
|
||||
}
|
||||
|
@ -277,7 +277,7 @@ void GcodeSuite::M43() {
|
|||
for (uint8_t i = first_pin; i <= last_pin; i++) {
|
||||
pin_t pin = GET_PIN_MAP_PIN(i);
|
||||
if (!VALID_PIN(pin)) continue;
|
||||
if (!ignore_protection && pin_is_protected(pin)) continue;
|
||||
if (M43_NEVER_TOUCH(i) || (!ignore_protection && pin_is_protected(pin))) continue;
|
||||
pinMode(pin, INPUT_PULLUP);
|
||||
delay(1);
|
||||
/*
|
||||
|
@ -300,7 +300,7 @@ void GcodeSuite::M43() {
|
|||
for (uint8_t i = first_pin; i <= last_pin; i++) {
|
||||
pin_t pin = GET_PIN_MAP_PIN(i);
|
||||
if (!VALID_PIN(pin)) continue;
|
||||
if (!ignore_protection && pin_is_protected(pin)) continue;
|
||||
if (M43_NEVER_TOUCH(i) || (!ignore_protection && pin_is_protected(pin))) continue;
|
||||
const byte val =
|
||||
/*
|
||||
IS_ANALOG(pin)
|
||||
|
|
|
@ -53,7 +53,7 @@ uint8_t spindle_laser_power; // = 0
|
|||
* NOTE: A minimum PWM frequency of 50 Hz is needed. All prescaler
|
||||
* factors for timers 2, 3, 4, and 5 are acceptable.
|
||||
*
|
||||
* SPINDLE_LASER_ENABLE_PIN needs an external pullup or it may power on
|
||||
* SPINDLE_LASER_ENA_PIN needs an external pullup or it may power on
|
||||
* the spindle/laser during power-up or when connecting to the host
|
||||
* (usually goes through a reset which sets all I/O pins to tri-state)
|
||||
*
|
||||
|
@ -73,7 +73,7 @@ inline void delay_for_power_down() { safe_delay(SPINDLE_LASER_POWERDOWN_DELAY);
|
|||
*/
|
||||
|
||||
inline void set_spindle_laser_ocr(const uint8_t ocr) {
|
||||
WRITE(SPINDLE_LASER_ENABLE_PIN, SPINDLE_LASER_ENABLE_INVERT); // turn spindle on (active low)
|
||||
WRITE(SPINDLE_LASER_ENA_PIN, SPINDLE_LASER_ENABLE_INVERT); // turn spindle on (active low)
|
||||
analogWrite(SPINDLE_LASER_PWM_PIN, (SPINDLE_LASER_PWM_INVERT) ? 255 - ocr : ocr);
|
||||
}
|
||||
|
||||
|
@ -81,7 +81,7 @@ inline void set_spindle_laser_ocr(const uint8_t ocr) {
|
|||
|
||||
void update_spindle_laser_power() {
|
||||
if (spindle_laser_power == 0) {
|
||||
WRITE(SPINDLE_LASER_ENABLE_PIN, !SPINDLE_LASER_ENABLE_INVERT); // turn spindle off (active low)
|
||||
WRITE(SPINDLE_LASER_ENA_PIN, !SPINDLE_LASER_ENABLE_INVERT); // turn spindle off (active low)
|
||||
analogWrite(SPINDLE_LASER_PWM_PIN, SPINDLE_LASER_PWM_INVERT ? 255 : 0); // only write low byte
|
||||
delay_for_power_down();
|
||||
}
|
||||
|
@ -101,7 +101,7 @@ inline void set_spindle_laser_ocr(const uint8_t ocr) {
|
|||
#endif // SPINDLE_LASER_PWM
|
||||
|
||||
bool spindle_laser_enabled() {
|
||||
return !!spindle_laser_power; // READ(SPINDLE_LASER_ENABLE_PIN) == SPINDLE_LASER_ENABLE_INVERT;
|
||||
return !!spindle_laser_power; // READ(SPINDLE_LASER_ENA_PIN) == SPINDLE_LASER_ENABLE_INVERT;
|
||||
}
|
||||
|
||||
void set_spindle_laser_enabled(const bool enable) {
|
||||
|
@ -111,11 +111,11 @@ void set_spindle_laser_enabled(const bool enable) {
|
|||
update_spindle_laser_power();
|
||||
#else
|
||||
if (enable) {
|
||||
WRITE(SPINDLE_LASER_ENABLE_PIN, SPINDLE_LASER_ENABLE_INVERT);
|
||||
WRITE(SPINDLE_LASER_ENA_PIN, SPINDLE_LASER_ENABLE_INVERT);
|
||||
delay_for_power_up();
|
||||
}
|
||||
else {
|
||||
WRITE(SPINDLE_LASER_ENABLE_PIN, !SPINDLE_LASER_ENABLE_INVERT);
|
||||
WRITE(SPINDLE_LASER_ENA_PIN, !SPINDLE_LASER_ENABLE_INVERT);
|
||||
delay_for_power_down();
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -42,10 +42,10 @@
|
|||
*
|
||||
* M605 S0 : (FULL_CONTROL) The slicer has full control over both X-carriages and can achieve optimal travel
|
||||
* results as long as it supports dual X-carriages.
|
||||
*
|
||||
*
|
||||
* M605 S1 : (AUTO_PARK) The firmware automatically parks and unparks the X-carriages on tool-change so that
|
||||
* additional slicer support is not required.
|
||||
*
|
||||
*
|
||||
* M605 S2 X R : (DUPLICATION) The firmware moves the second X-carriage and extruder in synchronization with
|
||||
* the first X-carriage and extruder, to print 2 copies of the same object at the same time.
|
||||
* Set the constant X-offset and temperature differential with M605 S2 X[offs] R[deg] and
|
||||
|
|
|
@ -55,7 +55,7 @@ void GcodeSuite::T(const uint8_t tool_index) {
|
|||
|
||||
#if ENABLED(PRUSA_MMU2)
|
||||
if (parser.string_arg) {
|
||||
mmu2.toolChange(parser.string_arg); // Special commands T?/Tx/Tc
|
||||
mmu2.tool_change(parser.string_arg); // Special commands T?/Tx/Tc
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -84,7 +84,7 @@ void GcodeSuite::M701() {
|
|||
|
||||
// Load filament
|
||||
#if ENABLED(PRUSA_MMU2)
|
||||
mmu2.loadFilamentToNozzle(target_extruder);
|
||||
mmu2.load_filament_to_nozzle(target_extruder);
|
||||
#else
|
||||
constexpr float slow_load_length = FILAMENT_CHANGE_SLOW_LOAD_LENGTH;
|
||||
const float fast_load_length = ABS(parser.seen('L') ? parser.value_axis_units(E_AXIS)
|
||||
|
|
|
@ -29,17 +29,20 @@
|
|||
#include "../../../module/motion.h"
|
||||
#include "../../../lcd/ultralcd.h"
|
||||
|
||||
#define DEBUG_OUT ENABLED(DEBUG_POWER_LOSS_RECOVERY)
|
||||
#include "../../../core/debug_out.h"
|
||||
|
||||
void menu_job_recovery();
|
||||
|
||||
#if ENABLED(DEBUG_POWER_LOSS_RECOVERY)
|
||||
|
||||
inline void plr_error(PGM_P const prefix) {
|
||||
SERIAL_ECHO_START();
|
||||
inline void plr_error(PGM_P const prefix) {
|
||||
#if ENABLED(DEBUG_POWER_LOSS_RECOVERY)
|
||||
DEBUG_ECHO_START();
|
||||
serialprintPGM(prefix);
|
||||
SERIAL_ECHOLNPGM(" Power-Loss Recovery Data");
|
||||
}
|
||||
|
||||
#endif
|
||||
DEBUG_ECHOLNPGM(" Power-Loss Recovery Data");
|
||||
#else
|
||||
UNUSED(prefix);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* M1000: Resume from power-loss (undocumented)
|
||||
|
@ -54,11 +57,8 @@ void GcodeSuite::M1000() {
|
|||
else
|
||||
recovery.resume();
|
||||
}
|
||||
else {
|
||||
#if ENABLED(DEBUG_POWER_LOSS_RECOVERY)
|
||||
plr_error(recovery.info.valid_head ? PSTR("No") : PSTR("Invalid"));
|
||||
#endif
|
||||
}
|
||||
else
|
||||
plr_error(recovery.info.valid_head ? PSTR("No") : PSTR("Invalid"));
|
||||
|
||||
}
|
||||
|
||||
|
|
|
@ -41,7 +41,7 @@ void GcodeSuite::M403() {
|
|||
type = parser.intval('F', -1);
|
||||
|
||||
if (WITHIN(index, 0, 4) && WITHIN(type, 0, 2))
|
||||
mmu2.setFilamentType(index, type);
|
||||
mmu2.set_filament_type(index, type);
|
||||
else
|
||||
SERIAL_ECHO_MSG("M403 - bad arguments.");
|
||||
}
|
||||
|
|
|
@ -105,7 +105,7 @@ void GcodeSuite::get_destination_from_command() {
|
|||
|
||||
#if ENABLED(POWER_LOSS_RECOVERY)
|
||||
// Only update power loss recovery on moves with E
|
||||
if ((seen[E_AXIS] || seen[Z_AXIS]) && IS_SD_PRINTING()) recovery.save();
|
||||
if (seen[E_AXIS] && (seen[X_AXIS] || seen[Y_AXIS]) && IS_SD_PRINTING()) recovery.save();
|
||||
#endif
|
||||
|
||||
if (parser.linearval('F') > 0)
|
||||
|
@ -269,6 +269,16 @@ void GcodeSuite::process_parsed_command(
|
|||
break;
|
||||
#endif
|
||||
|
||||
#if ENABLED(CNC_COORDINATE_SYSTEMS)
|
||||
case 53: G53(); break;
|
||||
case 54: G54(); break;
|
||||
case 55: G55(); break;
|
||||
case 56: G56(); break;
|
||||
case 57: G57(); break;
|
||||
case 58: G58(); break;
|
||||
case 59: G59(); break;
|
||||
#endif
|
||||
|
||||
#if ENABLED(GCODE_MOTION_MODES)
|
||||
case 80: G80(); break; // G80: Reset the current motion mode
|
||||
#endif
|
||||
|
@ -348,10 +358,6 @@ void GcodeSuite::process_parsed_command(
|
|||
case 48: M48(); break; // M48: Z probe repeatability test
|
||||
#endif
|
||||
|
||||
#if ENABLED(G26_MESH_VALIDATION)
|
||||
case 49: M49(); break; // M49: Turn on or off G26 debug flag for verbose output
|
||||
#endif
|
||||
|
||||
#if ENABLED(LCD_SET_PROGRESS_MANUALLY)
|
||||
case 73: M73(); break; // M73: Set progress percentage (for display on LCD)
|
||||
#endif
|
||||
|
|
|
@ -495,10 +495,6 @@ private:
|
|||
static void M48();
|
||||
#endif
|
||||
|
||||
#if ENABLED(G26_MESH_VALIDATION)
|
||||
static void M49();
|
||||
#endif
|
||||
|
||||
#if ENABLED(LCD_SET_PROGRESS_MANUALLY)
|
||||
static void M73();
|
||||
#endif
|
||||
|
|
|
@ -59,7 +59,7 @@ bool GcodeSuite::select_coordinate_system(const int8_t _new) {
|
|||
*
|
||||
* Marlin also uses G53 on a line by itself to go back to native space.
|
||||
*/
|
||||
inline void GcodeSuite::G53() {
|
||||
void GcodeSuite::G53() {
|
||||
const int8_t _system = active_coordinate_system;
|
||||
active_coordinate_system = -1;
|
||||
if (parser.chain()) { // If this command has more following...
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
|
|
|
@ -25,6 +25,7 @@
|
|||
#if ENABLED(BABYSTEPPING)
|
||||
|
||||
#include "../gcode.h"
|
||||
#include "../../feature/babystep.h"
|
||||
#include "../../module/probe.h"
|
||||
#include "../../module/temperature.h"
|
||||
#include "../../module/planner.h"
|
||||
|
@ -49,7 +50,7 @@
|
|||
else {
|
||||
hotend_offset[Z_AXIS][active_extruder] -= offs;
|
||||
SERIAL_ECHO_START();
|
||||
SERIAL_ECHOLNPAIR(MSG_IDEX_Z_OFFSET ": ", hotend_offset[Z_AXIS][active_extruder]);
|
||||
SERIAL_ECHOLNPAIR(MSG_Z_OFFSET ": ", hotend_offset[Z_AXIS][active_extruder]);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
@ -64,7 +65,7 @@ void GcodeSuite::M290() {
|
|||
for (uint8_t a = X_AXIS; a <= Z_AXIS; a++)
|
||||
if (parser.seenval(axis_codes[a]) || (a == Z_AXIS && parser.seenval('S'))) {
|
||||
const float offs = constrain(parser.value_axis_units((AxisEnum)a), -2, 2);
|
||||
thermalManager.babystep_axis((AxisEnum)a, offs * planner.settings.axis_steps_per_mm[a]);
|
||||
babystep.add_mm((AxisEnum)a, offs);
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
if (a == Z_AXIS && (!parser.seen('P') || parser.value_bool())) mod_zprobe_zoffset(offs);
|
||||
#endif
|
||||
|
@ -72,7 +73,7 @@ void GcodeSuite::M290() {
|
|||
#else
|
||||
if (parser.seenval('Z') || parser.seenval('S')) {
|
||||
const float offs = constrain(parser.value_axis_units(Z_AXIS), -2, 2);
|
||||
thermalManager.babystep_axis(Z_AXIS, offs * planner.settings.axis_steps_per_mm[Z_AXIS]);
|
||||
babystep.add_mm(Z_AXIS, offs);
|
||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||
if (!parser.seen('P') || parser.value_bool()) mod_zprobe_zoffset(offs);
|
||||
#endif
|
||||
|
|
|
@ -37,10 +37,6 @@
|
|||
#include "../feature/leds/printer_event_leds.h"
|
||||
#endif
|
||||
|
||||
#if ENABLED(POWER_LOSS_RECOVERY)
|
||||
#include "../feature/power_loss_recovery.h"
|
||||
#endif
|
||||
|
||||
/**
|
||||
* GCode line number handling. Hosts may opt to include line numbers when
|
||||
* sending commands to Marlin, and lines will be checked for sequentiality.
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
|
|
|
@ -87,8 +87,8 @@
|
|||
#define U8GLIB_LM6059_AF
|
||||
#define SD_DETECT_INVERTED
|
||||
#elif ENABLED(AZSMZ_12864)
|
||||
#define LCD_CONTRAST_MIN 120
|
||||
#define LCD_CONTRAST_MAX 255
|
||||
#define LCD_CONTRAST_MIN 120
|
||||
#define LCD_CONTRAST_MAX 255
|
||||
#define DEFAULT_LCD_CONTRAST 190
|
||||
#define U8GLIB_ST7565_64128N
|
||||
#endif
|
||||
|
@ -139,6 +139,13 @@
|
|||
|
||||
#define MINIPANEL
|
||||
|
||||
#elif ENABLED(FYSETC_MINI_12864)
|
||||
|
||||
#define DOGLCD
|
||||
#define ULTIPANEL
|
||||
#define DEFAULT_LCD_CONTRAST 255
|
||||
#define LED_COLORS_REDUCE_GREEN
|
||||
|
||||
#endif
|
||||
|
||||
#if EITHER(MAKRPANEL, MINIPANEL)
|
||||
|
@ -313,36 +320,20 @@
|
|||
|
||||
#define HAS_ADC_BUTTONS ENABLED(ADC_KEYPAD)
|
||||
|
||||
#if HAS_GRAPHICAL_LCD
|
||||
/**
|
||||
* Default LCD contrast for Graphical LCD displays
|
||||
*/
|
||||
#define HAS_LCD_CONTRAST ( \
|
||||
ENABLED(MAKRPANEL) \
|
||||
|| ENABLED(CARTESIO_UI) \
|
||||
|| ENABLED(VIKI2) \
|
||||
|| ENABLED(AZSMZ_12864) \
|
||||
|| ENABLED(miniVIKI) \
|
||||
|| ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) \
|
||||
)
|
||||
#if HAS_LCD_CONTRAST
|
||||
#ifndef LCD_CONTRAST_MIN
|
||||
#define LCD_CONTRAST_MIN 0
|
||||
#endif
|
||||
#ifndef LCD_CONTRAST_MAX
|
||||
#define LCD_CONTRAST_MAX 63
|
||||
#endif
|
||||
#ifndef DEFAULT_LCD_CONTRAST
|
||||
#define DEFAULT_LCD_CONTRAST 32
|
||||
#endif
|
||||
/**
|
||||
* Default LCD contrast for Graphical LCD displays
|
||||
*/
|
||||
#define HAS_LCD_CONTRAST HAS_GRAPHICAL_LCD && defined(DEFAULT_LCD_CONTRAST)
|
||||
#if HAS_LCD_CONTRAST
|
||||
#ifndef LCD_CONTRAST_MIN
|
||||
#define LCD_CONTRAST_MIN 0
|
||||
#endif
|
||||
#ifndef LCD_CONTRAST_MAX
|
||||
#define LCD_CONTRAST_MAX 63
|
||||
#endif
|
||||
#ifndef DEFAULT_LCD_CONTRAST
|
||||
#define DEFAULT_LCD_CONTRAST 32
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// Boot screens
|
||||
#if !HAS_SPI_LCD
|
||||
#undef SHOW_BOOTSCREEN
|
||||
#elif !defined(BOOTSCREEN_TIMEOUT)
|
||||
#define BOOTSCREEN_TIMEOUT 2500
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -434,7 +425,7 @@
|
|||
*/
|
||||
#if ENABLED(DISTINCT_E_FACTORS) && E_STEPPERS > 1
|
||||
#define XYZE_N (XYZ + E_STEPPERS)
|
||||
#define E_AXIS_N(E) (E_AXIS + E)
|
||||
#define E_AXIS_N(E) AxisEnum(E_AXIS + E)
|
||||
#else
|
||||
#undef DISTINCT_E_FACTORS
|
||||
#define XYZE_N XYZE
|
||||
|
@ -517,9 +508,11 @@
|
|||
#define HAS_FILAMENT_SENSOR ENABLED(FILAMENT_RUNOUT_SENSOR)
|
||||
|
||||
#define Z_MULTI_STEPPER_DRIVERS EITHER(Z_DUAL_STEPPER_DRIVERS, Z_TRIPLE_STEPPER_DRIVERS)
|
||||
#define Z_MULTI_ENDSTOPS EITHER(Z_DUAL_ENDSTOPS, Z_TRIPLE_ENDSTOPS)
|
||||
#define HAS_EXTRA_ENDSTOPS (EITHER(X_DUAL_ENDSTOPS, Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS)
|
||||
#define HAS_GAME_MENU (1 < ENABLED(MARLIN_BRICKOUT) + ENABLED(MARLIN_INVADERS) + ENABLED(MARLIN_SNAKE))
|
||||
#define Z_MULTI_ENDSTOPS EITHER(Z_DUAL_ENDSTOPS, Z_TRIPLE_ENDSTOPS)
|
||||
#define HAS_EXTRA_ENDSTOPS (EITHER(X_DUAL_ENDSTOPS, Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS)
|
||||
|
||||
#define HAS_GAMES ANY(MARLIN_BRICKOUT, MARLIN_INVADERS, MARLIN_SNAKE, MARLIN_MAZE)
|
||||
#define HAS_GAME_MENU (1 < ENABLED(MARLIN_BRICKOUT) + ENABLED(MARLIN_INVADERS) + ENABLED(MARLIN_SNAKE) + ENABLED(MARLIN_MAZE))
|
||||
|
||||
#define IS_SCARA EITHER(MORGAN_SCARA, MAKERARM_SCARA)
|
||||
#define IS_KINEMATIC (ENABLED(DELTA) || IS_SCARA)
|
||||
|
@ -563,3 +556,7 @@
|
|||
#endif
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if ENABLED(SLIM_LCD_MENUS)
|
||||
#define BOOT_MARLIN_LOGO_SMALL
|
||||
#endif
|
||||
|
|
|
@ -873,9 +873,6 @@
|
|||
#define TMC_HAS_SPI (HAS_TMCX1X0 || HAS_DRIVER(TMC2660))
|
||||
#define HAS_STALLGUARD (HAS_TMCX1X0 || HAS_DRIVER(TMC2660))
|
||||
#define HAS_STEALTHCHOP (HAS_TMCX1X0 || HAS_DRIVER(TMC2208))
|
||||
#define AXIS_HAS_SPI(ST) (AXIS_DRIVER_TYPE(ST, TMC2130) || AXIS_DRIVER_TYPE(ST, TMC2160) || AXIS_DRIVER_TYPE(ST, TMC2660))
|
||||
#define AXIS_HAS_STALLGUARD(ST) (AXIS_DRIVER_TYPE(ST, TMC2130) || AXIS_DRIVER_TYPE(ST, TMC2160) || AXIS_DRIVER_TYPE(ST, TMC2660) || AXIS_DRIVER_TYPE(ST, TMC5130) || AXIS_DRIVER_TYPE(ST, TMC5160))
|
||||
#define AXIS_HAS_STEALTHCHOP(ST) (AXIS_DRIVER_TYPE(ST, TMC2130) || AXIS_DRIVER_TYPE(ST, TMC2160) || AXIS_DRIVER_TYPE(ST, TMC2208) || AXIS_DRIVER_TYPE(ST, TMC5130) || AXIS_DRIVER_TYPE(ST, TMC5160))
|
||||
|
||||
#define STEALTHCHOP_ENABLED ANY(STEALTHCHOP_XY, STEALTHCHOP_Z, STEALTHCHOP_E)
|
||||
#define USE_SENSORLESS EITHER(SENSORLESS_HOMING, SENSORLESS_PROBING)
|
||||
|
@ -921,7 +918,7 @@
|
|||
#define HAS_TEMP_HOTEND (HAS_TEMP_ADC_0 || ENABLED(HEATER_0_USES_MAX6675))
|
||||
#define HAS_TEMP_BED HAS_TEMP_ADC_BED
|
||||
#define HAS_TEMP_CHAMBER HAS_TEMP_ADC_CHAMBER
|
||||
#define HAS_HEATED_CHAMBER (HAS_TEMP_CHAMBER && PIN_EXISTS(CHAMBER_HEATER))
|
||||
#define HAS_HEATED_CHAMBER (HAS_TEMP_CHAMBER && PIN_EXISTS(HEATER_CHAMBER))
|
||||
|
||||
// Heaters
|
||||
#define HAS_HEATER_0 (PIN_EXISTS(HEATER_0))
|
||||
|
@ -1679,7 +1676,7 @@
|
|||
// Get LCD character width/height, which may be overridden by pins, configs, etc.
|
||||
#ifndef LCD_WIDTH
|
||||
#if HAS_GRAPHICAL_LCD
|
||||
#define LCD_WIDTH 22
|
||||
#define LCD_WIDTH 21
|
||||
#elif ENABLED(ULTIPANEL)
|
||||
#define LCD_WIDTH 20
|
||||
#elif HAS_SPI_LCD
|
||||
|
|
|
@ -341,6 +341,10 @@
|
|||
#error "MAX6675_SS is now MAX6675_SS_PIN. Please update your configuration and/or pins."
|
||||
#elif defined(MAX6675_SS2)
|
||||
#error "MAX6675_SS2 is now MAX6675_SS2_PIN. Please update your configuration and/or pins."
|
||||
#elif defined(SPINDLE_LASER_ENABLE_PIN)
|
||||
#error "SPINDLE_LASER_ENABLE_PIN is now SPINDLE_LASER_ENA_PIN. Please update your configuration and/or pins."
|
||||
#elif defined(CHAMBER_HEATER_PIN)
|
||||
#error "CHAMBER_HEATER_PIN is now HEATER_CHAMBER_PIN. Please update your configuration and/or pins."
|
||||
#elif defined(TMC_Z_CALIBRATION)
|
||||
#error "TMC_Z_CALIBRATION has been deprecated in favor of Z_STEPPER_AUTO_ALIGN. Please update your configuration."
|
||||
#elif defined(Z_MIN_PROBE_ENDSTOP)
|
||||
|
@ -551,6 +555,10 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
|
|||
#endif
|
||||
#endif
|
||||
|
||||
#if defined(EVENT_GCODE_SD_STOP) && DISABLED(NOZZLE_PARK_FEATURE)
|
||||
static_assert(NULL == strstr(EVENT_GCODE_SD_STOP, "G27"), "NOZZLE_PARK_FEATURE is required to use G27 in EVENT_GCODE_SD_STOP.");
|
||||
#endif
|
||||
|
||||
/**
|
||||
* I2C Position Encoders
|
||||
*/
|
||||
|
@ -1758,6 +1766,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
|
|||
+ ENABLED(G3D_PANEL) \
|
||||
+ (ENABLED(MINIPANEL) && DISABLED(MKS_MINI_12864)) \
|
||||
+ ENABLED(MKS_MINI_12864) \
|
||||
+ ENABLED(FYSETC_MINI_12864) \
|
||||
+ (ENABLED(REPRAPWORLD_KEYPAD) && DISABLED(CARTESIO_UI, ZONESTAR_LCD)) \
|
||||
+ ENABLED(RIGIDBOT_PANEL) \
|
||||
+ ENABLED(RA_CONTROL_PANEL) \
|
||||
|
|
|
@ -1025,7 +1025,7 @@ void MarlinUI::draw_status_screen() {
|
|||
}
|
||||
|
||||
void draw_edit_screen(PGM_P const pstr, const char* const value/*=NULL*/) {
|
||||
lcd_moveto(1, 1);
|
||||
lcd_moveto(0, 1);
|
||||
lcd_put_u8str_P(pstr);
|
||||
if (value != NULL) {
|
||||
lcd_put_wchar(':');
|
||||
|
@ -1037,6 +1037,16 @@ void MarlinUI::draw_status_screen() {
|
|||
}
|
||||
}
|
||||
|
||||
void draw_select_screen(PGM_P const yes, PGM_P const no, const bool yesno, PGM_P const pref, const char * const string, PGM_P const suff) {
|
||||
SETCURSOR(0, 0); lcd_put_u8str_P(pref);
|
||||
if (string) wrap_string(1, string);
|
||||
if (suff) lcd_put_u8str_P(suff);
|
||||
SETCURSOR(0, LCD_HEIGHT - 1);
|
||||
lcd_put_wchar(yesno ? ' ' : '['); lcd_put_u8str_P(no); lcd_put_wchar(yesno ? ' ' : ']');
|
||||
SETCURSOR_RJ(utf8_strlen_P(yes) + 2, LCD_HEIGHT - 1);
|
||||
lcd_put_wchar(yesno ? '[' : ' '); lcd_put_u8str_P(yes); lcd_put_wchar(yesno ? ']' : ' ');
|
||||
}
|
||||
|
||||
#if ENABLED(SDSUPPORT)
|
||||
|
||||
void draw_sd_menu_item(const bool sel, const uint8_t row, PGM_P const pstr, CardReader &theCard, const bool isDir) {
|
||||
|
|
|
@ -47,7 +47,7 @@
|
|||
uint8_t u8g_com_HAL_LPC1768_ssd_hw_i2c_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr);
|
||||
#define U8G_COM_SSD_I2C_HAL u8g_com_arduino_ssd_i2c_fn
|
||||
|
||||
#if defined(ARDUINO_ARCH_STM32F1)
|
||||
#ifdef ARDUINO_ARCH_STM32F1
|
||||
uint8_t u8g_com_stm32duino_fsmc_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr);
|
||||
#define U8G_COM_HAL_FSMC_FN u8g_com_stm32duino_fsmc_fn
|
||||
#else
|
||||
|
|
|
@ -29,107 +29,97 @@
|
|||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#if ENABLED(SHOW_BOOTSCREEN)
|
||||
#if ENABLED(SHOW_CUSTOM_BOOTSCREEN)
|
||||
|
||||
//#define START_BMPHIGH // Costs 399 bytes more flash
|
||||
|
||||
#if ENABLED(SHOW_CUSTOM_BOOTSCREEN)
|
||||
|
||||
#include "../../../_Bootscreen.h"
|
||||
|
||||
#ifndef CUSTOM_BOOTSCREEN_TIMEOUT
|
||||
#define CUSTOM_BOOTSCREEN_TIMEOUT 2500
|
||||
#endif
|
||||
#include "../../../_Bootscreen.h"
|
||||
|
||||
#ifndef CUSTOM_BOOTSCREEN_BMP_BYTEWIDTH
|
||||
#define CUSTOM_BOOTSCREEN_BMP_BYTEWIDTH ((CUSTOM_BOOTSCREEN_BMPWIDTH + 7) / 8)
|
||||
#endif
|
||||
|
||||
#if ENABLED(START_BMPHIGH)
|
||||
|
||||
#define START_BMPWIDTH 112
|
||||
|
||||
const unsigned char start_bmp[] PROGMEM = {
|
||||
B00000001,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,
|
||||
B00001111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,
|
||||
B00011110,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,B11111111,B11111111,
|
||||
B00111000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000011,B11111111,B11111111,
|
||||
B01110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000001,B11111111,B11111111,
|
||||
B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B11111111,B11111111,
|
||||
B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B01111111,B11111111,
|
||||
B11000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B01111000,B00000000,B00000000,B00111111,B11111111,
|
||||
B11000000,B00001111,B11000000,B11111100,B00000000,B00000000,B00000000,B00000000,B00000000,B01111000,B00011000,B00000000,B00011111,B11111111,
|
||||
B11000000,B00111111,B11100001,B11111111,B00000000,B00000000,B00000000,B00000000,B00000000,B01111000,B00111100,B00000000,B00001111,B11111111,
|
||||
B11000000,B01111111,B11110011,B11111111,B10000000,B00000000,B00000000,B00000000,B00000000,B01111000,B00111100,B00000000,B00000111,B11111111,
|
||||
B11000000,B11111111,B11111111,B11111111,B11000000,B00000000,B00000000,B00000000,B00000000,B01111000,B00111100,B00000000,B00000011,B11111111,
|
||||
B11000001,B11111000,B01111111,B10000111,B11100000,B00000000,B00000000,B00000000,B00000000,B01111000,B00000000,B00000000,B00000001,B11111111,
|
||||
B11000001,B11110000,B00111111,B00000011,B11100000,B00000000,B00000000,B00000000,B00000000,B01111000,B00000000,B00000000,B00000000,B11111111,
|
||||
B11000001,B11100000,B00011110,B00000001,B11100000,B00011111,B00000000,B00000011,B11100000,B01111000,B00111100,B00000011,B11110000,B01111111,
|
||||
B11000001,B11100000,B00011110,B00000001,B11100000,B01111111,B11000000,B00001111,B11111000,B01111000,B00111100,B00000111,B11111100,B00111111,
|
||||
B11000001,B11100000,B00011110,B00000001,B11100001,B11111111,B11100000,B00011111,B11111100,B01111000,B00111100,B00001111,B11111110,B00011111,
|
||||
B11000001,B11100000,B00011110,B00000001,B11100011,B11111111,B11110000,B00111111,B11111110,B01111000,B00111100,B00011111,B11111110,B00001111,
|
||||
B11000001,B11100000,B00011110,B00000001,B11100011,B11110011,B11111000,B00111111,B00111110,B01111000,B00111100,B00111111,B00111111,B00000111,
|
||||
B11000001,B11100000,B00011110,B00000001,B11100111,B11100000,B11111100,B01111100,B00011111,B01111000,B00111100,B00111110,B00011111,B00000111,
|
||||
B11000001,B11100000,B00011110,B00000001,B11100111,B11000000,B01111100,B01111100,B00001111,B01111000,B00111100,B00111100,B00001111,B00000011,
|
||||
B11000001,B11100000,B00011110,B00000001,B11100111,B10000000,B01111100,B01111000,B00001111,B01111000,B00111100,B00111100,B00001111,B00000011,
|
||||
B11000001,B11100000,B00011110,B00000001,B11100111,B10000000,B00111100,B01111000,B00000000,B01111000,B00111100,B00111100,B00001111,B00000011,
|
||||
B11000001,B11100000,B00011110,B00000001,B11100111,B10000000,B00111100,B01111000,B00000000,B01111000,B00111100,B00111100,B00001111,B00000011,
|
||||
B11000001,B11100000,B00011110,B00000001,B11100111,B10000000,B00111100,B01111000,B00000000,B01111000,B00111100,B00111100,B00001111,B00000011,
|
||||
B11000001,B11100000,B00011110,B00000001,B11100111,B11000000,B00111100,B01111000,B00000000,B01111000,B00111100,B00111100,B00001111,B00000011,
|
||||
B11000001,B11100000,B00011110,B00000001,B11100011,B11100000,B00111100,B01111000,B00000000,B01111100,B00111100,B00111100,B00001111,B00000011,
|
||||
B11000001,B11100000,B00011110,B00000001,B11100011,B11111111,B00111111,B11111000,B00000000,B01111111,B10111100,B00111100,B00001111,B00000011,
|
||||
B11000001,B11100000,B00011110,B00000001,B11100001,B11111111,B00111111,B11111000,B00000000,B00111111,B10111111,B11111100,B00001111,B00000011,
|
||||
B11000001,B11100000,B00011110,B00000001,B11100000,B11111111,B00111111,B11111000,B00000000,B00011111,B10111111,B11111100,B00001111,B00000011,
|
||||
B11000001,B11100000,B00011110,B00000001,B11100000,B01111111,B00111111,B11111000,B00000000,B00001111,B10111111,B11111100,B00001111,B00000011,
|
||||
B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,
|
||||
B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000110,
|
||||
B01110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00001110,
|
||||
B00111000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00011100,
|
||||
B00011110,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B01111000,
|
||||
B00001111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11110000,
|
||||
B00000001,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B10000000
|
||||
};
|
||||
|
||||
#else
|
||||
|
||||
#define START_BMPWIDTH 56
|
||||
|
||||
const unsigned char start_bmp[] PROGMEM = {
|
||||
B00011111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,
|
||||
B01100000,B00000000,B00000000,B00000000,B00000000,B00000001,B11111111,
|
||||
B01000000,B00000000,B00000000,B00000000,B00000000,B00000000,B11111111,
|
||||
B10000000,B00000000,B00000000,B00000000,B00000000,B00000000,B01111111,
|
||||
B10000011,B11001111,B00000000,B00000000,B00001100,B00110000,B00111111,
|
||||
B10000111,B11111111,B10000000,B00000000,B00001100,B00110000,B00011111,
|
||||
B10000110,B01111001,B10000000,B00000000,B00001100,B00000000,B00001111,
|
||||
B10001100,B00110000,B11000111,B10000011,B10001100,B00110000,B11100111,
|
||||
B10001100,B00110000,B11001111,B11000111,B11001100,B00110001,B11110011,
|
||||
B10001100,B00110000,B11011100,B11101100,B11101100,B00110011,B10111001,
|
||||
B10001100,B00110000,B11011000,B01101100,B01101100,B00110011,B00011001,
|
||||
B10001100,B00110000,B11010000,B01101100,B00001100,B00110011,B00011001,
|
||||
B10001100,B00110000,B11011000,B01101100,B00001100,B00110011,B00011001,
|
||||
B10001100,B00110000,B11011100,B01101100,B00001110,B00111011,B00011001,
|
||||
B10001100,B00110000,B11001111,B01111100,B00000111,B10011111,B00011001,
|
||||
B10001100,B00110000,B11000111,B01111100,B00000011,B10001111,B00011001,
|
||||
B01000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000010,
|
||||
B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000110,
|
||||
B00011111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111000
|
||||
};
|
||||
|
||||
#ifndef CUSTOM_BOOTSCREEN_BMPHEIGHT
|
||||
#define CUSTOM_BOOTSCREEN_BMPHEIGHT (sizeof(custom_start_bmp) / (CUSTOM_BOOTSCREEN_BMP_BYTEWIDTH))
|
||||
#endif
|
||||
|
||||
#ifndef START_BMP_BYTEWIDTH
|
||||
#define START_BMP_BYTEWIDTH ((START_BMPWIDTH + 7) / 8)
|
||||
#endif
|
||||
#ifndef START_BMPHEIGHT
|
||||
#define START_BMPHEIGHT (sizeof(start_bmp) / (START_BMP_BYTEWIDTH))
|
||||
#endif
|
||||
|
||||
static_assert(sizeof(start_bmp) == (START_BMP_BYTEWIDTH) * (START_BMPHEIGHT), "Bootscreen (start_bmp) dimensions don't match data.");
|
||||
|
||||
#endif
|
||||
|
||||
#ifndef CUSTOM_BOOTSCREEN_BMP_BYTEWIDTH
|
||||
#define CUSTOM_BOOTSCREEN_BMP_BYTEWIDTH ((CUSTOM_BOOTSCREEN_BMPWIDTH + 7) / 8)
|
||||
#if ENABLED(BOOT_MARLIN_LOGO_SMALL)
|
||||
|
||||
#define START_BMPWIDTH 56
|
||||
|
||||
const unsigned char start_bmp[] PROGMEM = {
|
||||
B00011111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,
|
||||
B01100000,B00000000,B00000000,B00000000,B00000000,B00000001,B11111111,
|
||||
B01000000,B00000000,B00000000,B00000000,B00000000,B00000000,B11111111,
|
||||
B10000000,B00000000,B00000000,B00000000,B00000000,B00000000,B01111111,
|
||||
B10000011,B11001111,B00000000,B00000000,B00001100,B00110000,B00111111,
|
||||
B10000111,B11111111,B10000000,B00000000,B00001100,B00110000,B00011111,
|
||||
B10000110,B01111001,B10000000,B00000000,B00001100,B00000000,B00001111,
|
||||
B10001100,B00110000,B11000111,B10000011,B10001100,B00110000,B11100111,
|
||||
B10001100,B00110000,B11001111,B11000111,B11001100,B00110001,B11110011,
|
||||
B10001100,B00110000,B11011100,B11101100,B11101100,B00110011,B10111001,
|
||||
B10001100,B00110000,B11011000,B01101100,B01101100,B00110011,B00011001,
|
||||
B10001100,B00110000,B11010000,B01101100,B00001100,B00110011,B00011001,
|
||||
B10001100,B00110000,B11011000,B01101100,B00001100,B00110011,B00011001,
|
||||
B10001100,B00110000,B11011100,B01101100,B00001110,B00111011,B00011001,
|
||||
B10001100,B00110000,B11001111,B01111100,B00000111,B10011111,B00011001,
|
||||
B10001100,B00110000,B11000111,B01111100,B00000011,B10001111,B00011001,
|
||||
B01000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000010,
|
||||
B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000110,
|
||||
B00011111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111000
|
||||
};
|
||||
|
||||
#else
|
||||
|
||||
#define START_BMPWIDTH 112
|
||||
|
||||
const unsigned char start_bmp[] PROGMEM = {
|
||||
B00000001,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,
|
||||
B00001111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,
|
||||
B00011110,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,B11111111,B11111111,
|
||||
B00111000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000011,B11111111,B11111111,
|
||||
B01110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000001,B11111111,B11111111,
|
||||
B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B11111111,B11111111,
|
||||
B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B01111111,B11111111,
|
||||
B11000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B01111000,B00000000,B00000000,B00111111,B11111111,
|
||||
B11000000,B00001111,B11000000,B11111100,B00000000,B00000000,B00000000,B00000000,B00000000,B01111000,B00011000,B00000000,B00011111,B11111111,
|
||||
B11000000,B00111111,B11100001,B11111111,B00000000,B00000000,B00000000,B00000000,B00000000,B01111000,B00111100,B00000000,B00001111,B11111111,
|
||||
B11000000,B01111111,B11110011,B11111111,B10000000,B00000000,B00000000,B00000000,B00000000,B01111000,B00111100,B00000000,B00000111,B11111111,
|
||||
B11000000,B11111111,B11111111,B11111111,B11000000,B00000000,B00000000,B00000000,B00000000,B01111000,B00111100,B00000000,B00000011,B11111111,
|
||||
B11000001,B11111000,B01111111,B10000111,B11100000,B00000000,B00000000,B00000000,B00000000,B01111000,B00000000,B00000000,B00000001,B11111111,
|
||||
B11000001,B11110000,B00111111,B00000011,B11100000,B00000000,B00000000,B00000000,B00000000,B01111000,B00000000,B00000000,B00000000,B11111111,
|
||||
B11000001,B11100000,B00011110,B00000001,B11100000,B00011111,B00000000,B00000011,B11100000,B01111000,B00111100,B00000011,B11110000,B01111111,
|
||||
B11000001,B11100000,B00011110,B00000001,B11100000,B01111111,B11000000,B00001111,B11111000,B01111000,B00111100,B00000111,B11111100,B00111111,
|
||||
B11000001,B11100000,B00011110,B00000001,B11100001,B11111111,B11100000,B00011111,B11111100,B01111000,B00111100,B00001111,B11111110,B00011111,
|
||||
B11000001,B11100000,B00011110,B00000001,B11100011,B11111111,B11110000,B00111111,B11111110,B01111000,B00111100,B00011111,B11111110,B00001111,
|
||||
B11000001,B11100000,B00011110,B00000001,B11100011,B11110011,B11111000,B00111111,B00111110,B01111000,B00111100,B00111111,B00111111,B00000111,
|
||||
B11000001,B11100000,B00011110,B00000001,B11100111,B11100000,B11111100,B01111100,B00011111,B01111000,B00111100,B00111110,B00011111,B00000111,
|
||||
B11000001,B11100000,B00011110,B00000001,B11100111,B11000000,B01111100,B01111100,B00001111,B01111000,B00111100,B00111100,B00001111,B00000011,
|
||||
B11000001,B11100000,B00011110,B00000001,B11100111,B10000000,B01111100,B01111000,B00001111,B01111000,B00111100,B00111100,B00001111,B00000011,
|
||||
B11000001,B11100000,B00011110,B00000001,B11100111,B10000000,B00111100,B01111000,B00000000,B01111000,B00111100,B00111100,B00001111,B00000011,
|
||||
B11000001,B11100000,B00011110,B00000001,B11100111,B10000000,B00111100,B01111000,B00000000,B01111000,B00111100,B00111100,B00001111,B00000011,
|
||||
B11000001,B11100000,B00011110,B00000001,B11100111,B10000000,B00111100,B01111000,B00000000,B01111000,B00111100,B00111100,B00001111,B00000011,
|
||||
B11000001,B11100000,B00011110,B00000001,B11100111,B11000000,B00111100,B01111000,B00000000,B01111000,B00111100,B00111100,B00001111,B00000011,
|
||||
B11000001,B11100000,B00011110,B00000001,B11100011,B11100000,B00111100,B01111000,B00000000,B01111100,B00111100,B00111100,B00001111,B00000011,
|
||||
B11000001,B11100000,B00011110,B00000001,B11100011,B11111111,B00111111,B11111000,B00000000,B01111111,B10111100,B00111100,B00001111,B00000011,
|
||||
B11000001,B11100000,B00011110,B00000001,B11100001,B11111111,B00111111,B11111000,B00000000,B00111111,B10111111,B11111100,B00001111,B00000011,
|
||||
B11000001,B11100000,B00011110,B00000001,B11100000,B11111111,B00111111,B11111000,B00000000,B00011111,B10111111,B11111100,B00001111,B00000011,
|
||||
B11000001,B11100000,B00011110,B00000001,B11100000,B01111111,B00111111,B11111000,B00000000,B00001111,B10111111,B11111100,B00001111,B00000011,
|
||||
B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,
|
||||
B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000110,
|
||||
B01110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00001110,
|
||||
B00111000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00011100,
|
||||
B00011110,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B01111000,
|
||||
B00001111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11110000,
|
||||
B00000001,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B10000000
|
||||
};
|
||||
|
||||
#endif
|
||||
#ifndef CUSTOM_BOOTSCREEN_BMPHEIGHT
|
||||
#define CUSTOM_BOOTSCREEN_BMPHEIGHT (sizeof(custom_start_bmp) / (CUSTOM_BOOTSCREEN_BMP_BYTEWIDTH))
|
||||
|
||||
#ifndef START_BMP_BYTEWIDTH
|
||||
#define START_BMP_BYTEWIDTH ((START_BMPWIDTH + 7) / 8)
|
||||
#endif
|
||||
#ifndef START_BMPHEIGHT
|
||||
#define START_BMPHEIGHT (sizeof(start_bmp) / (START_BMP_BYTEWIDTH))
|
||||
#endif
|
||||
|
||||
static_assert(sizeof(start_bmp) == (START_BMP_BYTEWIDTH) * (START_BMPHEIGHT), "Bootscreen (start_bmp) dimensions don't match data.");
|
||||
|
|
|
@ -97,7 +97,7 @@ static void fontgroup_drawwchar(font_group_t *group, const font_t *fnt_default,
|
|||
* @param utf8_msg : the UTF-8 string
|
||||
* @param cb_read_byte : how to read the utf8_msg, from RAM or ROM (call read_byte_ram or pgm_read_byte)
|
||||
* @param userdata : User's data
|
||||
* @param cb_draw_ram : the callback function of userdata to draw a !RAM! string (actural it is to draw a one byte string in RAM)
|
||||
* @param cb_draw_ram : the callback function of userdata to draw a !RAM! string (actually it is to draw a one byte string in RAM)
|
||||
*
|
||||
* @return N/A
|
||||
*
|
||||
|
|
|
@ -41,7 +41,10 @@
|
|||
|
||||
#include "ultralcd_DOGM.h"
|
||||
#include "u8g_fontutf8.h"
|
||||
#include "dogm_Bootscreen.h"
|
||||
|
||||
#if ENABLED(SHOW_BOOTSCREEN)
|
||||
#include "dogm_Bootscreen.h"
|
||||
#endif
|
||||
|
||||
#include "../lcdprint.h"
|
||||
#include "../fontutils.h"
|
||||
|
@ -138,6 +141,9 @@ void MarlinUI::set_font(const MarlinFont font_nr) {
|
|||
#else
|
||||
draw_custom_bootscreen(custom_start_bmp);
|
||||
#endif
|
||||
#ifndef CUSTOM_BOOTSCREEN_TIMEOUT
|
||||
#define CUSTOM_BOOTSCREEN_TIMEOUT 2500
|
||||
#endif
|
||||
safe_delay(CUSTOM_BOOTSCREEN_TIMEOUT);
|
||||
}
|
||||
|
||||
|
@ -148,31 +154,58 @@ void MarlinUI::set_font(const MarlinFont font_nr) {
|
|||
lcd_custom_bootscreen();
|
||||
#endif
|
||||
|
||||
constexpr uint8_t offy =
|
||||
#if ENABLED(START_BMPHIGH)
|
||||
(LCD_PIXEL_HEIGHT - (START_BMPHEIGHT)) / 2
|
||||
#else
|
||||
MENU_FONT_HEIGHT
|
||||
#endif
|
||||
;
|
||||
// Screen dimensions.
|
||||
//const uint8_t width = u8g.getWidth(), height = u8g.getHeight();
|
||||
constexpr uint8_t width = LCD_PIXEL_WIDTH, height = LCD_PIXEL_HEIGHT;
|
||||
|
||||
const uint8_t width = u8g.getWidth(), height = u8g.getHeight(),
|
||||
offx = (width - (START_BMPWIDTH)) / 2;
|
||||
// Determine text space needed
|
||||
#ifndef STRING_SPLASH_LINE2
|
||||
constexpr uint8_t text_total_height = MENU_FONT_HEIGHT,
|
||||
text_width_1 = (sizeof(STRING_SPLASH_LINE1) - 1) * (MENU_FONT_WIDTH),
|
||||
text_width_2 = 0;
|
||||
#else
|
||||
constexpr uint8_t text_total_height = (MENU_FONT_HEIGHT) * 2,
|
||||
text_width_1 = (sizeof(STRING_SPLASH_LINE1) - 1) * (MENU_FONT_WIDTH),
|
||||
text_width_2 = (sizeof(STRING_SPLASH_LINE2) - 1) * (MENU_FONT_WIDTH);
|
||||
#endif
|
||||
constexpr uint8_t text_max_width = MAX(text_width_1, text_width_2),
|
||||
rspace = width - (START_BMPWIDTH);
|
||||
|
||||
int8_t offx, offy, txt_base, txt_offx_1, txt_offx_2;
|
||||
|
||||
// Can the text fit to the right of the bitmap?
|
||||
if (text_max_width < rspace) {
|
||||
constexpr uint8_t inter = (width - text_max_width - (START_BMPWIDTH)) / 3; // Evenly distribute horizontal space
|
||||
offx = inter; // First the boot logo...
|
||||
offy = (height - (START_BMPHEIGHT)) / 2; // ...V-aligned in the full height
|
||||
txt_offx_1 = txt_offx_2 = inter + (START_BMPWIDTH) + inter; // Text right of the bitmap
|
||||
txt_base = (height + MENU_FONT_ASCENT + text_total_height - (MENU_FONT_HEIGHT)) / 2; // Text vertical center
|
||||
}
|
||||
else {
|
||||
constexpr uint8_t inter = (height - text_total_height - (START_BMPHEIGHT)) / 3; // Evenly distribute vertical space
|
||||
offy = inter; // V-align boot logo proportionally
|
||||
offx = rspace / 2; // Center the boot logo in the whole space
|
||||
txt_offx_1 = (width - text_width_1) / 2; // Text 1 centered
|
||||
txt_offx_2 = (width - text_width_2) / 2; // Text 2 centered
|
||||
txt_base = offy + START_BMPHEIGHT + offy + text_total_height - (MENU_FONT_DESCENT); // Even spacing looks best
|
||||
}
|
||||
NOLESS(offx, 0);
|
||||
NOLESS(offy, 0);
|
||||
|
||||
u8g.firstPage();
|
||||
do {
|
||||
u8g.drawBitmapP(offx, offy, (START_BMPWIDTH + 7) / 8, START_BMPHEIGHT, start_bmp);
|
||||
set_font(FONT_MENU);
|
||||
#ifndef STRING_SPLASH_LINE2
|
||||
const uint8_t txt1X = width - (sizeof(STRING_SPLASH_LINE1) - 1) * (MENU_FONT_WIDTH);
|
||||
u8g.drawStr(txt1X, (height + MENU_FONT_HEIGHT) / 2, STRING_SPLASH_LINE1);
|
||||
u8g.drawStr(txt_offx_1, txt_base, STRING_SPLASH_LINE1);
|
||||
#else
|
||||
const uint8_t txt1X = (width - (sizeof(STRING_SPLASH_LINE1) - 1) * (MENU_FONT_WIDTH)) / 2,
|
||||
txt2X = (width - (sizeof(STRING_SPLASH_LINE2) - 1) * (MENU_FONT_WIDTH)) / 2;
|
||||
u8g.drawStr(txt1X, height - (MENU_FONT_HEIGHT) * 3 / 2, STRING_SPLASH_LINE1);
|
||||
u8g.drawStr(txt2X, height - (MENU_FONT_HEIGHT) * 1 / 2, STRING_SPLASH_LINE2);
|
||||
u8g.drawStr(txt_offx_1, txt_base - (MENU_FONT_HEIGHT), STRING_SPLASH_LINE1);
|
||||
u8g.drawStr(txt_offx_2, txt_base, STRING_SPLASH_LINE2);
|
||||
#endif
|
||||
} while (u8g.nextPage());
|
||||
#ifndef BOOTSCREEN_TIMEOUT
|
||||
#define BOOTSCREEN_TIMEOUT 2500
|
||||
#endif
|
||||
safe_delay(BOOTSCREEN_TIMEOUT);
|
||||
}
|
||||
|
||||
|
@ -380,7 +413,7 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop
|
|||
if (value != NULL) {
|
||||
lcd_put_wchar(':');
|
||||
if (extra_row) {
|
||||
// Assume the value is numeric (with no descender)
|
||||
// Assume that value is numeric (with no descender)
|
||||
baseline += EDIT_FONT_ASCENT + 2;
|
||||
onpage = PAGE_CONTAINS(baseline - (EDIT_FONT_ASCENT - 1), baseline);
|
||||
}
|
||||
|
@ -392,6 +425,27 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop
|
|||
}
|
||||
}
|
||||
|
||||
inline void draw_boxed_string(const uint8_t x, const uint8_t y, PGM_P const pstr, const bool inv) {
|
||||
const uint8_t len = utf8_strlen_P(pstr), bw = len * (MENU_FONT_WIDTH),
|
||||
bx = x * (MENU_FONT_WIDTH), by = (y + 1) * (MENU_FONT_HEIGHT);
|
||||
if (inv) {
|
||||
u8g.setColorIndex(1);
|
||||
u8g.drawBox(bx - 1, by - (MENU_FONT_ASCENT) + 1, bw + 2, MENU_FONT_HEIGHT - 1);
|
||||
u8g.setColorIndex(0);
|
||||
}
|
||||
lcd_moveto(bx, by);
|
||||
lcd_put_u8str_P(pstr);
|
||||
if (inv) u8g.setColorIndex(1);
|
||||
}
|
||||
|
||||
void draw_select_screen(PGM_P const yes, PGM_P const no, const bool yesno, PGM_P const pref, const char * const string, PGM_P const suff) {
|
||||
SETCURSOR(0, 0); lcd_put_u8str_P(pref);
|
||||
if (string) wrap_string(1, string);
|
||||
if (suff) lcd_put_u8str_P(suff);
|
||||
draw_boxed_string(1, LCD_HEIGHT - 1, no, !yesno);
|
||||
draw_boxed_string(LCD_WIDTH - (utf8_strlen_P(yes) + 1), LCD_HEIGHT - 1, yes, yesno);
|
||||
}
|
||||
|
||||
#if ENABLED(SDSUPPORT)
|
||||
|
||||
void draw_sd_menu_item(const bool sel, const uint8_t row, PGM_P const pstr, CardReader &theCard, const bool isDir) {
|
||||
|
@ -500,22 +554,22 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop
|
|||
#if EITHER(BABYSTEP_ZPROBE_GFX_OVERLAY, MESH_EDIT_GFX_OVERLAY)
|
||||
|
||||
const unsigned char cw_bmp[] PROGMEM = {
|
||||
B00000011,B11111000,B00000000,
|
||||
B00001111,B11111110,B00000000,
|
||||
B00011110,B00001111,B00000000,
|
||||
B00111000,B00000111,B00000000,
|
||||
B00111000,B00000011,B10000000,
|
||||
B01110000,B00000011,B10000000,
|
||||
B01110000,B00001111,B11100000,
|
||||
B01110000,B00000111,B11000000,
|
||||
B01110000,B00000011,B10000000,
|
||||
B01110000,B00000001,B00000000,
|
||||
B01110000,B00000000,B00000000,
|
||||
B00111000,B00000000,B00000000,
|
||||
B00111000,B00000111,B00000000,
|
||||
B00011110,B00001111,B00000000,
|
||||
B00001111,B11111110,B00000000,
|
||||
B00000011,B11111000,B00000000
|
||||
B00000001,B11111100,B00000000,
|
||||
B00000111,B11111111,B00000000,
|
||||
B00001111,B00000111,B10000000,
|
||||
B00001110,B00000001,B11000000,
|
||||
B00000000,B00000001,B11000000,
|
||||
B00000000,B00000000,B11100000,
|
||||
B00001000,B00000000,B11100000,
|
||||
B00011100,B00000000,B11100000,
|
||||
B00111110,B00000000,B11100000,
|
||||
B01111111,B00000000,B11100000,
|
||||
B00011100,B00000000,B11100000,
|
||||
B00001110,B00000000,B11100000,
|
||||
B00001110,B00000001,B11000000,
|
||||
B00000111,B10000011,B11000000,
|
||||
B00000011,B11111111,B10000000,
|
||||
B00000000,B11111110,B00000000
|
||||
};
|
||||
|
||||
const unsigned char ccw_bmp[] PROGMEM = {
|
||||
|
@ -615,10 +669,10 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop
|
|||
|
||||
// Draw cw/ccw indicator and up/down arrows.
|
||||
if (PAGE_CONTAINS(47, 62)) {
|
||||
u8g.drawBitmapP(left + 0, 47, 3, 16, rot_down);
|
||||
u8g.drawBitmapP(right + 0, 47, 3, 16, rot_up);
|
||||
u8g.drawBitmapP(right + 20, 48 - dir, 2, 13, up_arrow_bmp);
|
||||
u8g.drawBitmapP(left + 20, 49 - dir, 2, 13, down_arrow_bmp);
|
||||
u8g.drawBitmapP(right + 0, 48 - dir, 2, 13, up_arrow_bmp);
|
||||
u8g.drawBitmapP(left + 0, 49 - dir, 2, 13, down_arrow_bmp);
|
||||
u8g.drawBitmapP(left + 13, 47, 3, 16, rot_down);
|
||||
u8g.drawBitmapP(right + 13, 47, 3, 16, rot_up);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -107,7 +107,7 @@
|
|||
// Generic support for SSD1309 OLED I2C LCDs
|
||||
#define U8G_CLASS U8GLIB_SSD1309_128X64
|
||||
#define U8G_PARAM (U8G_I2C_OPT_NONE | U8G_I2C_OPT_FAST)
|
||||
#elif ENABLED(MINIPANEL)
|
||||
#elif EITHER(MINIPANEL, FYSETC_MINI_12864)
|
||||
// The MINIPanel display
|
||||
//#define U8G_CLASS U8GLIB_MINI12864
|
||||
//#define U8G_PARAM DOGLCD_CS, DOGLCD_A0 // 8 stripes
|
||||
|
|
|
@ -97,6 +97,10 @@
|
|||
#include "../../feature/runout.h"
|
||||
#endif
|
||||
|
||||
#if ENABLED(BABYSTEPPING)
|
||||
#include "../../feature/babystep.h"
|
||||
#endif
|
||||
|
||||
inline float clamp(const float value, const float minimum, const float maximum) {
|
||||
return MAX(MIN(value, maximum), minimum);
|
||||
}
|
||||
|
@ -584,10 +588,10 @@ namespace ExtUI {
|
|||
bool babystepAxis_steps(const int16_t steps, const axis_t axis) {
|
||||
switch (axis) {
|
||||
#if ENABLED(BABYSTEP_XY)
|
||||
case X: thermalManager.babystep_axis(X_AXIS, steps); break;
|
||||
case Y: thermalManager.babystep_axis(Y_AXIS, steps); break;
|
||||
case X: babystep.add_steps(X_AXIS, steps); break;
|
||||
case Y: babystep.add_steps(Y_AXIS, steps); break;
|
||||
#endif
|
||||
case Z: thermalManager.babystep_axis(Z_AXIS, steps); break;
|
||||
case Z: babystep.add_steps(Z_AXIS, steps); break;
|
||||
default: return false;
|
||||
};
|
||||
return true;
|
||||
|
|
|
@ -105,7 +105,7 @@ namespace ExtUI {
|
|||
float getFeedrate_percent();
|
||||
uint8_t getProgress_percent();
|
||||
uint32_t getProgress_seconds_elapsed();
|
||||
|
||||
|
||||
#if HAS_LEVELING
|
||||
bool getLevelingActive();
|
||||
void setLevelingActive(const bool);
|
||||
|
|
|
@ -10,8 +10,8 @@
|
|||
#include "../inc/MarlinConfig.h"
|
||||
|
||||
#if ENABLED(ULTRA_LCD)
|
||||
#include "ultralcd.h"
|
||||
#include "../Marlin.h"
|
||||
#include "ultralcd.h"
|
||||
#include "../Marlin.h"
|
||||
#endif
|
||||
|
||||
#include "fontutils.h"
|
||||
|
|
|
@ -34,6 +34,8 @@
|
|||
#define THIS_LANGUAGES_SPECIAL_SYMBOLS _UxGT("ÄäÖöÜüß²³")
|
||||
|
||||
#define WELCOME_MSG MACHINE_NAME _UxGT(" bereit")
|
||||
#define MSG_YES _UxGT("JA")
|
||||
#define MSG_NO _UxGT("NEIN")
|
||||
#define MSG_BACK _UxGT("Zurück")
|
||||
#define MSG_SD_INSERTED _UxGT("SD-Karte erkannt")
|
||||
#define MSG_SD_REMOVED _UxGT("SD-Karte entfernt")
|
||||
|
@ -97,14 +99,14 @@
|
|||
#define MSG_UBL_TOOLS _UxGT("UBL-Werkzeuge")
|
||||
#define MSG_UBL_LEVEL_BED _UxGT("Unified Bed Leveling")
|
||||
#define MSG_IDEX_MENU _UxGT("IDEX-Modus")
|
||||
#define MSG_OFFSETS_MENU _UxGT("Werkzeugversätze")
|
||||
#define MSG_IDEX_MODE_AUTOPARK _UxGT("Autom. Parken")
|
||||
#define MSG_IDEX_MODE_DUPLICATE _UxGT("Duplizieren")
|
||||
#define MSG_IDEX_MODE_MIRRORED_COPY _UxGT("Spiegelkopie")
|
||||
#define MSG_IDEX_MODE_FULL_CTRL _UxGT("vollstä. Kontrolle")
|
||||
#define MSG_IDEX_X_OFFSET _UxGT("2. Düse X")
|
||||
#define MSG_IDEX_Y_OFFSET _UxGT("2. Düse Y")
|
||||
#define MSG_IDEX_Z_OFFSET _UxGT("2. Düse Z")
|
||||
#define MSG_IDEX_SAVE_OFFSETS _UxGT("Versätze speichern")
|
||||
#define MSG_X_OFFSET _UxGT("2. Düse X")
|
||||
#define MSG_Y_OFFSET _UxGT("2. Düse Y")
|
||||
#define MSG_Z_OFFSET _UxGT("2. Düse Z")
|
||||
#define MSG_UBL_MANUAL_MESH _UxGT("Netz manuell erst.")
|
||||
#define MSG_UBL_BC_INSERT _UxGT("Unterlegen & messen")
|
||||
#define MSG_UBL_BC_INSERT2 _UxGT("Messen")
|
||||
|
@ -197,6 +199,7 @@
|
|||
#define MSG_BED_Z _UxGT("Bett Z")
|
||||
#define MSG_NOZZLE _UxGT("Düse")
|
||||
#define MSG_BED _UxGT("Bett")
|
||||
#define MSG_CHAMBER _UxGT("Gehäuse")
|
||||
#define MSG_FAN_SPEED _UxGT("Lüfter")
|
||||
#define MSG_EXTRA_FAN_SPEED _UxGT("Geschw. Extralüfter")
|
||||
#define MSG_FLOW _UxGT("Flussrate")
|
||||
|
@ -269,6 +272,9 @@
|
|||
#define MSG_WATCH _UxGT("Info")
|
||||
#define MSG_PREPARE _UxGT("Vorbereitung")
|
||||
#define MSG_TUNE _UxGT("Justierung")
|
||||
#define MSG_START_PRINT _UxGT("Starte Druck")
|
||||
#define MSG_BUTTON_PRINT _UxGT("Drucke")
|
||||
#define MSG_BUTTON_CANCEL _UxGT("Abbrechen")
|
||||
#define MSG_PAUSE_PRINT _UxGT("SD-Druck pausieren")
|
||||
#define MSG_RESUME_PRINT _UxGT("SD-Druck fortsetzen")
|
||||
#define MSG_STOP_PRINT _UxGT("SD-Druck abbrechen")
|
||||
|
@ -310,6 +316,9 @@
|
|||
#define MSG_BLTOUCH_SELFTEST _UxGT("BLTouch Selbsttest")
|
||||
#define MSG_BLTOUCH_RESET _UxGT("BLTouch zurücks.")
|
||||
#define MSG_BLTOUCH_DEPLOY _UxGT("BLTouch ausfahren")
|
||||
#define MSG_BLTOUCH_SW_MODE _UxGT("BLTouch SW-Modus")
|
||||
#define MSG_BLTOUCH_5V_MODE _UxGT("BLTouch 5V-Modus")
|
||||
#define MSG_BLTOUCH_STOW _UxGT("BLTouch einfahren")
|
||||
#define MSG_BLTOUCH_STOW _UxGT("BLTouch einfahren")
|
||||
#define MSG_MANUAL_DEPLOY _UxGT("Z-Sonde ausfahren")
|
||||
#define MSG_MANUAL_STOW _UxGT("Z-Sonde einfahren")
|
||||
|
@ -319,6 +328,7 @@
|
|||
#define MSG_BABYSTEP_X _UxGT("Babystep X")
|
||||
#define MSG_BABYSTEP_Y _UxGT("Babystep Y")
|
||||
#define MSG_BABYSTEP_Z _UxGT("Babystep Z")
|
||||
#define MSG_BABYSTEP_TOTAL _UxGT("Total")
|
||||
#define MSG_ENDSTOP_ABORT _UxGT("Endstopp Abbr.")
|
||||
#define MSG_HEATING_FAILED_LCD _UxGT("HEIZEN ERFOLGLOS")
|
||||
#define MSG_HEATING_FAILED_LCD_BED _UxGT("Bett heizen fehlge.")
|
||||
|
@ -329,6 +339,8 @@
|
|||
#define MSG_ERR_MINTEMP LCD_STR_THERMOMETER _UxGT(" UNTERSCHRITTEN")
|
||||
#define MSG_ERR_MAXTEMP_BED _UxGT("BETT ") LCD_STR_THERMOMETER _UxGT(" ÜBERSCHRITTEN")
|
||||
#define MSG_ERR_MINTEMP_BED _UxGT("BETT ") LCD_STR_THERMOMETER _UxGT(" UNTERSCHRITTEN")
|
||||
#define MSG_ERR_MAXTEMP_CHAMBER _UxGT("Err: GEHÄUSE MAX TEM")
|
||||
#define MSG_ERR_MINTEMP_CHAMBER _UxGT("Err: GEHÄUSE MIN TEM")
|
||||
#define MSG_ERR_Z_HOMING MSG_HOME _UxGT(" ") MSG_X MSG_Y _UxGT(" ") MSG_FIRST
|
||||
#define MSG_HALTED _UxGT("DRUCKER STOPP")
|
||||
#define MSG_PLEASE_RESET _UxGT("Bitte neustarten")
|
||||
|
@ -447,6 +459,10 @@
|
|||
#define MSG_VTOOLS_RESET _UxGT("V-Tools ist resetet")
|
||||
#define MSG_START_Z _UxGT("Z Start")
|
||||
#define MSG_END_Z _UxGT("Z End")
|
||||
#define MSG_BRICKOUT _UxGT("Brickout")
|
||||
#define MSG_INVADERS _UxGT("Invaders")
|
||||
#define MSG_SNAKE _UxGT("Sn4k3")
|
||||
#define MSG_MAZE _UxGT("Maze")
|
||||
|
||||
//
|
||||
// Die Filament-Change-Bildschirme können bis zu 3 Zeilen auf einem 4-Zeilen-Display anzeigen
|
||||
|
@ -454,6 +470,7 @@
|
|||
#if LCD_HEIGHT >= 4
|
||||
#define MSG_ADVANCED_PAUSE_WAITING_1 _UxGT("Knopf drücken um")
|
||||
#define MSG_ADVANCED_PAUSE_WAITING_2 _UxGT("Druck fortzusetzen")
|
||||
#define MSG_PAUSE_PRINT_INIT_1 _UxGT("Parken...")
|
||||
#define MSG_FILAMENT_CHANGE_INIT_1 _UxGT("Warte auf den")
|
||||
#define MSG_FILAMENT_CHANGE_INIT_2 _UxGT("Start des")
|
||||
#define MSG_FILAMENT_CHANGE_INIT_3 _UxGT("Filamentwechsels...")
|
||||
|
@ -499,3 +516,8 @@
|
|||
#define MSG_TMC_HOMING_THRS _UxGT("Sensorloses Homing")
|
||||
#define MSG_TMC_STEPPING_MODE _UxGT("Schrittmodus")
|
||||
#define MSG_TMC_STEALTH_ENABLED _UxGT("StealthChop einsch.")
|
||||
#define MSG_SERVICE_RESET _UxGT("Reset")
|
||||
#define MSG_SERVICE_IN _UxGT(" im:")
|
||||
#define MSG_BACKLASH _UxGT("Spiel")
|
||||
#define MSG_BACKLASH_CORRECTION _UxGT("Korrektur")
|
||||
#define MSG_BACKLASH_SMOOTHING _UxGT("Glätten")
|
||||
|
|
|
@ -52,6 +52,12 @@
|
|||
#ifndef WELCOME_MSG
|
||||
#define WELCOME_MSG MACHINE_NAME _UxGT(" Ready.")
|
||||
#endif
|
||||
#ifndef MSG_YES
|
||||
#define MSG_YES _UxGT("YES")
|
||||
#endif
|
||||
#ifndef MSG_NO
|
||||
#define MSG_NO _UxGT("NO")
|
||||
#endif
|
||||
#ifndef MSG_BACK
|
||||
#define MSG_BACK _UxGT("Back")
|
||||
#endif
|
||||
|
@ -241,6 +247,9 @@
|
|||
#ifndef MSG_IDEX_MENU
|
||||
#define MSG_IDEX_MENU _UxGT("IDEX Mode")
|
||||
#endif
|
||||
#ifndef MSG_OFFSETS_MENU
|
||||
#define MSG_OFFSETS_MENU _UxGT("Tool Offsets")
|
||||
#endif
|
||||
#ifndef MSG_IDEX_MODE_AUTOPARK
|
||||
#define MSG_IDEX_MODE_AUTOPARK _UxGT("Auto-Park")
|
||||
#endif
|
||||
|
@ -253,17 +262,14 @@
|
|||
#ifndef MSG_IDEX_MODE_FULL_CTRL
|
||||
#define MSG_IDEX_MODE_FULL_CTRL _UxGT("Full control")
|
||||
#endif
|
||||
#ifndef MSG_IDEX_X_OFFSET
|
||||
#define MSG_IDEX_X_OFFSET _UxGT("2nd nozzle X")
|
||||
#ifndef MSG_X_OFFSET
|
||||
#define MSG_X_OFFSET _UxGT("2nd nozzle X")
|
||||
#endif
|
||||
#ifndef MSG_IDEX_Y_OFFSET
|
||||
#define MSG_IDEX_Y_OFFSET _UxGT("2nd nozzle Y")
|
||||
#ifndef MSG_Y_OFFSET
|
||||
#define MSG_Y_OFFSET _UxGT("2nd nozzle Y")
|
||||
#endif
|
||||
#ifndef MSG_IDEX_Z_OFFSET
|
||||
#define MSG_IDEX_Z_OFFSET _UxGT("2nd nozzle Z")
|
||||
#endif
|
||||
#ifndef MSG_IDEX_SAVE_OFFSETS
|
||||
#define MSG_IDEX_SAVE_OFFSETS _UxGT("Save Offsets")
|
||||
#ifndef MSG_Z_OFFSET
|
||||
#define MSG_Z_OFFSET _UxGT("2nd nozzle Z")
|
||||
#endif
|
||||
#ifndef MSG_UBL_MANUAL_MESH
|
||||
#define MSG_UBL_MANUAL_MESH _UxGT("Manually Build Mesh")
|
||||
|
@ -744,6 +750,15 @@
|
|||
#ifndef MSG_TUNE
|
||||
#define MSG_TUNE _UxGT("Tune")
|
||||
#endif
|
||||
#ifndef MSG_START_PRINT
|
||||
#define MSG_START_PRINT _UxGT("Start print")
|
||||
#endif
|
||||
#ifndef MSG_BUTTON_PRINT
|
||||
#define MSG_BUTTON_PRINT _UxGT("Print")
|
||||
#endif
|
||||
#ifndef MSG_BUTTON_CANCEL
|
||||
#define MSG_BUTTON_CANCEL _UxGT("Cancel")
|
||||
#endif
|
||||
#ifndef MSG_PAUSE_PRINT
|
||||
#define MSG_PAUSE_PRINT _UxGT("Pause print")
|
||||
#endif
|
||||
|
@ -903,6 +918,9 @@
|
|||
#ifndef MSG_BABYSTEP_Z
|
||||
#define MSG_BABYSTEP_Z _UxGT("Babystep Z")
|
||||
#endif
|
||||
#ifndef MSG_BABYSTEP_TOTAL
|
||||
#define MSG_BABYSTEP_TOTAL _UxGT("Total")
|
||||
#endif
|
||||
#ifndef MSG_ENDSTOP_ABORT
|
||||
#define MSG_ENDSTOP_ABORT _UxGT("Endstop abort")
|
||||
#endif
|
||||
|
|
|
@ -32,6 +32,8 @@
|
|||
#define DISPLAY_CHARSET_ISO10646_1
|
||||
|
||||
#define WELCOME_MSG MACHINE_NAME _UxGT(" pronto.")
|
||||
#define MSG_YES _UxGT("SI")
|
||||
#define MSG_NO _UxGT("NO")
|
||||
#define MSG_BACK _UxGT("Indietro")
|
||||
#define MSG_SD_INSERTED _UxGT("SD Card inserita")
|
||||
#define MSG_SD_REMOVED _UxGT("SD Card rimossa")
|
||||
|
@ -95,14 +97,14 @@
|
|||
#define MSG_UBL_TOOLS _UxGT("Strumenti UBL")
|
||||
#define MSG_UBL_LEVEL_BED _UxGT("Unified Bed Leveling")
|
||||
#define MSG_IDEX_MENU _UxGT("Modo IDEX")
|
||||
#define MSG_OFFSETS_MENU _UxGT("Strumenti Offsets")
|
||||
#define MSG_IDEX_MODE_AUTOPARK _UxGT("Auto-Park")
|
||||
#define MSG_IDEX_MODE_DUPLICATE _UxGT("Duplicazione")
|
||||
#define MSG_IDEX_MODE_MIRRORED_COPY _UxGT("Copia speculare")
|
||||
#define MSG_IDEX_MODE_FULL_CTRL _UxGT("Pieno controllo")
|
||||
#define MSG_IDEX_X_OFFSET _UxGT("2° ugello X")
|
||||
#define MSG_IDEX_Y_OFFSET _UxGT("2° ugello Y")
|
||||
#define MSG_IDEX_Z_OFFSET _UxGT("2° ugello Z")
|
||||
#define MSG_IDEX_SAVE_OFFSETS _UxGT("Memorizza Offsets")
|
||||
#define MSG_X_OFFSET _UxGT("2° ugello X")
|
||||
#define MSG_Y_OFFSET _UxGT("2° ugello Y")
|
||||
#define MSG_Z_OFFSET _UxGT("2° ugello Z")
|
||||
#define MSG_UBL_MANUAL_MESH _UxGT("Mesh Manuale")
|
||||
#define MSG_UBL_BC_INSERT _UxGT("Metti spes. e misura")
|
||||
#define MSG_UBL_BC_INSERT2 _UxGT("Misura")
|
||||
|
@ -268,6 +270,9 @@
|
|||
#define MSG_WATCH _UxGT("Schermata info")
|
||||
#define MSG_PREPARE _UxGT("Prepara")
|
||||
#define MSG_TUNE _UxGT("Regola")
|
||||
#define MSG_START_PRINT _UxGT("Avvia stampa")
|
||||
#define MSG_BUTTON_PRINT _UxGT("Stampa")
|
||||
#define MSG_BUTTON_CANCEL _UxGT("Annulla")
|
||||
#define MSG_PAUSE_PRINT _UxGT("Pausa stampa")
|
||||
#define MSG_RESUME_PRINT _UxGT("Riprendi stampa")
|
||||
#define MSG_STOP_PRINT _UxGT("Arresta stampa")
|
||||
|
@ -321,6 +326,7 @@
|
|||
#define MSG_BABYSTEP_X _UxGT("Babystep X")
|
||||
#define MSG_BABYSTEP_Y _UxGT("Babystep Y")
|
||||
#define MSG_BABYSTEP_Z _UxGT("Babystep Z")
|
||||
#define MSG_BABYSTEP_TOTAL _UxGT("Totali")
|
||||
#define MSG_ENDSTOP_ABORT _UxGT("Finecorsa annullati")
|
||||
#define MSG_HEATING_FAILED_LCD _UxGT("Riscald. Fallito")
|
||||
#define MSG_HEATING_FAILED_LCD_BED _UxGT("Risc. piatto fallito")
|
||||
|
@ -449,6 +455,10 @@
|
|||
#define MSG_VTOOLS_RESET _UxGT("V-tools ripristin.")
|
||||
#define MSG_START_Z _UxGT("Z inizio")
|
||||
#define MSG_END_Z _UxGT("Z fine")
|
||||
#define MSG_BRICKOUT _UxGT("Brickout")
|
||||
#define MSG_INVADERS _UxGT("Invaders")
|
||||
#define MSG_SNAKE _UxGT("Sn4k3")
|
||||
#define MSG_MAZE _UxGT("Maze")
|
||||
|
||||
//
|
||||
// Le schermate di Cambio Filamento possono visualizzare fino a 3 linee su un display a 4 righe
|
||||
|
@ -505,3 +515,7 @@
|
|||
|
||||
#define MSG_SERVICE_RESET _UxGT("Resetta")
|
||||
#define MSG_SERVICE_IN _UxGT(" tra:")
|
||||
|
||||
#define MSG_BACKLASH _UxGT("Gioco")
|
||||
#define MSG_BACKLASH_CORRECTION _UxGT("Correzione")
|
||||
#define MSG_BACKLASH_SMOOTHING _UxGT("Smoothing")
|
||||
|
|
Some files were not shown because too many files have changed in this diff Show more
Loading…
Reference in a new issue