mirror of
https://github.com/MarlinFirmware/Marlin.git
synced 2026-01-08 07:37:43 -07:00
Merge branch 'bugfix-2.1.x' of https://github.com/MarlinFirmware/Marlin into bugfix-2.1.x-March2
This commit is contained in:
commit
15eca149bc
80 changed files with 1837 additions and 463 deletions
|
|
@ -767,6 +767,7 @@
|
|||
|
||||
#define MPC_TUNING_POS { X_CENTER, Y_CENTER, 1.0f } // (mm) M306 Autotuning position, ideally bed center at first layer height.
|
||||
#define MPC_TUNING_END_Z 10.0f // (mm) M306 Autotuning final Z position.
|
||||
//#define EVENT_GCODE_AFTER_MPC_TUNE "M84" // G-code to execute after MPC tune finished and Z raised.
|
||||
#endif
|
||||
|
||||
//===========================================================================
|
||||
|
|
|
|||
|
|
@ -2997,7 +2997,7 @@
|
|||
/**
|
||||
* Trinamic Smart Drivers
|
||||
*
|
||||
* To use TMC2130, TMC2160, TMC2660, TMC5130, TMC5160 stepper drivers in SPI mode:
|
||||
* To use TMC2130, TMC2160, TMC2240, TMC2660, TMC5130, TMC5160 stepper drivers in SPI mode:
|
||||
* - Connect your SPI pins to the Hardware SPI interface on the board.
|
||||
* Some boards have simple jumper connections! See your board's documentation.
|
||||
* - Define the required Stepper CS pins in your `pins_MYBOARD.h` file.
|
||||
|
|
@ -3258,7 +3258,7 @@
|
|||
// @section tmc/spi
|
||||
|
||||
/**
|
||||
* Override default SPI pins for TMC2130, TMC2160, TMC2660, TMC5130 and TMC5160 drivers here.
|
||||
* Override default SPI pins for TMC2130, TMC2160, TMC2240, TMC2660, TMC5130 and TMC5160 drivers here.
|
||||
* The default pins can be found in your board's pins file.
|
||||
*/
|
||||
//#define X_CS_PIN -1
|
||||
|
|
@ -3285,7 +3285,7 @@
|
|||
//#define E7_CS_PIN -1
|
||||
|
||||
/**
|
||||
* Software option for SPI driven drivers (TMC2130, TMC2160, TMC2660, TMC5130 and TMC5160).
|
||||
* Software option for SPI driven drivers (TMC2130, TMC2160, TMC2240, TMC2660, TMC5130 and TMC5160).
|
||||
* The default SW SPI pins are defined the respective pins files,
|
||||
* but you can override or define them here.
|
||||
*/
|
||||
|
|
@ -3470,7 +3470,7 @@
|
|||
*
|
||||
* It is recommended to set HOMING_BUMP_MM to { 0, 0, 0 }.
|
||||
*
|
||||
* SPI_ENDSTOPS *** TMC2130/TMC5160 Only ***
|
||||
* SPI_ENDSTOPS *** TMC2130, TMC2240, and TMC5160 Only ***
|
||||
* Poll the driver through SPI to determine load when homing.
|
||||
* Removes the need for a wire from DIAG1 to an endstop pin.
|
||||
*
|
||||
|
|
@ -3498,7 +3498,7 @@
|
|||
//#define U_STALL_SENSITIVITY 8
|
||||
//#define V_STALL_SENSITIVITY 8
|
||||
//#define W_STALL_SENSITIVITY 8
|
||||
//#define SPI_ENDSTOPS // TMC2130/TMC5160 only
|
||||
//#define SPI_ENDSTOPS // TMC2130, TMC2240, and TMC5160
|
||||
//#define IMPROVE_HOMING_RELIABILITY
|
||||
#endif
|
||||
|
||||
|
|
|
|||
|
|
@ -41,7 +41,7 @@
|
|||
* here we define this default string as the date where the latest release
|
||||
* version was tagged.
|
||||
*/
|
||||
//#define STRING_DISTRIBUTION_DATE "2025-05-25"
|
||||
//#define STRING_DISTRIBUTION_DATE "2025-05-29"
|
||||
|
||||
/**
|
||||
* The protocol for communication to the host. Protocol indicates communication
|
||||
|
|
|
|||
|
|
@ -42,7 +42,7 @@ void eeprom_init() {
|
|||
|
||||
void eeprom_write_byte(uint8_t *pos, uint8_t value) {
|
||||
const unsigned eeprom_address = (unsigned)pos;
|
||||
return BL24CXX::writeOneByte(eeprom_address, value);
|
||||
BL24CXX::writeOneByte(eeprom_address, value);
|
||||
}
|
||||
|
||||
uint8_t eeprom_read_byte(uint8_t *pos) {
|
||||
|
|
|
|||
|
|
@ -26,4 +26,4 @@
|
|||
#define TS_TYPICAL_SLOPE 4.5
|
||||
|
||||
// TODO: Implement voltage scaling (calibrated Vrefint) and ADC resolution scaling (when applicable)
|
||||
#define TEMP_SOC_SENSOR(RAW) ((TS_TYPICAL_V - (RAW) / float(OVERSAMPLENR) / float(HAL_ADC_RANGE) * (float(ADC_VREF_MV) / 1000)) / ((TS_TYPICAL_SLOPE) / 1000) + TS_TYPICAL_TEMP)
|
||||
#define TEMP_SOC_SENSOR(RAW) ((TS_TYPICAL_V - (RAW) / float(OVERSAMPLENR) / float(HAL_ADC_RANGE) * (float(ADC_VREF_MV) / 1000.0f)) / ((TS_TYPICAL_SLOPE) / 1000.0f) + TS_TYPICAL_TEMP)
|
||||
|
|
|
|||
|
|
@ -39,7 +39,7 @@ void eeprom_init() {
|
|||
|
||||
void eeprom_write_byte(uint8_t *pos, unsigned char value) {
|
||||
const unsigned eeprom_address = (unsigned)pos;
|
||||
return BL24CXX::writeOneByte(eeprom_address, value);
|
||||
BL24CXX::writeOneByte(eeprom_address, value);
|
||||
}
|
||||
|
||||
uint8_t eeprom_read_byte(uint8_t *pos) {
|
||||
|
|
|
|||
|
|
@ -44,7 +44,7 @@ void eeprom_init() { BL24CXX::init(); }
|
|||
|
||||
void eeprom_write_byte(uint8_t *pos, uint8_t value) {
|
||||
const unsigned eeprom_address = (unsigned)pos;
|
||||
return BL24CXX::writeOneByte(eeprom_address, value);
|
||||
BL24CXX::writeOneByte(eeprom_address, value);
|
||||
}
|
||||
|
||||
uint8_t eeprom_read_byte(uint8_t *pos) {
|
||||
|
|
|
|||
|
|
@ -341,6 +341,6 @@
|
|||
|
||||
#elif defined(TS_TYPICAL_V) && defined(TS_TYPICAL_SLOPE) && defined(TS_TYPICAL_TEMP)
|
||||
|
||||
#define TEMP_SOC_SENSOR(RAW) ((TS_TYPICAL_V - (RAW) / float(OVERSAMPLENR) / float(HAL_ADC_RANGE) * (float(ADC_VREF_MV) / 1000.0f)) / ((TS_TYPICAL_SLOPE) / 1000) + TS_TYPICAL_TEMP)
|
||||
#define TEMP_SOC_SENSOR(RAW) ((TS_TYPICAL_V - (RAW) / float(OVERSAMPLENR) / float(HAL_ADC_RANGE) * (float(ADC_VREF_MV) / 1000.0f)) / ((TS_TYPICAL_SLOPE) / 1000.0f) + TS_TYPICAL_TEMP)
|
||||
|
||||
#endif
|
||||
|
|
|
|||
|
|
@ -42,7 +42,7 @@ void eeprom_init() { BL24CXX::init(); }
|
|||
|
||||
void eeprom_write_byte(uint8_t *pos, uint8_t value) {
|
||||
const unsigned eeprom_address = (unsigned)pos;
|
||||
return BL24CXX::writeOneByte(eeprom_address, value);
|
||||
BL24CXX::writeOneByte(eeprom_address, value);
|
||||
}
|
||||
|
||||
uint8_t eeprom_read_byte(uint8_t *pos) {
|
||||
|
|
|
|||
|
|
@ -113,9 +113,12 @@
|
|||
#define HAS_TRINAMIC_STANDALONE 1
|
||||
#endif
|
||||
|
||||
#if HAS_DRIVER(TMC2130) || HAS_DRIVER(TMC2160) || HAS_DRIVER(TMC5130) || HAS_DRIVER(TMC5160) || HAS_DRIVER(TMC2240)
|
||||
#if HAS_DRIVER(TMC2130) || HAS_DRIVER(TMC2160) || HAS_DRIVER(TMC5130) || HAS_DRIVER(TMC5160)
|
||||
#define HAS_TMCX1X0 1
|
||||
#endif
|
||||
#if HAS_TMCX1X0 || HAS_DRIVER(TMC2240)
|
||||
#define HAS_TMCX1X0_OR_2240 1
|
||||
#endif
|
||||
#if HAS_DRIVER(TMC2208) || HAS_DRIVER(TMC2209)
|
||||
#define HAS_TMC220x 1
|
||||
#endif
|
||||
|
|
@ -207,6 +210,7 @@
|
|||
#define THRS_TMC2160 255
|
||||
#define THRS_TMC2208 255
|
||||
#define THRS_TMC2209 255
|
||||
#define THRS_TMC2240 255
|
||||
#define THRS_TMC2660 65535
|
||||
#define THRS_TMC5130 65535
|
||||
#define THRS_TMC5160 65535
|
||||
|
|
|
|||
|
|
@ -114,10 +114,6 @@ void serial_ternary(FSTR_P const pre, const bool onoff, FSTR_P const on, FSTR_P
|
|||
if (post) SERIAL_ECHO(post);
|
||||
}
|
||||
|
||||
void serialprint_onoff(const bool onoff) { SERIAL_ECHO(onoff ? F(STR_ON) : F(STR_OFF)); }
|
||||
void serialprintln_onoff(const bool onoff) { serialprint_onoff(onoff); SERIAL_EOL(); }
|
||||
void serialprint_truefalse(const bool tf) { SERIAL_ECHO(tf ? F("true") : F("false")); }
|
||||
|
||||
void print_bin(uint16_t val) {
|
||||
for (uint8_t i = 16; i--;) {
|
||||
SERIAL_CHAR('0' + TEST(val, i));
|
||||
|
|
|
|||
|
|
@ -233,9 +233,9 @@ void serial_ternary(FSTR_P const pre, const bool onoff, FSTR_P const on, FSTR_P
|
|||
// Print up to 255 spaces
|
||||
void SERIAL_ECHO_SP(uint8_t count);
|
||||
|
||||
void serialprint_onoff(const bool onoff);
|
||||
void serialprintln_onoff(const bool onoff);
|
||||
void serialprint_truefalse(const bool tf);
|
||||
inline FSTR_P const ON_OFF(const bool onoff) { return onoff ? F("ON") : F("OFF"); }
|
||||
inline FSTR_P const TRUE_FALSE(const bool tf) { return tf ? F("true") : F("false"); }
|
||||
|
||||
void serial_offset(const_float_t v, const uint8_t sp=0); // For v==0 draw space (sp==1) or plus (sp==2)
|
||||
|
||||
void print_bin(const uint16_t val);
|
||||
|
|
|
|||
|
|
@ -168,7 +168,7 @@ template <class L, class R> struct IF<true, L, R> { typedef L type; };
|
|||
|
||||
// Helpers
|
||||
#define _RECIP(N) ((N) ? 1.0f / static_cast<float>(N) : 0.0f)
|
||||
#define _ABS(N) ((N) < 0 ? -(N) : (N))
|
||||
#define _ABS(N) ((N) < decltype(N)(0) ? -(N) : (N))
|
||||
#define _LS(N) T(uint32_t(N) << p)
|
||||
#define _RS(N) T(uint32_t(N) >> p)
|
||||
#define _LSE(N) N = T(uint32_t(N) << p)
|
||||
|
|
@ -640,8 +640,8 @@ struct XYZval {
|
|||
FI void reset() { NUM_AXIS_CODE(x = 0, y = 0, z = 0, i = 0, j = 0, k = 0, u = 0, v = 0, w = 0); }
|
||||
|
||||
// Setters taking struct types and arrays
|
||||
FI void set(const XYval<T> pxy) { XY_CODE(x = pxy.x, y = pxy.y); }
|
||||
FI void set(const XYval<T> pxy, const T pz) { XYZ_CODE(x = pxy.x, y = pxy.y, z = pz); }
|
||||
FI void set(const XYval<T> &pxy) { XY_CODE(x = pxy.x, y = pxy.y); }
|
||||
FI void set(const XYval<T> &pxy, const T pz) { XYZ_CODE(x = pxy.x, y = pxy.y, z = pz); }
|
||||
FI void set(const T (&arr)[NUM_AXES]) { NUM_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5], u = arr[6], v = arr[7], w = arr[8]); }
|
||||
#if LOGICAL_AXES > NUM_AXES
|
||||
FI void set(const T (&arr)[LOGICAL_AXES]) { NUM_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5], u = arr[6], v = arr[7], w = arr[8]); }
|
||||
|
|
@ -743,7 +743,7 @@ struct XYZval {
|
|||
|
||||
// Absolute difference between two objects
|
||||
FI constexpr XYZval<T> diff(const XYZEval<T> &rs) const { return NUM_AXIS_ARRAY(T(_ABS(x - rs.x)), T(_ABS(y - rs.y)), T(_ABS(z - rs.z)), T(_ABS(i - rs.i)), T(_ABS(j - rs.j)), T(_ABS(k - rs.k)), T(_ABS(u - rs.u)), T(_ABS(v - rs.v)), T(_ABS(w - rs.w)) ); }
|
||||
FI constexpr XYZval<T> diff(const XYZval<T> &rs) const { return NUM_AXIS_ARRAY(T(_ABS(x - rs.x)), T(_ABS(y - rs.y)), T(_ABS(z - rs.z)), T(_ABS(i - rs.i)), T(_ABS(j - rs.j)), T(_ABS(k - rs.k)), T(_ABS(u - rs.u)), T(_ABS(v - rs.v)), T(_ABS(w - rs.w)) ); }
|
||||
FI constexpr XYZval<T> diff(const XYZval<T> &rs) const { return NUM_AXIS_ARRAY(T(_ABS(x - rs.x)), T(_ABS(y - rs.y)), T(_ABS(z - rs.z)), T(_ABS(i - rs.i)), T(_ABS(j - rs.j)), T(_ABS(k - rs.k)), T(_ABS(u - rs.u)), T(_ABS(v - rs.v)), T(_ABS(w - rs.w)) ); }
|
||||
FI constexpr XYZval<T> diff(const XYval<T> &rs) const { return NUM_AXIS_ARRAY(T(_ABS(x - rs.x)), T(_ABS(y - rs.y)), z, i, j, k, u, v, w ); }
|
||||
|
||||
// Modifier operators
|
||||
|
|
@ -787,17 +787,17 @@ struct XYZEval {
|
|||
FI void reset() { LOGICAL_AXIS_GANG(e =, x =, y =, z =, i =, j =, k =, u =, v =, w =) 0; }
|
||||
|
||||
// Setters taking struct types and arrays
|
||||
FI void set(const XYval<T> pxy) { XY_CODE(x = pxy.x, y = pxy.y); }
|
||||
FI void set(const XYval<T> pxy, const T pz) { XYZ_CODE(x = pxy.x, y = pxy.y, z = pz); }
|
||||
FI void set(const XYZval<T> pxyz) { set(NUM_AXIS_ELEM_LC(pxyz)); }
|
||||
FI void set(const T (&arr)[NUM_AXES]) { NUM_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5], u = arr[6], v = arr[7], w = arr[8]); }
|
||||
FI void set(const XYval<T> &pxy) { XY_CODE(x = pxy.x, y = pxy.y); }
|
||||
FI void set(const XYval<T> &pxy, const T pz) { XYZ_CODE(x = pxy.x, y = pxy.y, z = pz); }
|
||||
FI void set(const XYZval<T> &pxyz) { set(NUM_AXIS_ELEM_LC(pxyz)); }
|
||||
FI void set(const T (&arr)[NUM_AXES]) { NUM_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5], u = arr[6], v = arr[7], w = arr[8]); }
|
||||
#if LOGICAL_AXES > NUM_AXES
|
||||
FI void set(const T (&arr)[LOGICAL_AXES]) { LOGICAL_AXIS_CODE(e = arr[LOGICAL_AXES-1], x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5], u = arr[6], v = arr[7], w = arr[8]); }
|
||||
FI void set(const XYval<T> pxy, const T pz, const T pe) { set(pxy, pz); e = pe; }
|
||||
FI void set(const XYZval<T> pxyz, const T pe) { set(pxyz); e = pe; }
|
||||
FI void set(LOGICAL_AXIS_ARGS_LC(const T)) { LOGICAL_AXIS_CODE(_e = e, a = x, b = y, c = z, _i = i, _j = j, _k = k, _u = u, _v = v, _w = w); }
|
||||
FI void set(const T (&arr)[LOGICAL_AXES]) { LOGICAL_AXIS_CODE(e = arr[LOGICAL_AXES-1], x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5], u = arr[6], v = arr[7], w = arr[8]); }
|
||||
FI void set(const XYval<T> &pxy, const T pz, const T pe) { set(pxy, pz); e = pe; }
|
||||
FI void set(const XYZval<T> &pxyz, const T pe) { set(pxyz); e = pe; }
|
||||
FI void set(LOGICAL_AXIS_ARGS_LC(const T)) { LOGICAL_AXIS_CODE(_e = e, a = x, b = y, c = z, _i = i, _j = j, _k = k, _u = u, _v = v, _w = w); }
|
||||
#if DISTINCT_AXES > LOGICAL_AXES
|
||||
FI void set(const T (&arr)[DISTINCT_AXES]) { LOGICAL_AXIS_CODE(e = arr[LOGICAL_AXES-1], x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5], u = arr[6], v = arr[7], w = arr[8]); }
|
||||
FI void set(const T (&arr)[DISTINCT_AXES]) { LOGICAL_AXIS_CODE(e = arr[LOGICAL_AXES-1], x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5], u = arr[6], v = arr[7], w = arr[8]); }
|
||||
#endif
|
||||
#endif
|
||||
|
||||
|
|
@ -933,9 +933,9 @@ struct XYZarray {
|
|||
};
|
||||
FI void reset() { ZERO(data); }
|
||||
|
||||
FI void set(const int n, const XYval<T> p) { NUM_AXIS_CODE(x[n]=p.x, y[n]=p.y,,,,,,,); }
|
||||
FI void set(const int n, const XYZval<T> p) { NUM_AXIS_CODE(x[n]=p.x, y[n]=p.y, z[n]=p.z, i[n]=p.i, j[n]=p.j, k[n]=p.k, u[n]=p.u, v[n]=p.v, w[n]=p.w ); }
|
||||
FI void set(const int n, const XYZEval<T> p) { NUM_AXIS_CODE(x[n]=p.x, y[n]=p.y, z[n]=p.z, i[n]=p.i, j[n]=p.j, k[n]=p.k, u[n]=p.u, v[n]=p.v, w[n]=p.w ); }
|
||||
FI void set(const int n, const XYval<T> &p) { NUM_AXIS_CODE(x[n]=p.x, y[n]=p.y,,,,,,,); }
|
||||
FI void set(const int n, const XYZval<T> &p) { NUM_AXIS_CODE(x[n]=p.x, y[n]=p.y, z[n]=p.z, i[n]=p.i, j[n]=p.j, k[n]=p.k, u[n]=p.u, v[n]=p.v, w[n]=p.w ); }
|
||||
FI void set(const int n, const XYZEval<T> &p) { NUM_AXIS_CODE(x[n]=p.x, y[n]=p.y, z[n]=p.z, i[n]=p.i, j[n]=p.j, k[n]=p.k, u[n]=p.u, v[n]=p.v, w[n]=p.w ); }
|
||||
|
||||
// Setter for all individual args
|
||||
FI void set(const int n OPTARGS_NUM(const T)) { NUM_AXIS_CODE(a[n] = x, b[n] = y, c[n] = z, _i[n] = i, _j[n] = j, _k[n] = k, _u[n] = u, _v[n] = v, _w[n] = w); }
|
||||
|
|
@ -981,9 +981,9 @@ struct XYZEarray {
|
|||
};
|
||||
FI void reset() { ZERO(data); }
|
||||
|
||||
FI void set(const int n, const XYval<T> p) { NUM_AXIS_CODE(x[n]=p.x, y[n]=p.y,,,,,,,); }
|
||||
FI void set(const int n, const XYZval<T> p) { NUM_AXIS_CODE(x[n]=p.x, y[n]=p.y, z[n]=p.z, i[n]=p.i, j[n]=p.j, k[n]=p.k, u[n]=p.u, v[n]=p.v, w[n]=p.w ); }
|
||||
FI void set(const int n, const XYZEval<T> p) { LOGICAL_AXIS_CODE(e[n]=p.e, x[n]=p.x, y[n]=p.y, z[n]=p.z, i[n]=p.i, j[n]=p.j, k[n]=p.k, u[n]=p.u, v[n]=p.v, w[n]=p.w ); }
|
||||
FI void set(const int n, const XYval<T> &p) { NUM_AXIS_CODE(x[n]=p.x, y[n]=p.y,,,,,,,); }
|
||||
FI void set(const int n, const XYZval<T> &p) { NUM_AXIS_CODE(x[n]=p.x, y[n]=p.y, z[n]=p.z, i[n]=p.i, j[n]=p.j, k[n]=p.k, u[n]=p.u, v[n]=p.v, w[n]=p.w ); }
|
||||
FI void set(const int n, const XYZEval<T> &p) { LOGICAL_AXIS_CODE(e[n]=p.e, x[n]=p.x, y[n]=p.y, z[n]=p.z, i[n]=p.i, j[n]=p.j, k[n]=p.k, u[n]=p.u, v[n]=p.v, w[n]=p.w ); }
|
||||
|
||||
// Setter for all individual args
|
||||
FI void set(const int n OPTARGS_NUM(const T)) { NUM_AXIS_CODE(a[n] = x, b[n] = y, c[n] = z, _i[n] = i, _j[n] = j, _k[n] = k, _u[n] = u, _v[n] = v, _w[n] = w); }
|
||||
|
|
|
|||
|
|
@ -169,9 +169,11 @@ void MeatPack::handle_command(const MeatPack_Command c) {
|
|||
void MeatPack::report_state() {
|
||||
// NOTE: if any configuration vars are added below, the outgoing sync text for host plugin
|
||||
// should not contain the "PV' substring, as this is used to indicate protocol version
|
||||
SERIAL_ECHOPGM("[MP] " MeatPack_ProtocolVersion " ");
|
||||
serialprint_onoff(TEST(state, MPConfig_Bit_Active));
|
||||
SERIAL_ECHO(TEST(state, MPConfig_Bit_NoSpaces) ? F(" NSP\n") : F(" ESP\n"));
|
||||
SERIAL_ECHO(
|
||||
F("[MP] " MeatPack_ProtocolVersion " "),
|
||||
ON_OFF(TEST(state, MPConfig_Bit_Active)),
|
||||
TEST(state, MPConfig_Bit_NoSpaces) ? F(" NSP\n") : F(" ESP\n")
|
||||
);
|
||||
}
|
||||
|
||||
/**
|
||||
|
|
|
|||
|
|
@ -72,7 +72,7 @@
|
|||
#endif
|
||||
;
|
||||
#if ENABLED(TMC_DEBUG)
|
||||
#if HAS_TMCX1X0 || HAS_TMC220x
|
||||
#if HAS_TMCX1X0_OR_2240 || HAS_TMC220x
|
||||
uint8_t cs_actual;
|
||||
#endif
|
||||
#if HAS_STALLGUARD
|
||||
|
|
@ -298,7 +298,7 @@
|
|||
st.printLabel();
|
||||
SString<60> report(':', pwm_scale);
|
||||
#if ENABLED(TMC_DEBUG)
|
||||
#if HAS_TMCX1X0 || HAS_TMC220x
|
||||
#if HAS_TMCX1X0_OR_2240 || HAS_TMC220x
|
||||
report.append('/', data.cs_actual);
|
||||
#endif
|
||||
#if HAS_STALLGUARD
|
||||
|
|
@ -575,14 +575,35 @@
|
|||
|
||||
template<class TMC>
|
||||
static void print_vsense(TMC &st) { SERIAL_ECHO(st.vsense() ? F("1=.18") : F("0=.325")); }
|
||||
#if HAS_DRIVER(TMC2160)
|
||||
template<char AXIS_LETTER, char DRIVER_ID, AxisEnum AXIS_ID>
|
||||
void print_vsense(TMCMarlin<TMC2160Stepper, AXIS_LETTER, DRIVER_ID, AXIS_ID> &) { }
|
||||
#endif
|
||||
#if HAS_DRIVER(TMC5160)
|
||||
template<char AXIS_LETTER, char DRIVER_ID, AxisEnum AXIS_ID>
|
||||
void print_vsense(TMCMarlin<TMC5160Stepper, AXIS_LETTER, DRIVER_ID, AXIS_ID> &) { }
|
||||
#endif
|
||||
#if HAS_DRIVER(TMC2240)
|
||||
template<char AXIS_LETTER, char DRIVER_ID, AxisEnum AXIS_ID>
|
||||
void print_vsense(TMCMarlin<TMC2240Stepper, AXIS_LETTER, DRIVER_ID, AXIS_ID> &) { }
|
||||
#endif
|
||||
|
||||
template <typename TMC>
|
||||
void print_cs_actual(TMC &st) { SERIAL_ECHO(st.cs_actual(), F("/31")); }
|
||||
#if HAS_DRIVER(TMC2240)
|
||||
template<char AXIS_LETTER, char DRIVER_ID, AxisEnum AXIS_ID>
|
||||
void print_cs_actual(TMCMarlin<TMC2240Stepper, AXIS_LETTER, DRIVER_ID, AXIS_ID> &) { }
|
||||
#endif
|
||||
|
||||
static void print_true_or_false(const bool tf) { SERIAL_ECHO(TRUE_FALSE(tf)); }
|
||||
|
||||
#if HAS_DRIVER(TMC2130) || HAS_DRIVER(TMC5130)
|
||||
static void _tmc_status(TMC2130Stepper &st, const TMC_debug_enum i) {
|
||||
switch (i) {
|
||||
case TMC_PWM_SCALE: SERIAL_ECHO(st.PWM_SCALE()); break;
|
||||
case TMC_SGT: SERIAL_ECHO(st.sgt()); break;
|
||||
case TMC_STEALTHCHOP: serialprint_truefalse(st.en_pwm_mode()); break;
|
||||
case TMC_INTERPOLATE: serialprint_truefalse(st.intpol()); break;
|
||||
case TMC_STEALTHCHOP: print_true_or_false(st.en_pwm_mode()); break;
|
||||
case TMC_INTERPOLATE: print_true_or_false(st.intpol()); break;
|
||||
default: break;
|
||||
}
|
||||
}
|
||||
|
|
@ -600,17 +621,11 @@
|
|||
#endif
|
||||
|
||||
#if HAS_DRIVER(TMC2160) || HAS_DRIVER(TMC5160)
|
||||
template<char AXIS_LETTER, char DRIVER_ID, AxisEnum AXIS_ID>
|
||||
void print_vsense(TMCMarlin<TMC2160Stepper, AXIS_LETTER, DRIVER_ID, AXIS_ID> &) { }
|
||||
|
||||
template<char AXIS_LETTER, char DRIVER_ID, AxisEnum AXIS_ID>
|
||||
void print_vsense(TMCMarlin<TMC5160Stepper, AXIS_LETTER, DRIVER_ID, AXIS_ID> &) { }
|
||||
|
||||
static void _tmc_status(TMC2160Stepper &st, const TMC_debug_enum i) {
|
||||
switch (i) {
|
||||
case TMC_PWM_SCALE: SERIAL_ECHO(st.PWM_SCALE()); break;
|
||||
case TMC_SGT: SERIAL_ECHO(st.sgt()); break;
|
||||
case TMC_STEALTHCHOP: serialprint_truefalse(st.en_pwm_mode()); break;
|
||||
case TMC_STEALTHCHOP: print_true_or_false(st.en_pwm_mode()); break;
|
||||
case TMC_GLOBAL_SCALER:
|
||||
{
|
||||
const uint16_t value = st.GLOBAL_SCALER();
|
||||
|
|
@ -618,7 +633,7 @@
|
|||
SERIAL_ECHOPGM("/256");
|
||||
}
|
||||
break;
|
||||
case TMC_INTERPOLATE: serialprint_truefalse(st.intpol()); break;
|
||||
case TMC_INTERPOLATE: print_true_or_false(st.intpol()); break;
|
||||
default: break;
|
||||
}
|
||||
}
|
||||
|
|
@ -632,8 +647,8 @@
|
|||
case TMC_PWM_SCALE_AUTO: SERIAL_ECHO(st.pwm_scale_auto()); break;
|
||||
case TMC_PWM_OFS_AUTO: SERIAL_ECHO(st.pwm_ofs_auto()); break;
|
||||
case TMC_PWM_GRAD_AUTO: SERIAL_ECHO(st.pwm_grad_auto()); break;
|
||||
case TMC_STEALTHCHOP: serialprint_truefalse(st.stealth()); break;
|
||||
case TMC_INTERPOLATE: serialprint_truefalse(st.intpol()); break;
|
||||
case TMC_STEALTHCHOP: print_true_or_false(st.stealth()); break;
|
||||
case TMC_INTERPOLATE: print_true_or_false(st.intpol()); break;
|
||||
default: break;
|
||||
}
|
||||
}
|
||||
|
|
@ -676,22 +691,52 @@
|
|||
|
||||
#endif // HAS_TMC220x
|
||||
|
||||
#if HAS_DRIVER(TMC2240)
|
||||
static void _tmc_parse_drv_status(TMC2240Stepper, const TMC_drv_status_enum) { }
|
||||
static void _tmc_status(TMC2240Stepper &st, const TMC_debug_enum i) {
|
||||
switch (i) {
|
||||
case TMC_PWM_SCALE_SUM: SERIAL_ECHO(st.pwm_scale_sum()); break;
|
||||
case TMC_PWM_SCALE_AUTO: SERIAL_ECHO(st.pwm_scale_auto()); break;
|
||||
case TMC_PWM_OFS_AUTO: SERIAL_ECHO(st.pwm_ofs_auto()); break;
|
||||
case TMC_PWM_GRAD_AUTO: SERIAL_ECHO(st.pwm_grad_auto()); break;
|
||||
case TMC_STEALTHCHOP: print_true_or_false(st.stealth()); break;
|
||||
case TMC_INTERPOLATE: print_true_or_false(st.intpol()); break;
|
||||
default: break;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#if HAS_DRIVER(TMC2660)
|
||||
static void _tmc_parse_drv_status(TMC2660Stepper, const TMC_drv_status_enum) { }
|
||||
static void _tmc_status(TMC2660Stepper &st, const TMC_debug_enum i) {
|
||||
switch (i) {
|
||||
case TMC_INTERPOLATE: serialprint_truefalse(st.intpol()); break;
|
||||
case TMC_INTERPOLATE: print_true_or_false(st.intpol()); break;
|
||||
default: break;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
template <typename TMC>
|
||||
void print_tstep(TMC &st) {
|
||||
const uint32_t tstep_value = st.TSTEP();
|
||||
if (tstep_value != 0xFFFFF)
|
||||
SERIAL_ECHO(tstep_value);
|
||||
else
|
||||
SERIAL_ECHOPGM("max");
|
||||
}
|
||||
void print_tstep(TMC2660Stepper &st) { }
|
||||
|
||||
template <typename TMC>
|
||||
void print_blank_time(TMC &st) { SERIAL_ECHO(st.blank_time()); }
|
||||
template<char AXIS_LETTER, char DRIVER_ID, AxisEnum AXIS_ID>
|
||||
void print_blank_time(TMCMarlin<TMC2240Stepper, AXIS_LETTER, DRIVER_ID, AXIS_ID> &) { }
|
||||
|
||||
template <typename TMC>
|
||||
static void tmc_status(TMC &st, const TMC_debug_enum i) {
|
||||
SERIAL_CHAR('\t');
|
||||
switch (i) {
|
||||
case TMC_CODES: st.printLabel(); break;
|
||||
case TMC_ENABLED: serialprint_truefalse(st.isEnabled()); break;
|
||||
case TMC_ENABLED: print_true_or_false(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_ECHO(p_float_t(st.rms_current() * 1.41, 0)); break;
|
||||
|
|
@ -703,16 +748,10 @@
|
|||
SERIAL_ECHO(st.ihold());
|
||||
SERIAL_ECHOPGM("/31");
|
||||
break;
|
||||
case TMC_CS_ACTUAL:
|
||||
SERIAL_ECHO(st.cs_actual());
|
||||
SERIAL_ECHOPGM("/31");
|
||||
break;
|
||||
case TMC_CS_ACTUAL: print_cs_actual(st); break;
|
||||
case TMC_VSENSE: print_vsense(st); break;
|
||||
case TMC_MICROSTEPS: SERIAL_ECHO(st.microsteps()); break;
|
||||
case TMC_TSTEP: {
|
||||
const uint32_t tstep_value = st.TSTEP();
|
||||
if (tstep_value != 0xFFFFF) SERIAL_ECHO(tstep_value); else SERIAL_ECHOPGM("max");
|
||||
} break;
|
||||
case TMC_TSTEP: print_tstep(st); break;
|
||||
#if ENABLED(HYBRID_THRESHOLD)
|
||||
case TMC_TPWMTHRS: SERIAL_ECHO(uint32_t(st.TPWMTHRS())); break;
|
||||
case TMC_TPWMTHRS_MMS: {
|
||||
|
|
@ -720,12 +759,12 @@
|
|||
if (tpwmthrs_val) SERIAL_ECHO(tpwmthrs_val); else SERIAL_CHAR('-');
|
||||
} break;
|
||||
#endif
|
||||
case TMC_OTPW: serialprint_truefalse(st.otpw()); break;
|
||||
case TMC_OTPW: print_true_or_false(st.otpw()); break;
|
||||
#if ENABLED(MONITOR_DRIVER_STATUS)
|
||||
case TMC_OTPW_TRIGGERED: serialprint_truefalse(st.getOTPW()); break;
|
||||
case TMC_OTPW_TRIGGERED: print_true_or_false(st.getOTPW()); break;
|
||||
#endif
|
||||
case TMC_TOFF: SERIAL_ECHO(st.toff()); break;
|
||||
case TMC_TBL: SERIAL_ECHO(st.blank_time()); break;
|
||||
case TMC_TBL: print_blank_time(st); break;
|
||||
case TMC_HEND: SERIAL_ECHO(st.hysteresis_end()); break;
|
||||
case TMC_HSTRT: SERIAL_ECHO(st.hysteresis_start()); break;
|
||||
case TMC_MSCNT: SERIAL_ECHO(st.get_microstep_counter()); break;
|
||||
|
|
@ -739,7 +778,7 @@
|
|||
SERIAL_CHAR('\t');
|
||||
switch (i) {
|
||||
case TMC_CODES: st.printLabel(); break;
|
||||
case TMC_ENABLED: serialprint_truefalse(st.isEnabled()); break;
|
||||
case TMC_ENABLED: print_true_or_false(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_ECHO(p_float_t(st.rms_current() * 1.41, 0)); break;
|
||||
|
|
@ -749,14 +788,14 @@
|
|||
break;
|
||||
case TMC_VSENSE: SERIAL_ECHO(st.vsense() ? F("1=.165") : F("0=.310")); break;
|
||||
case TMC_MICROSTEPS: SERIAL_ECHO(st.microsteps()); break;
|
||||
//case TMC_OTPW: serialprint_truefalse(st.otpw()); break;
|
||||
//case TMC_OTPW_TRIGGERED: serialprint_truefalse(st.getOTPW()); break;
|
||||
//case TMC_OTPW: print_true_or_false(st.otpw()); break;
|
||||
//case TMC_OTPW_TRIGGERED: print_true_or_false(st.getOTPW()); break;
|
||||
case TMC_SGT: SERIAL_ECHO(st.sgt()); break;
|
||||
case TMC_TOFF: SERIAL_ECHO(st.toff()); break;
|
||||
case TMC_TBL: SERIAL_ECHO(st.blank_time()); break;
|
||||
case TMC_TBL: print_blank_time(st); break;
|
||||
case TMC_HEND: SERIAL_ECHO(st.hysteresis_end()); break;
|
||||
case TMC_HSTRT: SERIAL_ECHO(st.hysteresis_start()); break;
|
||||
default: break;
|
||||
default: _tmc_status(st, i); break;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
|
@ -916,10 +955,10 @@
|
|||
TMC_REPORT("Stallguard thrs", TMC_SGT);
|
||||
TMC_REPORT("uStep count", TMC_MSCNT);
|
||||
DRV_REPORT("DRVSTATUS", TMC_DRV_CODES);
|
||||
#if HAS_TMCX1X0 || HAS_TMC220x
|
||||
#if HAS_TMCX1X0_OR_2240 || HAS_TMC220x
|
||||
DRV_REPORT("sg_result", TMC_SG_RESULT);
|
||||
#endif
|
||||
#if HAS_TMCX1X0
|
||||
#if HAS_TMCX1X0_OR_2240
|
||||
DRV_REPORT("stallguard", TMC_STALLGUARD);
|
||||
DRV_REPORT("fsactive", TMC_FSACTIVE);
|
||||
#endif
|
||||
|
|
@ -944,21 +983,22 @@
|
|||
|
||||
#define PRINT_TMC_REGISTER(REG_CASE) case TMC_GET_##REG_CASE: print_hex_long(st.REG_CASE(), ':'); break
|
||||
|
||||
#if HAS_TMCX1X0
|
||||
static void tmc_get_ic_registers(TMC2130Stepper &st, const TMC_get_registers_enum i) {
|
||||
switch (i) {
|
||||
PRINT_TMC_REGISTER(TCOOLTHRS);
|
||||
PRINT_TMC_REGISTER(THIGH);
|
||||
PRINT_TMC_REGISTER(COOLCONF);
|
||||
default: SERIAL_CHAR('\t'); break;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
#if HAS_TMC220x
|
||||
static void tmc_get_ic_registers(TMC2208Stepper, const TMC_get_registers_enum) { SERIAL_CHAR('\t'); }
|
||||
#endif
|
||||
|
||||
#if HAS_TRINAMIC_CONFIG
|
||||
|
||||
template<class TMC>
|
||||
static void tmc_get_ic_registers(TMC &, const TMC_get_registers_enum) { SERIAL_CHAR('\t'); }
|
||||
|
||||
#if HAS_TMCX1X0
|
||||
static void tmc_get_ic_registers(TMC2130Stepper &st, const TMC_get_registers_enum i) {
|
||||
switch (i) {
|
||||
PRINT_TMC_REGISTER(TCOOLTHRS);
|
||||
PRINT_TMC_REGISTER(THIGH);
|
||||
PRINT_TMC_REGISTER(COOLCONF);
|
||||
default: SERIAL_CHAR('\t'); break;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
template<class TMC>
|
||||
static void tmc_get_registers(TMC &st, const TMC_get_registers_enum i) {
|
||||
switch (i) {
|
||||
|
|
@ -978,7 +1018,8 @@
|
|||
}
|
||||
SERIAL_CHAR('\t');
|
||||
}
|
||||
#endif
|
||||
#endif // HAS_TRINAMIC_CONFIG
|
||||
|
||||
#if HAS_DRIVER(TMC2660)
|
||||
template <char AXIS_LETTER, char DRIVER_ID, AxisEnum AXIS_ID>
|
||||
static void tmc_get_registers(TMCMarlin<TMC2660Stepper, AXIS_LETTER, DRIVER_ID, AXIS_ID> &st, const TMC_get_registers_enum i) {
|
||||
|
|
@ -1105,7 +1146,7 @@
|
|||
// TODO
|
||||
return false;
|
||||
}
|
||||
void tmc_disable_stallguard(TMC2660Stepper, const bool) {};
|
||||
void tmc_disable_stallguard(TMC2660Stepper, const bool) { }
|
||||
|
||||
#endif // USE_SENSORLESS
|
||||
|
||||
|
|
|
|||
|
|
@ -422,6 +422,9 @@ void test_tmc_connection(LOGICAL_AXIS_DECL_LC(const bool, true));
|
|||
bool tmc_enable_stallguard(TMC2209Stepper &st);
|
||||
void tmc_disable_stallguard(TMC2209Stepper &st, const bool restore_stealth);
|
||||
|
||||
bool tmc_enable_stallguard(TMC2240Stepper &st);
|
||||
void tmc_disable_stallguard(TMC2240Stepper &st, const bool restore_stealth);
|
||||
|
||||
bool tmc_enable_stallguard(TMC2660Stepper);
|
||||
void tmc_disable_stallguard(TMC2660Stepper, const bool);
|
||||
|
||||
|
|
|
|||
|
|
@ -268,8 +268,10 @@ typedef struct {
|
|||
|
||||
// If the end point of the line is closer to the nozzle, flip the direction,
|
||||
// moving from the end to the start. On very small lines the optimization isn't worth it.
|
||||
if (dist_end < dist_start && (INTERSECTION_CIRCLE_RADIUS) < ABS(line_length))
|
||||
return print_line_from_here_to_there(e, s);
|
||||
if (dist_end < dist_start && (INTERSECTION_CIRCLE_RADIUS) < ABS(line_length)) {
|
||||
print_line_from_here_to_there(e, s);
|
||||
return;
|
||||
}
|
||||
|
||||
// Decide whether to retract & lift
|
||||
if (dist_start > 2.0) retract_lift_move(s);
|
||||
|
|
|
|||
|
|
@ -228,9 +228,7 @@ void GcodeSuite::M420() {
|
|||
if (to_enable && !planner.leveling_active)
|
||||
SERIAL_ERROR_MSG(STR_ERR_M420_FAILED);
|
||||
|
||||
SERIAL_ECHO_START();
|
||||
SERIAL_ECHOPGM("Bed Leveling ");
|
||||
serialprintln_onoff(planner.leveling_active);
|
||||
SERIAL_ECHO_MSG("Bed Leveling ", ON_OFF(planner.leveling_active));
|
||||
|
||||
#if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
|
||||
SERIAL_ECHO_START();
|
||||
|
|
@ -252,14 +250,13 @@ void GcodeSuite::M420_report(const bool forReplay/*=true*/) {
|
|||
report_heading_etc(forReplay, F(
|
||||
TERN(MESH_BED_LEVELING, "Mesh Bed Leveling", TERN(AUTO_BED_LEVELING_UBL, "Unified Bed Leveling", "Auto Bed Leveling"))
|
||||
));
|
||||
SERIAL_ECHO(
|
||||
SERIAL_ECHOLN(
|
||||
F(" M420 S"), planner.leveling_active
|
||||
#if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
|
||||
, FPSTR(SP_Z_STR), LINEAR_UNIT(planner.z_fade_height)
|
||||
#endif
|
||||
, F(" ; Leveling ")
|
||||
, F(" ; Leveling "), ON_OFF(planner.leveling_active)
|
||||
);
|
||||
serialprintln_onoff(planner.leveling_active);
|
||||
}
|
||||
|
||||
#endif // HAS_LEVELING
|
||||
|
|
|
|||
|
|
@ -98,7 +98,7 @@ void GcodeSuite::G29() {
|
|||
case MeshReport:
|
||||
SERIAL_ECHOPGM("Mesh Bed Leveling ");
|
||||
if (leveling_is_valid()) {
|
||||
serialprintln_onoff(planner.leveling_active);
|
||||
SERIAL_ECHOLN(ON_OFF(planner.leveling_active));
|
||||
bedlevel.report_mesh();
|
||||
}
|
||||
else
|
||||
|
|
|
|||
|
|
@ -598,7 +598,7 @@ void GcodeSuite::G33() {
|
|||
LOOP_NUM_AXES(axis) delta_tower_angle_trim[axis] -= a_sum / 3.0f;
|
||||
}
|
||||
|
||||
// adjust delta_height and endstops by the max amount
|
||||
// Adjust delta_height and endstops by the max amount
|
||||
const float z_temp = _MAX(delta_endstop_adj.a, delta_endstop_adj.b, delta_endstop_adj.c);
|
||||
delta_height -= z_temp;
|
||||
LOOP_NUM_AXES(axis) delta_endstop_adj[axis] -= z_temp;
|
||||
|
|
@ -606,7 +606,7 @@ void GcodeSuite::G33() {
|
|||
recalc_delta_settings();
|
||||
NOMORE(zero_std_dev_min, zero_std_dev);
|
||||
|
||||
// print report
|
||||
// Print report
|
||||
|
||||
if (verbose_level == 3 || verbose_level == 0) {
|
||||
print_calibration_results(z_at_pt, _tower_results, _opposite_results);
|
||||
|
|
|
|||
|
|
@ -124,8 +124,13 @@
|
|||
* S<percent> : Speed factor percentage.
|
||||
*/
|
||||
void GcodeSuite::M201() {
|
||||
if (!parser.seen("T" STR_AXES_LOGICAL TERN_(XY_FREQUENCY_LIMIT, "FS")))
|
||||
if (!parser.seen("T" STR_AXES_LOGICAL
|
||||
#ifdef XY_FREQUENCY_LIMIT
|
||||
"FS"
|
||||
#endif
|
||||
)) {
|
||||
return M201_report();
|
||||
}
|
||||
|
||||
const int8_t target_extruder = get_target_extruder_from_command();
|
||||
if (target_extruder < 0) return;
|
||||
|
|
@ -147,7 +152,11 @@ void GcodeSuite::M201_report(const bool forReplay/*=true*/) {
|
|||
TERN_(MARLIN_SMALL_BUILD, return);
|
||||
|
||||
report_heading_etc(forReplay, F(STR_MAX_ACCELERATION));
|
||||
|
||||
bool eol = false;
|
||||
|
||||
#if NUM_AXES
|
||||
eol = true;
|
||||
SERIAL_ECHOPGM_P(
|
||||
LIST_N(DOUBLE(NUM_AXES),
|
||||
PSTR(" M201 X"), LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[X_AXIS]),
|
||||
|
|
@ -164,13 +173,18 @@ void GcodeSuite::M201_report(const bool forReplay/*=true*/) {
|
|||
#endif
|
||||
|
||||
#if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS)
|
||||
eol = true;
|
||||
SERIAL_ECHOPGM_P(SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_acceleration_mm_per_s2[E_AXIS]));
|
||||
#endif
|
||||
|
||||
#if NUM_AXES || (HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS))
|
||||
SERIAL_EOL();
|
||||
#ifdef XY_FREQUENCY_LIMIT
|
||||
eol = true;
|
||||
SERIAL_ECHOPGM_P(PSTR(" F"), planner.xy_freq_limit_hz);
|
||||
SERIAL_ECHOPGM_P(PSTR(" S"), (planner.xy_freq_min_speed_factor * 100));
|
||||
#endif
|
||||
|
||||
if (eol) SERIAL_EOL();
|
||||
|
||||
#if ENABLED(DISTINCT_E_FACTORS)
|
||||
for (uint8_t i = 0; i < E_STEPPERS; ++i) {
|
||||
report_echo_start(forReplay);
|
||||
|
|
@ -205,7 +219,11 @@ void GcodeSuite::M203_report(const bool forReplay/*=true*/) {
|
|||
TERN_(MARLIN_SMALL_BUILD, return);
|
||||
|
||||
report_heading_etc(forReplay, F(STR_MAX_FEEDRATES));
|
||||
|
||||
bool eol = false;
|
||||
|
||||
#if NUM_AXES
|
||||
eol = true;
|
||||
SERIAL_ECHOPGM_P(
|
||||
LIST_N(DOUBLE(NUM_AXES),
|
||||
PSTR(" M203 X"), LINEAR_UNIT(planner.settings.max_feedrate_mm_s[X_AXIS]),
|
||||
|
|
@ -222,12 +240,11 @@ void GcodeSuite::M203_report(const bool forReplay/*=true*/) {
|
|||
#endif
|
||||
|
||||
#if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS)
|
||||
eol = true;
|
||||
SERIAL_ECHOPGM_P(SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_feedrate_mm_s[E_AXIS]));
|
||||
#endif
|
||||
|
||||
#if NUM_AXES || (HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS))
|
||||
SERIAL_EOL();
|
||||
#endif
|
||||
if (eol) SERIAL_EOL();
|
||||
|
||||
#if ENABLED(DISTINCT_E_FACTORS)
|
||||
for (uint8_t i = 0; i < E_STEPPERS; ++i) {
|
||||
|
|
|
|||
|
|
@ -43,8 +43,7 @@ void GcodeSuite::M211_report(const bool forReplay/*=true*/) {
|
|||
TERN_(MARLIN_SMALL_BUILD, return);
|
||||
|
||||
report_heading_etc(forReplay, F(STR_SOFT_ENDSTOPS));
|
||||
SERIAL_ECHOPGM(" M211 S", AS_DIGIT(soft_endstop._enabled), " ; ");
|
||||
serialprintln_onoff(soft_endstop._enabled);
|
||||
SERIAL_ECHOLNPGM(" M211 S", AS_DIGIT(soft_endstop._enabled), " ; ", ON_OFF(soft_endstop._enabled));
|
||||
|
||||
report_echo_start(forReplay);
|
||||
const xyz_pos_t l_soft_min = soft_endstop.min.asLogical(),
|
||||
|
|
|
|||
|
|
@ -173,8 +173,7 @@
|
|||
set_duplication_enabled(ena && (duplication_e_mask >= 3));
|
||||
}
|
||||
SERIAL_ECHO_START();
|
||||
SERIAL_ECHOPGM(STR_DUPLICATION_MODE);
|
||||
serialprint_onoff(extruder_duplication_enabled);
|
||||
SERIAL_ECHOPGM(STR_DUPLICATION_MODE, ON_OFF(extruder_duplication_enabled));
|
||||
if (ena) {
|
||||
SERIAL_ECHOPGM(" ( ");
|
||||
HOTEND_LOOP() if (TEST(duplication_e_mask, e)) { SERIAL_ECHO(e); SERIAL_CHAR(' '); }
|
||||
|
|
|
|||
|
|
@ -68,8 +68,7 @@ void GcodeSuite::M166() {
|
|||
|
||||
mixer.refresh_gradient();
|
||||
|
||||
SERIAL_ECHOPGM("Gradient Mix ");
|
||||
serialprint_onoff(mixer.gradient.enabled);
|
||||
SERIAL_ECHOPGM("Gradient Mix ", ON_OFF(mixer.gradient.enabled));
|
||||
if (mixer.gradient.enabled) {
|
||||
|
||||
#if ENABLED(GRADIENT_VTOOL)
|
||||
|
|
|
|||
|
|
@ -41,10 +41,10 @@
|
|||
*/
|
||||
void GcodeSuite::M413() {
|
||||
|
||||
if (!parser.seen_any()) return M413_report();
|
||||
|
||||
if (parser.seen('S'))
|
||||
recovery.enable(parser.value_bool());
|
||||
else
|
||||
M413_report();
|
||||
|
||||
#if HAS_PLR_BED_THRESHOLD
|
||||
if (parser.seenval('B'))
|
||||
|
|
@ -67,13 +67,12 @@ void GcodeSuite::M413_report(const bool forReplay/*=true*/) {
|
|||
TERN_(MARLIN_SMALL_BUILD, return);
|
||||
|
||||
report_heading_etc(forReplay, F(STR_POWER_LOSS_RECOVERY));
|
||||
SERIAL_ECHOPGM(" M413 S", AS_DIGIT(recovery.enabled)
|
||||
SERIAL_ECHOLNPGM(" M413 S", AS_DIGIT(recovery.enabled)
|
||||
#if HAS_PLR_BED_THRESHOLD
|
||||
, " B", recovery.bed_temp_threshold
|
||||
#endif
|
||||
, " ; ", ON_OFF(recovery.enabled)
|
||||
);
|
||||
SERIAL_ECHO(" ; ");
|
||||
serialprintln_onoff(recovery.enabled);
|
||||
}
|
||||
|
||||
#endif // POWER_LOSS_RECOVERY
|
||||
|
|
|
|||
|
|
@ -185,13 +185,12 @@ void GcodeSuite::M709() {
|
|||
void GcodeSuite::MMU3_report(const bool forReplay/*=true*/) {
|
||||
using namespace MMU3;
|
||||
report_heading(forReplay, F("MMU3 Operational Stats"));
|
||||
SERIAL_ECHOPGM(" MMU "); serialprintln_onoff(mmu3.mmu_hw_enabled);
|
||||
SERIAL_ECHOPGM(" Stealth Mode "); serialprintln_onoff(mmu3.stealth_mode);
|
||||
SERIAL_ECHOLNPGM(" MMU ", ON_OFF(mmu3.mmu_hw_enabled));
|
||||
SERIAL_ECHOLNPGM(" Stealth Mode ", ON_OFF(mmu3.stealth_mode));
|
||||
#if ENABLED(MMU3_HAS_CUTTER)
|
||||
SERIAL_ECHOPGM(" Cutter ");
|
||||
serialprintln_onoff(mmu3.cutter_mode != 0);
|
||||
SERIAL_ECHOLNPGM(" Cutter ", ON_OFF(mmu3.cutter_mode != 0));
|
||||
#endif
|
||||
SERIAL_ECHOPGM(" SpoolJoin "); serialprintln_onoff(spooljoin.enabled);
|
||||
SERIAL_ECHOLNPGM(" SpoolJoin ", ON_OFF(spooljoin.enabled));
|
||||
SERIAL_ECHOLNPGM(" Tool Changes ", operation_statistics.tool_change_counter);
|
||||
SERIAL_ECHOLNPGM(" Total Tool Changes ", operation_statistics.tool_change_total_counter);
|
||||
SERIAL_ECHOLNPGM(" Fails ", operation_statistics.fail_num);
|
||||
|
|
|
|||
|
|
@ -53,14 +53,12 @@ void GcodeSuite::M412() {
|
|||
}
|
||||
else {
|
||||
SERIAL_ECHO_START();
|
||||
SERIAL_ECHOPGM("Filament runout ");
|
||||
serialprint_onoff(runout.enabled);
|
||||
SERIAL_ECHOPGM("Filament runout ", ON_OFF(runout.enabled));
|
||||
#if HAS_FILAMENT_RUNOUT_DISTANCE
|
||||
SERIAL_ECHOPGM(" ; Distance ", runout.runout_distance(), "mm");
|
||||
#endif
|
||||
#if ENABLED(HOST_ACTION_COMMANDS)
|
||||
SERIAL_ECHOPGM(" ; Host handling ");
|
||||
serialprint_onoff(runout.host_handling);
|
||||
SERIAL_ECHOPGM(" ; Host handling ", ON_OFF(runout.host_handling));
|
||||
#endif
|
||||
SERIAL_EOL();
|
||||
}
|
||||
|
|
@ -70,14 +68,13 @@ void GcodeSuite::M412_report(const bool forReplay/*=true*/) {
|
|||
TERN_(MARLIN_SMALL_BUILD, return);
|
||||
|
||||
report_heading_etc(forReplay, F(STR_FILAMENT_RUNOUT_SENSOR));
|
||||
SERIAL_ECHOPGM(
|
||||
SERIAL_ECHOLNPGM(
|
||||
" M412 S", runout.enabled
|
||||
#if HAS_FILAMENT_RUNOUT_DISTANCE
|
||||
, " D", LINEAR_UNIT(runout.runout_distance())
|
||||
#endif
|
||||
, " ; Sensor "
|
||||
, " ; Sensor ", ON_OFF(runout.enabled)
|
||||
);
|
||||
serialprintln_onoff(runout.enabled);
|
||||
}
|
||||
|
||||
#endif // HAS_FILAMENT_SENSOR
|
||||
|
|
|
|||
|
|
@ -76,9 +76,7 @@
|
|||
template<typename TMC>
|
||||
static void tmc_report_otpw(TMC &st) {
|
||||
st.printLabel();
|
||||
SERIAL_ECHOPGM(" temperature prewarn triggered: ");
|
||||
serialprint_truefalse(st.getOTPW());
|
||||
SERIAL_EOL();
|
||||
SERIAL_ECHOLNPGM(" temperature prewarn triggered: ", TRUE_FALSE(st.getOTPW()));
|
||||
}
|
||||
|
||||
template<typename TMC>
|
||||
|
|
|
|||
|
|
@ -319,7 +319,7 @@ void GcodeSuite::dwell(const millis_t time) {
|
|||
/**
|
||||
* Process the parsed command and dispatch it to its handler
|
||||
*/
|
||||
void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) {
|
||||
void GcodeSuite::process_parsed_command(bool no_ok/*=false*/) {
|
||||
TERN_(HAS_FANCHECK, fan_check.check_deferred_error());
|
||||
|
||||
KEEPALIVE_STATE(IN_HANDLER);
|
||||
|
|
@ -582,7 +582,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) {
|
|||
case 109: M109(); break; // M109: Wait for hotend temperature to reach target
|
||||
#endif
|
||||
|
||||
case 105: M105(); return; // M105: Report Temperatures (and say "ok")
|
||||
case 105: M105(); no_ok = true; break; // M105: Report Temperatures (and say "ok")
|
||||
|
||||
#if HAS_FAN
|
||||
case 106: M106(); break; // M106: Fan On
|
||||
|
|
|
|||
|
|
@ -458,7 +458,7 @@ public:
|
|||
static int8_t get_target_e_stepper_from_command(const int8_t dval=-1);
|
||||
static void get_destination_from_command();
|
||||
|
||||
static void process_parsed_command(const bool no_ok=false);
|
||||
static void process_parsed_command(bool no_ok=false);
|
||||
static void process_next_command();
|
||||
|
||||
// Execute G-code in-place, preserving current G-code parameters
|
||||
|
|
|
|||
|
|
@ -86,9 +86,10 @@ void GcodeSuite::G0_G1(TERN_(HAS_FAST_MOVES, const bool fast_move/*=false*/)) {
|
|||
const float echange = destination.e - current_position.e;
|
||||
// Is this a retract or recover move?
|
||||
if (WITHIN(ABS(echange), MIN_AUTORETRACT, MAX_AUTORETRACT) && fwretract.retracted[active_extruder] == (echange > 0.0)) {
|
||||
current_position.e = destination.e; // Hide a G1-based retract/recover from calculations
|
||||
sync_plan_position_e(); // AND from the planner
|
||||
return fwretract.retract(echange < 0.0); // Firmware-based retract/recover (double-retract ignored)
|
||||
current_position.e = destination.e; // Hide a G1-based retract/recover from calculations
|
||||
sync_plan_position_e(); // AND from the planner
|
||||
fwretract.retract(echange < 0.0); // Firmware-based retract/recover (double-retract ignored)
|
||||
return;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
|||
|
|
@ -47,9 +47,7 @@ void GcodeSuite::M401() {
|
|||
seenS = parser.seen('S');
|
||||
if (seenH || seenS) {
|
||||
if (seenS) bltouch.high_speed_mode = parser.value_bool();
|
||||
SERIAL_ECHO_START();
|
||||
SERIAL_ECHOPGM("BLTouch HS mode ");
|
||||
serialprintln_onoff(bltouch.high_speed_mode);
|
||||
SERIAL_ECHO_MSG("BLTouch HS mode ", ON_OFF(bltouch.high_speed_mode));
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
|
|
|||
|
|
@ -80,7 +80,7 @@ void GcodeSuite::M951() {
|
|||
if (parser.seenval('H')) mpe_settings.fast_feedrate = MMM_TO_MMS(parser.value_linear_units());
|
||||
if (parser.seenval('D')) mpe_settings.travel_distance = parser.value_linear_units();
|
||||
if (parser.seenval('C')) mpe_settings.compensation_factor = parser.value_float();
|
||||
if (!parser.seen("CDHIJLR")) mpe_settings_report();
|
||||
if (!parser.seen_any()) mpe_settings_report();
|
||||
}
|
||||
|
||||
#endif // MAGNETIC_PARKING_EXTRUDER
|
||||
|
|
|
|||
|
|
@ -65,7 +65,10 @@ void GcodeSuite::M106() {
|
|||
|
||||
#if ENABLED(EXTRA_FAN_SPEED)
|
||||
const uint16_t t = parser.intval('T');
|
||||
if (t > 0) return thermalManager.set_temp_fan_speed(pfan, t);
|
||||
if (t > 0) {
|
||||
thermalManager.set_temp_fan_speed(pfan, t);
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
||||
const uint16_t dspeed = parser.seen_test('A') ? thermalManager.fan_speed[active_extruder] : 255;
|
||||
|
|
|
|||
|
|
@ -50,9 +50,7 @@ void GcodeSuite::M303() {
|
|||
#if HAS_PID_DEBUG
|
||||
if (parser.seen_test('D')) {
|
||||
FLIP(thermalManager.pid_debug_flag);
|
||||
SERIAL_ECHO_START();
|
||||
SERIAL_ECHOPGM("PID Debug ");
|
||||
serialprintln_onoff(thermalManager.pid_debug_flag);
|
||||
SERIAL_ECHO_MSG("PID Debug ", ON_OFF(thermalManager.pid_debug_flag));
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
|
|
|||
|
|
@ -765,15 +765,15 @@
|
|||
#endif
|
||||
|
||||
// Consolidate TMC26X, validate migration (#24373)
|
||||
#define _ISMAX_1(A) defined(A##_MAX_CURRENT)
|
||||
#define _ISSNS_1(A) defined(A##_SENSE_RESISTOR)
|
||||
#if DO(ISMAX,||,ALL_AXIS_NAMES)
|
||||
#define _ISMAX(A) defined(A##_MAX_CURRENT) ||
|
||||
#define _ISSNS(A) defined(A##_SENSE_RESISTOR) ||
|
||||
#if MAP(_ISMAX, ALL_AXIS_NAMES) 0
|
||||
#error "*_MAX_CURRENT is now set with *_CURRENT."
|
||||
#elif DO(ISSNS,||,ALL_AXIS_NAMES)
|
||||
#elif MAP(_ISSNS, ALL_AXIS_NAMES) 0
|
||||
#error "*_SENSE_RESISTOR (in Milli-Ohms) is now set with *_RSENSE (in Ohms), so you must divide values by 1000."
|
||||
#endif
|
||||
#undef _ISMAX_1
|
||||
#undef _ISSNS_1
|
||||
#undef _ISMAX
|
||||
#undef _ISSNS
|
||||
|
||||
// L64xx stepper drivers have been removed
|
||||
#define _L6470 0x6470
|
||||
|
|
|
|||
|
|
@ -663,11 +663,6 @@
|
|||
#define BOOT_MARLIN_LOGO_SMALL
|
||||
#endif
|
||||
|
||||
// Flow and feedrate editing
|
||||
#if HAS_EXTRUDERS && ANY(HAS_MARLINUI_MENU, DWIN_CREALITY_LCD, DWIN_LCD_PROUI, MALYAN_LCD, TOUCH_SCREEN)
|
||||
#define HAS_FLOW_EDIT 1
|
||||
#endif
|
||||
|
||||
/**
|
||||
* TFT Displays
|
||||
*
|
||||
|
|
|
|||
|
|
@ -3381,7 +3381,7 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i
|
|||
// Stall detection DIAG = HIGH : TMC2209/2240
|
||||
// Stall detection DIAG = LOW : TMC2130/2160/2660/5130/5160
|
||||
#if X_SENSORLESS
|
||||
#define _HIT_STATE AXIS_DRIVER_TYPE(X,TMC2209) || AXIS_DRIVER_TYPE(X,TMC2240)
|
||||
#define _HIT_STATE (AXIS_DRIVER_TYPE(X,TMC2209) || AXIS_DRIVER_TYPE(X,TMC2240))
|
||||
#if X_HOME_TO_MIN && X_MIN_ENDSTOP_HIT_STATE != _HIT_STATE
|
||||
#if _HIT_STATE
|
||||
#error "SENSORLESS_HOMING requires X_MIN_ENDSTOP_HIT_STATE HIGH for X MIN homing with TMC2209/2240."
|
||||
|
|
@ -3399,7 +3399,7 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i
|
|||
#endif
|
||||
|
||||
#if Y_SENSORLESS
|
||||
#define _HIT_STATE AXIS_DRIVER_TYPE(Y,TMC2209) || AXIS_DRIVER_TYPE(Y,TMC2240)
|
||||
#define _HIT_STATE (AXIS_DRIVER_TYPE(Y,TMC2209) || AXIS_DRIVER_TYPE(Y,TMC2240))
|
||||
#if Y_HOME_TO_MIN && Y_MIN_ENDSTOP_HIT_STATE != _HIT_STATE
|
||||
#if _HIT_STATE
|
||||
#error "SENSORLESS_HOMING requires Y_MIN_ENDSTOP_HIT_STATE HIGH for Y MIN homing with TMC2209/2240."
|
||||
|
|
@ -3417,7 +3417,7 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i
|
|||
#endif
|
||||
|
||||
#if Z_SENSORLESS
|
||||
#define _HIT_STATE AXIS_DRIVER_TYPE(Z,TMC2209) || AXIS_DRIVER_TYPE(Z,TMC2240)
|
||||
#define _HIT_STATE (AXIS_DRIVER_TYPE(Z,TMC2209) || AXIS_DRIVER_TYPE(Z,TMC2240))
|
||||
#if Z_HOME_TO_MIN && Z_MIN_ENDSTOP_HIT_STATE != _HIT_STATE
|
||||
#if _HIT_STATE
|
||||
#error "SENSORLESS_HOMING requires Z_MIN_ENDSTOP_HIT_STATE HIGH for Z MIN homing with TMC2209/2240."
|
||||
|
|
@ -3435,7 +3435,7 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i
|
|||
#endif
|
||||
|
||||
#if I_SENSORLESS
|
||||
#define _HIT_STATE AXIS_DRIVER_TYPE(I,TMC2209) || AXIS_DRIVER_TYPE(I,TMC2240)
|
||||
#define _HIT_STATE (AXIS_DRIVER_TYPE(I,TMC2209) || AXIS_DRIVER_TYPE(I,TMC2240))
|
||||
#if I_HOME_TO_MIN && I_MIN_ENDSTOP_HIT_STATE != _HIT_STATE
|
||||
#if _HIT_STATE
|
||||
#error "SENSORLESS_HOMING requires I_MIN_ENDSTOP_HIT_STATE HIGH for I MIN homing with TMC2209/2240."
|
||||
|
|
@ -3453,7 +3453,7 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i
|
|||
#endif
|
||||
|
||||
#if J_SENSORLESS
|
||||
#define _HIT_STATE AXIS_DRIVER_TYPE(J,TMC2209) || AXIS_DRIVER_TYPE(J,TMC2240)
|
||||
#define _HIT_STATE (AXIS_DRIVER_TYPE(J,TMC2209) || AXIS_DRIVER_TYPE(J,TMC2240))
|
||||
#if J_HOME_TO_MIN && J_MIN_ENDSTOP_HIT_STATE != _HIT_STATE
|
||||
#if _HIT_STATE
|
||||
#error "SENSORLESS_HOMING requires J_MIN_ENDSTOP_HIT_STATE HIGH for J MIN homing with TMC2209/2240."
|
||||
|
|
@ -3471,7 +3471,7 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i
|
|||
#endif
|
||||
|
||||
#if K_SENSORLESS
|
||||
#define _HIT_STATE AXIS_DRIVER_TYPE(K,TMC2209) || AXIS_DRIVER_TYPE(K,TMC2240)
|
||||
#define _HIT_STATE (AXIS_DRIVER_TYPE(K,TMC2209) || AXIS_DRIVER_TYPE(K,TMC2240))
|
||||
#if K_HOME_TO_MIN && K_MIN_ENDSTOP_HIT_STATE != _HIT_STATE
|
||||
#if _HIT_STATE
|
||||
#error "SENSORLESS_HOMING requires K_MIN_ENDSTOP_HIT_STATE HIGH for K MIN homing with TMC2209/2240."
|
||||
|
|
@ -3489,7 +3489,7 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i
|
|||
#endif
|
||||
|
||||
#if U_SENSORLESS
|
||||
#define _HIT_STATE AXIS_DRIVER_TYPE(U,TMC2209) || AXIS_DRIVER_TYPE(U,TMC2240)
|
||||
#define _HIT_STATE (AXIS_DRIVER_TYPE(U,TMC2209) || AXIS_DRIVER_TYPE(U,TMC2240))
|
||||
#if U_HOME_TO_MIN && U_MIN_ENDSTOP_HIT_STATE != _HIT_STATE
|
||||
#if _HIT_STATE
|
||||
#error "SENSORLESS_HOMING requires U_MIN_ENDSTOP_HIT_STATE HIGH for U MIN homing with TMC2209/2240."
|
||||
|
|
@ -3507,7 +3507,7 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i
|
|||
#endif
|
||||
|
||||
#if V_SENSORLESS
|
||||
#define _HIT_STATE AXIS_DRIVER_TYPE(V,TMC2209) || AXIS_DRIVER_TYPE(V,TMC2240)
|
||||
#define _HIT_STATE (AXIS_DRIVER_TYPE(V,TMC2209) || AXIS_DRIVER_TYPE(V,TMC2240))
|
||||
#if V_HOME_TO_MIN && V_MIN_ENDSTOP_HIT_STATE != _HIT_STATE
|
||||
#if _HIT_STATE
|
||||
#error "SENSORLESS_HOMING requires V_MIN_ENDSTOP_HIT_STATE HIGH for V MIN homing with TMC2209/2240."
|
||||
|
|
@ -3525,7 +3525,7 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i
|
|||
#endif
|
||||
|
||||
#if W_SENSORLESS
|
||||
#define _HIT_STATE AXIS_DRIVER_TYPE(W,TMC2209) || AXIS_DRIVER_TYPE(W,TMC2240)
|
||||
#define _HIT_STATE (AXIS_DRIVER_TYPE(W,TMC2209) || AXIS_DRIVER_TYPE(W,TMC2240))
|
||||
#if W_HOME_TO_MIN && W_MIN_ENDSTOP_HIT_STATE != _HIT_STATE
|
||||
#if _HIT_STATE
|
||||
#error "SENSORLESS_HOMING requires W_MIN_ENDSTOP_HIT_STATE HIGH for W MIN homing with TMC2209/2240."
|
||||
|
|
|
|||
|
|
@ -42,7 +42,7 @@
|
|||
* version was tagged.
|
||||
*/
|
||||
#ifndef STRING_DISTRIBUTION_DATE
|
||||
#define STRING_DISTRIBUTION_DATE "2025-05-25"
|
||||
#define STRING_DISTRIBUTION_DATE "2025-05-29"
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
|
|
|||
|
|
@ -137,9 +137,8 @@ EncoderState encoderReceiveAnalyze() {
|
|||
|
||||
// LED write data
|
||||
void LED_WriteData() {
|
||||
uint8_t tempCounter_LED, tempCounter_Bit;
|
||||
for (tempCounter_LED = 0; tempCounter_LED < LED_NUM; tempCounter_LED++) {
|
||||
for (tempCounter_Bit = 0; tempCounter_Bit < 24; tempCounter_Bit++) {
|
||||
for (uint8_t tempCounter_LED = 0; tempCounter_LED < LED_NUM; tempCounter_LED++) {
|
||||
for (uint8_t tempCounter_Bit = 0; tempCounter_Bit < 24; tempCounter_Bit++) {
|
||||
if (LED_DataArray[tempCounter_LED] & (0x800000 >> tempCounter_Bit)) {
|
||||
LED_DATA_HIGH;
|
||||
DELAY_NS(300);
|
||||
|
|
@ -190,20 +189,22 @@ EncoderState encoderReceiveAnalyze() {
|
|||
}
|
||||
}
|
||||
|
||||
struct { bool g, r, b; } led_flag = { false, false, false };
|
||||
struct { bool g, r, b; } led_flag;
|
||||
for (uint8_t i = 0; i < LED_NUM; i++) {
|
||||
led_flag = { false, false, false };
|
||||
while (1) {
|
||||
const uint8_t g = uint8_t(LED_DataArray[i] >> 16),
|
||||
r = uint8_t(LED_DataArray[i] >> 8),
|
||||
b = uint8_t(LED_DataArray[i]);
|
||||
if (g == led_data[i].g) led_flag.g = true;
|
||||
else LED_DataArray[i] += (g > led_data[i].g) ? -0x010000 : 0x010000;
|
||||
else LED_DataArray[i] += (g > led_data[i].g) ? -_BV32(16) : _BV32(16);
|
||||
if (r == led_data[i].r) led_flag.r = true;
|
||||
else LED_DataArray[i] += (r > led_data[i].r) ? -0x000100 : 0x000100;
|
||||
else LED_DataArray[i] += (r > led_data[i].r) ? -_BV32(8) : _BV32(8);
|
||||
if (b == led_data[i].b) led_flag.b = true;
|
||||
else LED_DataArray[i] += (b > led_data[i].b) ? -0x000001 : 0x000001;
|
||||
else LED_DataArray[i] += (b > led_data[i].b) ? -_BV32(0) : _BV32(0);
|
||||
|
||||
LED_WriteData();
|
||||
if (led_flag.r && led_flag.g && led_flag.b) break;
|
||||
if (led_flag.g && led_flag.r && led_flag.b) break;
|
||||
delay(change_Interval);
|
||||
}
|
||||
}
|
||||
|
|
|
|||
|
|
@ -2380,6 +2380,7 @@ void setMoveZ() { hmiValue.axis = Z_AXIS; setPFloatOnClick(Z_MIN_POS, Z_MAX_POS,
|
|||
#endif
|
||||
|
||||
void setSpeed() { setPIntOnClick(SPEED_EDIT_MIN, SPEED_EDIT_MAX); }
|
||||
void setFlow() { setPIntOnClick(FLOW_EDIT_MIN, FLOW_EDIT_MAX, []{ planner.refresh_e_factor(0); }); }
|
||||
|
||||
#if HAS_HOTEND
|
||||
void applyHotendTemp() { thermalManager.setTargetHotend(menuData.value, 0); }
|
||||
|
|
@ -2424,8 +2425,6 @@ void setSpeed() { setPIntOnClick(SPEED_EDIT_MIN, SPEED_EDIT_MAX); }
|
|||
|
||||
#endif // ADVANCED_PAUSE_FEATURE
|
||||
|
||||
void setFlow() { setPIntOnClick(FLOW_EDIT_MIN, FLOW_EDIT_MAX, []{ planner.refresh_e_factor(0); }); }
|
||||
|
||||
// Bed Tramming
|
||||
|
||||
#if ENABLED(LCD_BED_TRAMMING)
|
||||
|
|
@ -2597,23 +2596,25 @@ void setFlow() { setPIntOnClick(FLOW_EDIT_MIN, FLOW_EDIT_MAX, []{ planner.refres
|
|||
|
||||
#if ENABLED(MESH_BED_LEVELING)
|
||||
|
||||
#define MESH_Z_FDIGITS 2
|
||||
|
||||
void manualMeshStart() {
|
||||
LCD_MESSAGE(MSG_UBL_BUILD_MESH_MENU);
|
||||
gcode.process_subcommands_now(F("G28XYO\nG28Z\nM211S0\nG29S1"));
|
||||
#ifdef MANUAL_PROBE_START_Z
|
||||
const uint8_t line = currentMenu->line(mMeshMoveZItem->pos);
|
||||
DWINUI::drawSignedFloat(hmiData.colorText, hmiData.colorBackground, 3, 2, VALX - 2 * DWINUI::fontWidth(DWIN_FONT_MENU), MBASE(line), MANUAL_PROBE_START_Z);
|
||||
DWINUI::drawSignedFloat(hmiData.colorText, hmiData.colorBackground, 3, MESH_Z_FDIGITS, VALX - 2 * DWINUI::fontWidth(DWIN_FONT_MENU), MBASE(line), MANUAL_PROBE_START_Z);
|
||||
#endif
|
||||
}
|
||||
|
||||
void liveMeshMoveZ() {
|
||||
*menuData.floatPtr = menuData.value / POW(10, 2);
|
||||
*menuData.floatPtr = menuData.value / POW(10, MESH_Z_FDIGITS);
|
||||
if (!planner.is_full()) {
|
||||
planner.synchronize();
|
||||
planner.buffer_line(current_position, manual_feedrate_mm_s[Z_AXIS]);
|
||||
}
|
||||
}
|
||||
void setMMeshMoveZ() { setPFloatOnClick(-1, 1, 2, planner.synchronize, liveMeshMoveZ); }
|
||||
void setMMeshMoveZ() { setPFloatOnClick(-1, 1, MESH_Z_FDIGITS, planner.synchronize, liveMeshMoveZ); }
|
||||
|
||||
void manualMeshContinue() {
|
||||
gcode.process_subcommands_now(F("G29S2"));
|
||||
|
|
@ -2687,8 +2688,9 @@ void applyMaxAccel() { planner.set_max_acceleration(hmiValue.axis, menuData.valu
|
|||
#endif
|
||||
|
||||
#if ENABLED(LIN_ADVANCE)
|
||||
void applyLA_K() { planner.set_advance_k(menuData.value / MINUNITMULT); }
|
||||
void setLA_K() { setPFloatOnClick(0, 10, 3, applyLA_K); }
|
||||
#define LA_FDIGITS 3
|
||||
void applyLA_K() { planner.set_advance_k(menuData.value / POW(10, LA_FDIGITS)); }
|
||||
void setLA_K() { setPFloatOnClick(0, 10, LA_FDIGITS, applyLA_K); }
|
||||
#endif
|
||||
|
||||
#if HAS_X_AXIS
|
||||
|
|
@ -3519,6 +3521,7 @@ void drawTuneMenu() {
|
|||
if (SET_MENU_R(tuneMenu, selrect({73, 2, 28, 12}), MSG_TUNE, items)) {
|
||||
BACK_ITEM(gotoPrintProcess);
|
||||
EDIT_ITEM(ICON_Speed, MSG_SPEED, onDrawSpeedItem, setSpeed, &feedrate_percentage);
|
||||
EDIT_ITEM(ICON_Flow, MSG_FLOW, onDrawPIntMenu, setFlow, &planner.flow_percentage[0]);
|
||||
#if HAS_HOTEND
|
||||
hotendTargetItem = EDIT_ITEM(ICON_HotendTemp, MSG_UBL_SET_TEMP_HOTEND, onDrawHotendTemp, setHotendTemp, &thermalManager.temp_hotend[0].target);
|
||||
#endif
|
||||
|
|
@ -3533,7 +3536,6 @@ void drawTuneMenu() {
|
|||
#elif ALL(HAS_ZOFFSET_ITEM, MESH_BED_LEVELING, BABYSTEPPING)
|
||||
EDIT_ITEM(ICON_Zoffset, MSG_HOME_OFFSET_Z, onDrawPFloat2Menu, setZOffset, &BABY_Z_VAR);
|
||||
#endif
|
||||
EDIT_ITEM(ICON_Flow, MSG_FLOW, onDrawPIntMenu, setFlow, &planner.flow_percentage[0]);
|
||||
#if ENABLED(ADVANCED_PAUSE_FEATURE)
|
||||
MENU_ITEM(ICON_FilMan, MSG_FILAMENTCHANGE, onDrawMenuItem, changeFilament);
|
||||
#endif
|
||||
|
|
@ -3550,8 +3552,8 @@ void drawTuneMenu() {
|
|||
EDIT_ITEM(ICON_JDmm, MSG_JUNCTION_DEVIATION, onDrawPFloat3Menu, setJDmm, &planner.junction_deviation_mm);
|
||||
#endif
|
||||
#if ENABLED(PROUI_ITEM_ADVK)
|
||||
float editable_decimal = planner.get_advance_k();
|
||||
EDIT_ITEM(ICON_MaxAccelerated, MSG_ADVANCE_K, onDrawPFloat3Menu, setLA_K, &editable_decimal);
|
||||
float editable_k = planner.get_advance_k();
|
||||
EDIT_ITEM(ICON_MaxAccelerated, MSG_ADVANCE_K, onDrawPFloat3Menu, setLA_K, &editable_k);
|
||||
#endif
|
||||
#if HAS_LOCKSCREEN
|
||||
MENU_ITEM(ICON_Lock, MSG_LOCKSCREEN, onDrawMenuItem, dwinLockScreen);
|
||||
|
|
@ -3692,8 +3694,8 @@ void drawMotionMenu() {
|
|||
MENU_ITEM(ICON_Homing, MSG_HOMING_FEEDRATE, onDrawSubMenu, drawHomingFRMenu);
|
||||
#endif
|
||||
#if ENABLED(LIN_ADVANCE)
|
||||
float editable_decimal = planner.get_advance_k();
|
||||
EDIT_ITEM(ICON_MaxAccelerated, MSG_ADVANCE_K, onDrawPFloat3Menu, setLA_K, &editable_decimal);
|
||||
float editable_k = planner.get_advance_k();
|
||||
EDIT_ITEM(ICON_MaxAccelerated, MSG_ADVANCE_K, onDrawPFloat3Menu, setLA_K, &editable_k);
|
||||
#endif
|
||||
#if ENABLED(SHAPING_MENU)
|
||||
MENU_ITEM(ICON_InputShaping, MSG_INPUT_SHAPING, onDrawSubMenu, drawInputShaping_menu);
|
||||
|
|
@ -3701,8 +3703,8 @@ void drawMotionMenu() {
|
|||
#if ENABLED(ADAPTIVE_STEP_SMOOTHING_TOGGLE)
|
||||
EDIT_ITEM(ICON_UBLActive, MSG_STEP_SMOOTHING, onDrawChkbMenu, setAdaptiveStepSmoothing, &stepper.adaptive_step_smoothing_enabled);
|
||||
#endif
|
||||
EDIT_ITEM(ICON_Speed, MSG_SPEED, onDrawSpeedItem, setSpeed, &feedrate_percentage);
|
||||
EDIT_ITEM(ICON_Flow, MSG_FLOW, onDrawPIntMenu, setFlow, &planner.flow_percentage[0]);
|
||||
EDIT_ITEM(ICON_Speed, MSG_SPEED, onDrawPIntMenu, setSpeed, &feedrate_percentage);
|
||||
}
|
||||
updateMenu(motionMenu);
|
||||
}
|
||||
|
|
@ -4035,9 +4037,10 @@ void drawMaxAccelMenu() {
|
|||
void setSensorResponse() { setPFloatOnClick(0, 1, 4); }
|
||||
void setAmbientXfer() { setPFloatOnClick(0, 1, 4); }
|
||||
#if ENABLED(MPC_INCLUDE_FAN)
|
||||
void onDrawFanAdj(MenuItem* menuitem, int8_t line) { onDrawFloatMenu(menuitem, line, 4, thermalManager.temp_hotend[0].fanCoefficient()); }
|
||||
void applyFanAdj() { thermalManager.temp_hotend[0].applyFanAdjustment(menuData.value / POW(10, 4)); }
|
||||
void setFanAdj() { setFloatOnClick(0, 1, 4, thermalManager.temp_hotend[0].fanCoefficient(), applyFanAdj); }
|
||||
#define MPC_FAN_FDIGITS 4
|
||||
void onDrawFanAdj(MenuItem* menuitem, int8_t line) { onDrawFloatMenu(menuitem, line, MPC_FAN_FDIGITS, thermalManager.temp_hotend[0].fanCoefficient()); }
|
||||
void applyFanAdj() { thermalManager.temp_hotend[0].applyFanAdjustment(menuData.value / POW(10, MPC_FAN_FDIGITS)); }
|
||||
void setFanAdj() { setFloatOnClick(0, 1, MPC_FAN_FDIGITS, thermalManager.temp_hotend[0].fanCoefficient(), applyFanAdj); }
|
||||
#endif
|
||||
#endif
|
||||
|
||||
|
|
@ -4081,27 +4084,28 @@ void drawMaxAccelMenu() {
|
|||
#endif
|
||||
|
||||
#if ENABLED(PID_EDIT_MENU)
|
||||
void setKp() { setPFloatOnClick(0, 1000, 2); }
|
||||
#define PID_FDIGITS 2
|
||||
void setKp() { setPFloatOnClick(0, 1000, PID_FDIGITS); }
|
||||
void applyPIDi() {
|
||||
*menuData.floatPtr = scalePID_i(menuData.value / POW(10, 2));
|
||||
*menuData.floatPtr = scalePID_i(menuData.value / POW(10, PID_FDIGITS));
|
||||
TERN_(PIDTEMP, thermalManager.updatePID());
|
||||
}
|
||||
void applyPIDd() {
|
||||
*menuData.floatPtr = scalePID_d(menuData.value / POW(10, 2));
|
||||
*menuData.floatPtr = scalePID_d(menuData.value / POW(10, PID_FDIGITS));
|
||||
TERN_(PIDTEMP, thermalManager.updatePID());
|
||||
}
|
||||
void setKi() {
|
||||
menuData.floatPtr = (float*)static_cast<MenuItemPtr*>(currentMenu->selectedItem())->value;
|
||||
const float value = unscalePID_i(*menuData.floatPtr);
|
||||
setFloatOnClick(0, 1000, 2, value, applyPIDi);
|
||||
setFloatOnClick(0, 1000, PID_FDIGITS, value, applyPIDi);
|
||||
}
|
||||
void setKd() {
|
||||
menuData.floatPtr = (float*)static_cast<MenuItemPtr*>(currentMenu->selectedItem())->value;
|
||||
const float value = unscalePID_d(*menuData.floatPtr);
|
||||
setFloatOnClick(0, 1000, 2, value, applyPIDd);
|
||||
setFloatOnClick(0, 1000, PID_FDIGITS, value, applyPIDd);
|
||||
}
|
||||
void onDrawPIDi(MenuItem* menuitem, int8_t line) { onDrawFloatMenu(menuitem, line, 2, unscalePID_i(*(float*)static_cast<MenuItemPtr*>(menuitem)->value)); }
|
||||
void onDrawPIDd(MenuItem* menuitem, int8_t line) { onDrawFloatMenu(menuitem, line, 2, unscalePID_d(*(float*)static_cast<MenuItemPtr*>(menuitem)->value)); }
|
||||
void onDrawPIDi(MenuItem* menuitem, int8_t line) { onDrawFloatMenu(menuitem, line, PID_FDIGITS, unscalePID_i(*(float*)static_cast<MenuItemPtr*>(menuitem)->value)); }
|
||||
void onDrawPIDd(MenuItem* menuitem, int8_t line) { onDrawFloatMenu(menuitem, line, PID_FDIGITS, unscalePID_d(*(float*)static_cast<MenuItemPtr*>(menuitem)->value)); }
|
||||
#endif // PID_EDIT_MENU
|
||||
|
||||
#endif // HAS_PID_HEATING
|
||||
|
|
|
|||
|
|
@ -579,7 +579,7 @@ char *creat_title_text() {
|
|||
update_spi_flash();
|
||||
}
|
||||
card.closefile();
|
||||
#endif
|
||||
#endif // HAS_MEDIA
|
||||
}
|
||||
|
||||
void gcode_preview(char *path, int xpos_pixel, int ypos_pixel) {
|
||||
|
|
@ -662,27 +662,27 @@ char *creat_title_text() {
|
|||
}
|
||||
|
||||
void draw_default_preview(int xpos_pixel, int ypos_pixel, uint8_t sel) {
|
||||
int index;
|
||||
static constexpr uint16_t draw_col_count = 40; // Number of rows displayed each time, determines the size of bmp_public_buf
|
||||
static constexpr int draw_count = 200 / draw_col_count; // Total number of times to be displayed
|
||||
static constexpr uint32_t pixel_count = (DEFAULT_VIEW_MAX_SIZE) / draw_count; // Number of pixels read per time (uint8_t)
|
||||
int y_off = 0;
|
||||
W25QXX.init(SPI_QUARTER_SPEED);
|
||||
for (index = 0; index < 10; index++) { // 200*200
|
||||
for (int index = 0; index < draw_count; index++) { // 200*200
|
||||
#if HAS_BAK_VIEW_IN_FLASH
|
||||
if (sel == 1) {
|
||||
flash_view_Read(bmp_public_buf, 8000); // 20k
|
||||
flash_view_Read(bmp_public_buf, pixel_count); // 16k
|
||||
}
|
||||
else {
|
||||
default_view_Read(bmp_public_buf, DEFAULT_VIEW_MAX_SIZE / 10); // 8k
|
||||
default_view_Read(bmp_public_buf, pixel_count); // 16k
|
||||
}
|
||||
#else
|
||||
default_view_Read(bmp_public_buf, DEFAULT_VIEW_MAX_SIZE / 10); // 8k
|
||||
default_view_Read(bmp_public_buf, pixel_count); // 8k
|
||||
#endif
|
||||
|
||||
SPI_TFT.setWindow(xpos_pixel, y_off * 20 + ypos_pixel, 200, 20); // 200*200
|
||||
SPI_TFT.tftio.writeSequence((uint16_t*)(bmp_public_buf), DEFAULT_VIEW_MAX_SIZE / 20);
|
||||
SPI_TFT.setWindow(xpos_pixel, y_off * draw_col_count + ypos_pixel, 200, draw_col_count); // 200 * draw_col_count
|
||||
SPI_TFT.tftio.writeSequence((uint16_t*)(bmp_public_buf), uint16_t(pixel_count / 2));
|
||||
|
||||
y_off++;
|
||||
}
|
||||
W25QXX.init(SPI_QUARTER_SPEED);
|
||||
}
|
||||
|
||||
void disp_pre_gcode(int xpos_pixel, int ypos_pixel) {
|
||||
|
|
@ -700,6 +700,7 @@ char *creat_title_text() {
|
|||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif // HAS_GCODE_PREVIEW
|
||||
|
||||
void print_time_run() {
|
||||
|
|
|
|||
|
|
@ -35,6 +35,10 @@
|
|||
|
||||
#include <string.h>
|
||||
|
||||
#if ENABLED(USE_HASH_TABLE)
|
||||
#include "uthash.h"
|
||||
#endif
|
||||
|
||||
extern uint16_t DeviceCode;
|
||||
|
||||
#if HAS_MEDIA
|
||||
|
|
@ -92,7 +96,7 @@ static FSTR_P const assets[] = {
|
|||
F("bmp_file.bin"),
|
||||
|
||||
// Move motor screen
|
||||
// TODO: 6 equal icons, just in diffenct rotation... it may be optimized too
|
||||
// TODO: 6 equal icons, just in different rotation... it may be optimized too
|
||||
F("bmp_xAdd.bin"),
|
||||
F("bmp_xDec.bin"),
|
||||
F("bmp_yAdd.bin"),
|
||||
|
|
@ -223,42 +227,98 @@ static FSTR_P const assets[] = {
|
|||
static FSTR_P const fonts[] = { F("FontUNIGBK.bin") };
|
||||
#endif
|
||||
|
||||
uint8_t currentFlashPage = 0;
|
||||
#if HAS_SPI_FLASH_COMPRESSION
|
||||
uint8_t currentFlashPage = 0;
|
||||
#endif
|
||||
|
||||
uint32_t lv_get_pic_addr(uint8_t *Pname) {
|
||||
uint8_t Pic_cnt;
|
||||
uint8_t i, j;
|
||||
PIC_MSG PIC;
|
||||
uint32_t tmp_cnt = 0;
|
||||
uint32_t addr = 0;
|
||||
#if ENABLED(USE_HASH_TABLE)
|
||||
|
||||
currentFlashPage = 0;
|
||||
typedef struct {
|
||||
char name[PIC_NAME_MAX_LEN - PIC_NAME_OFFSET]; /* key */
|
||||
uint32_t addr;
|
||||
UT_hash_handle hh; /* makes this structure hashable */
|
||||
} PicHashEntry;
|
||||
|
||||
#if ENABLED(MARLIN_DEV_MODE)
|
||||
SERIAL_ECHOLNPGM("Getting picture SPI Flash Address: ", (const char*)Pname);
|
||||
#endif
|
||||
PicHashEntry* pic_hash = NULL;
|
||||
|
||||
W25QXX.init(SPI_QUARTER_SPEED);
|
||||
// Initialize the image address hash table
|
||||
void init_img_map() {
|
||||
uint8_t Pic_cnt;
|
||||
W25QXX.SPI_FLASH_BufferRead(&Pic_cnt, PIC_COUNTER_ADDR, 1);
|
||||
if (Pic_cnt == 0xFF) Pic_cnt = 0;
|
||||
|
||||
W25QXX.SPI_FLASH_BufferRead(&Pic_cnt, PIC_COUNTER_ADDR, 1);
|
||||
if (Pic_cnt == 0xFF) Pic_cnt = 0;
|
||||
for (i = 0; i < Pic_cnt; i++) {
|
||||
j = 0;
|
||||
do {
|
||||
W25QXX.SPI_FLASH_BufferRead(&PIC.name[j], PIC_NAME_ADDR + tmp_cnt, 1);
|
||||
tmp_cnt++;
|
||||
} while (PIC.name[j++] != '\0');
|
||||
uint32_t tmp_cnt = 0;
|
||||
for (uint8_t i = 0; i < Pic_cnt; i++) {
|
||||
char name[PIC_NAME_MAX_LEN - PIC_NAME_OFFSET];
|
||||
uint8_t j = 0;
|
||||
do {
|
||||
W25QXX.SPI_FLASH_BufferRead((uint8_t*)&name[j], PIC_NAME_ADDR + tmp_cnt, 1);
|
||||
tmp_cnt++;
|
||||
} while (name[j++] != '\0');
|
||||
|
||||
if ((strcasecmp((char*)Pname, (char*)PIC.name)) == 0) {
|
||||
uint32_t addr;
|
||||
if (DeviceCode == 0x9488 || DeviceCode == 0x5761)
|
||||
addr = PIC_DATA_ADDR_TFT35 + i * PER_PIC_MAX_SPACE_TFT35;
|
||||
else
|
||||
addr = PIC_DATA_ADDR_TFT32 + i * PER_PIC_MAX_SPACE_TFT32;
|
||||
return addr;
|
||||
|
||||
// Add to hash table, don't save "bmp_"
|
||||
PicHashEntry* entry = (PicHashEntry*)malloc(sizeof(*entry));
|
||||
strncpy(entry->name, (name + PIC_NAME_OFFSET), sizeof(name));
|
||||
entry->addr = addr;
|
||||
HASH_ADD_STR(pic_hash, name, entry);
|
||||
}
|
||||
#if ENABLED(MARLIN_DEV_MODE)
|
||||
SERIAL_ECHOLNPGM("Image Hash Table Count: ", HASH_COUNT(pic_hash), ", Size(Bytes): ", HASH_OVERHEAD(hh, pic_hash));
|
||||
#endif
|
||||
}
|
||||
return addr;
|
||||
}
|
||||
|
||||
uint32_t lv_get_pic_addr(uint8_t *Pname) {
|
||||
#if ENABLED(MARLIN_DEV_MODE)
|
||||
SERIAL_ECHOLNPGM("Getting picture SPI Flash Address: ", (const char*)Pname);
|
||||
#endif
|
||||
|
||||
PicHashEntry* entry;
|
||||
HASH_FIND_STR(pic_hash, (char*)(Pname + PIC_NAME_OFFSET), entry);
|
||||
return entry ? entry->addr : 0;
|
||||
}
|
||||
|
||||
#else // !USE_HASH_TABLE
|
||||
|
||||
uint32_t lv_get_pic_addr(uint8_t *Pname) {
|
||||
uint8_t Pic_cnt;
|
||||
uint8_t i, j;
|
||||
PIC_MSG PIC;
|
||||
uint32_t tmp_cnt = 0;
|
||||
uint32_t addr = 0;
|
||||
|
||||
#if ENABLED(MARLIN_DEV_MODE)
|
||||
SERIAL_ECHOLNPGM("Getting picture SPI Flash Address: ", (const char*)Pname);
|
||||
#endif
|
||||
|
||||
W25QXX.init(SPI_QUARTER_SPEED);
|
||||
|
||||
W25QXX.SPI_FLASH_BufferRead(&Pic_cnt, PIC_COUNTER_ADDR, 1);
|
||||
if (Pic_cnt == 0xFF) Pic_cnt = 0;
|
||||
for (i = 0; i < Pic_cnt; i++) {
|
||||
j = 0;
|
||||
do {
|
||||
W25QXX.SPI_FLASH_BufferRead(&PIC.name[j], PIC_NAME_ADDR + tmp_cnt, 1);
|
||||
tmp_cnt++;
|
||||
} while (PIC.name[j++] != '\0');
|
||||
|
||||
if ((strcasecmp((char*)Pname, (char*)PIC.name)) == 0) {
|
||||
if (DeviceCode == 0x9488 || DeviceCode == 0x5761)
|
||||
addr = PIC_DATA_ADDR_TFT35 + i * PER_PIC_MAX_SPACE_TFT35;
|
||||
else
|
||||
addr = PIC_DATA_ADDR_TFT32 + i * PER_PIC_MAX_SPACE_TFT32;
|
||||
break;
|
||||
}
|
||||
}
|
||||
return addr;
|
||||
}
|
||||
|
||||
#endif // !USE_HASH_TABLE
|
||||
|
||||
const char *assetsPath = "assets";
|
||||
const char *bakPath = "_assets";
|
||||
|
|
@ -309,8 +369,8 @@ uint8_t picLogoWrite(uint8_t *LogoName, uint8_t *Logo_Wbuff, uint32_t LogoWriteS
|
|||
|
||||
uint32_t TitleLogoWrite_Addroffset = 0;
|
||||
uint8_t picTitleLogoWrite(uint8_t *TitleLogoName, uint8_t *TitleLogo_Wbuff, uint32_t TitleLogoWriteSize) {
|
||||
if (TitleLogoWriteSize <= 0)
|
||||
return 0;
|
||||
if (TitleLogoWriteSize <= 0) return 0;
|
||||
|
||||
if ((DeviceCode == 0x9488) || (DeviceCode == 0x5761))
|
||||
W25QXX.SPI_FLASH_BufferWrite(TitleLogo_Wbuff, PIC_ICON_LOGO_ADDR_TFT35 + TitleLogoWrite_Addroffset, TitleLogoWriteSize);
|
||||
else
|
||||
|
|
@ -341,9 +401,7 @@ uint32_t picInfoWrite(uint8_t *P_name, uint32_t P_size) {
|
|||
union union32 size_tmp;
|
||||
|
||||
W25QXX.SPI_FLASH_BufferRead(&pic_counter, PIC_COUNTER_ADDR, 1);
|
||||
|
||||
if (pic_counter == 0xFF)
|
||||
pic_counter = 0;
|
||||
if (pic_counter == 0xFF) pic_counter = 0;
|
||||
|
||||
if ((DeviceCode == 0x9488) || (DeviceCode == 0x5761))
|
||||
picSaveAddr = PIC_DATA_ADDR_TFT35 + pic_counter * PER_PIC_MAX_SPACE_TFT35;
|
||||
|
|
@ -416,6 +474,7 @@ uint32_t picInfoWrite(uint8_t *P_name, uint32_t P_size) {
|
|||
}
|
||||
|
||||
hal.watchdog_refresh();
|
||||
disp_string(100, 165, FTOP(F(" ")), 0xFFFF, 0x0000); // clean string
|
||||
disp_assets_update_progress(fn);
|
||||
|
||||
W25QXX.init(SPI_QUARTER_SPEED);
|
||||
|
|
@ -449,16 +508,18 @@ uint32_t picInfoWrite(uint8_t *P_name, uint32_t P_size) {
|
|||
}
|
||||
else if (assetType == ASSET_TYPE_ICON) {
|
||||
Pic_Write_Addr = picInfoWrite((uint8_t*)fn, pfileSize);
|
||||
SPIFlash.beginWrite(Pic_Write_Addr);
|
||||
#if HAS_SPI_FLASH_COMPRESSION
|
||||
SPIFlash.beginWrite(Pic_Write_Addr);
|
||||
do {
|
||||
hal.watchdog_refresh();
|
||||
pbr = file.read(public_buf, SPI_FLASH_PageSize);
|
||||
TERN_(MARLIN_DEV_MODE, totalSizes += pbr);
|
||||
SPIFlash.writeData(public_buf, SPI_FLASH_PageSize);
|
||||
} while (pbr >= SPI_FLASH_PageSize);
|
||||
SPIFlash.endWrite();
|
||||
#else
|
||||
do {
|
||||
hal.watchdog_refresh();
|
||||
pbr = file.read(public_buf, BMP_WRITE_BUF_LEN);
|
||||
W25QXX.SPI_FLASH_BufferWrite(public_buf, Pic_Write_Addr, pbr);
|
||||
Pic_Write_Addr += pbr;
|
||||
|
|
@ -468,7 +529,6 @@ uint32_t picInfoWrite(uint8_t *P_name, uint32_t P_size) {
|
|||
SERIAL_ECHOLNPGM("Space used: ", fn, " - ", (SPIFlash.getCurrentPage() + 1) * SPI_FLASH_PageSize / 1024, "KB");
|
||||
totalCompressed += (SPIFlash.getCurrentPage() + 1) * SPI_FLASH_PageSize;
|
||||
#endif
|
||||
SPIFlash.endWrite();
|
||||
}
|
||||
else if (assetType == ASSET_TYPE_FONT) {
|
||||
Pic_Write_Addr = UNIGBK_FLASH_ADDR;
|
||||
|
|
@ -557,8 +617,7 @@ void picRead(uint8_t *Pname, uint8_t *P_Rbuff) {
|
|||
PIC_MSG PIC;
|
||||
|
||||
W25QXX.SPI_FLASH_BufferRead(&Pic_cnt, PIC_COUNTER_ADDR, 1);
|
||||
if (Pic_cnt == 0xFF)
|
||||
Pic_cnt = 0;
|
||||
if (Pic_cnt == 0xFF) Pic_cnt = 0;
|
||||
|
||||
for (i = 0; i < Pic_cnt; i++) {
|
||||
j = 0;
|
||||
|
|
@ -578,12 +637,12 @@ void picRead(uint8_t *Pname, uint8_t *P_Rbuff) {
|
|||
|
||||
void lv_pic_test(uint8_t *P_Rbuff, uint32_t addr, uint32_t size) {
|
||||
#if HAS_SPI_FLASH_COMPRESSION
|
||||
if (currentFlashPage == 0)
|
||||
if (currentFlashPage == 0) {
|
||||
currentFlashPage = 1;
|
||||
SPIFlash.beginRead(addr);
|
||||
}
|
||||
SPIFlash.readData(P_Rbuff, size);
|
||||
currentFlashPage++;
|
||||
#else
|
||||
W25QXX.init(SPI_QUARTER_SPEED);
|
||||
W25QXX.SPI_FLASH_BufferRead((uint8_t *)P_Rbuff, addr, size);
|
||||
#endif
|
||||
}
|
||||
|
|
|
|||
|
|
@ -29,6 +29,9 @@
|
|||
|
||||
#include <stdint.h>
|
||||
#include <string.h>
|
||||
#include "SPIFlashStorage.h"
|
||||
|
||||
#define USE_HASH_TABLE
|
||||
|
||||
#ifndef HAS_SPI_FLASH_FONT
|
||||
#define HAS_SPI_FLASH_FONT 1 // Disabled until fix the font load code
|
||||
|
|
@ -53,7 +56,8 @@
|
|||
#endif
|
||||
|
||||
#define PIC_MAX_CN 100 // Maximum number of pictures
|
||||
#define PIC_NAME_MAX_LEN 50 // Picture name maximum length
|
||||
#define PIC_NAME_MAX_LEN 30 // Picture name maximum length
|
||||
#define PIC_NAME_OFFSET 4 // Same picture filename section
|
||||
|
||||
#define LOGO_MAX_SIZE_TFT35 (300 * 1024)
|
||||
#define LOGO_MAX_SIZE_TFT32 (150 * 1024)
|
||||
|
|
@ -61,7 +65,11 @@
|
|||
#define DEFAULT_VIEW_MAX_SIZE (200 * 200 * 2)
|
||||
#define FLASH_VIEW_MAX_SIZE (200 * 200 * 2)
|
||||
|
||||
#define PER_PIC_MAX_SPACE_TFT35 (9 * 1024)
|
||||
#if HAS_SPI_FLASH_COMPRESSION
|
||||
#define PER_PIC_MAX_SPACE_TFT35 ( 9 * 1024)
|
||||
#else
|
||||
#define PER_PIC_MAX_SPACE_TFT35 (32 * 1024)
|
||||
#endif
|
||||
#define PER_PIC_MAX_SPACE_TFT32 (16 * 1024)
|
||||
#define PER_FONT_MAX_SPACE (16 * 1024)
|
||||
|
||||
|
|
@ -154,6 +162,9 @@ typedef struct pic_msg PIC_MSG;
|
|||
#define PIC_SIZE_xM 6
|
||||
#define FONT_SIZE_xM 2
|
||||
|
||||
#if ENABLED(USE_HASH_TABLE)
|
||||
void init_img_map();
|
||||
#endif
|
||||
void picRead(uint8_t *Pname, uint8_t *P_Rbuff);
|
||||
void picLogoRead(uint8_t *LogoName, uint8_t *Logo_Rbuff, uint32_t LogoReadsize);
|
||||
void lv_pic_test(uint8_t *P_Rbuff, uint32_t addr, uint32_t size);
|
||||
|
|
|
|||
|
|
@ -85,7 +85,7 @@ lv_group_t* g;
|
|||
uint16_t DeviceCode = 0x9488;
|
||||
extern uint8_t sel_id;
|
||||
|
||||
uint8_t bmp_public_buf[14 * 1024];
|
||||
uint8_t bmp_public_buf[16 * 1024];
|
||||
uint8_t public_buf[513];
|
||||
|
||||
extern bool flash_preview_begin, default_preview_flg, gcode_preview_over;
|
||||
|
|
@ -149,9 +149,14 @@ void tft_lvgl_init() {
|
|||
|
||||
touch.init();
|
||||
|
||||
#if ENABLED(USE_HASH_TABLE)
|
||||
init_img_map(); // Initialize the image address hash table
|
||||
hal.watchdog_refresh(); // Hash table init takes time
|
||||
#endif
|
||||
|
||||
lv_init();
|
||||
|
||||
lv_disp_buf_init(&disp_buf, bmp_public_buf, nullptr, LV_HOR_RES_MAX * 14); // Initialize the display buffer
|
||||
lv_disp_buf_init(&disp_buf, bmp_public_buf, nullptr, LV_HOR_RES_MAX * 17); // Initialize the display buffer
|
||||
|
||||
lv_disp_drv_t disp_drv; // Descriptor of a display driver
|
||||
lv_disp_drv_init(&disp_drv); // Basic initialization
|
||||
|
|
@ -268,8 +273,6 @@ void my_disp_flush(lv_disp_drv_t * disp, const lv_area_t * area, lv_color_t * co
|
|||
SPI_TFT.tftio.writeSequence((uint16_t*)color_p, width * height);
|
||||
lv_disp_flush_ready(disp_drv_p); // Indicate you are ready with the flushing
|
||||
#endif
|
||||
|
||||
W25QXX.init(SPI_QUARTER_SPEED);
|
||||
}
|
||||
|
||||
#if ENABLED(USE_SPI_DMA_TC)
|
||||
|
|
@ -327,20 +330,26 @@ bool my_mousewheel_read(lv_indev_drv_t * indev_drv, lv_indev_data_t * data) {
|
|||
return false; // No more data to read so return false
|
||||
}
|
||||
|
||||
extern uint8_t currentFlashPage;
|
||||
#if HAS_SPI_FLASH_COMPRESSION
|
||||
extern uint8_t currentFlashPage;
|
||||
#endif
|
||||
|
||||
// spi_flash
|
||||
uint32_t pic_read_base_addr = 0, pic_read_addr_offset = 0;
|
||||
lv_fs_res_t spi_flash_open_cb (lv_fs_drv_t * drv, void * file_p, const char * path, lv_fs_mode_t mode) {
|
||||
static char last_path_name[30];
|
||||
#if HAS_SPI_FLASH_COMPRESSION
|
||||
currentFlashPage = 0;
|
||||
#endif
|
||||
if (strcasecmp(last_path_name, path) != 0) {
|
||||
pic_read_base_addr = lv_get_pic_addr((uint8_t *)path);
|
||||
// clean lvgl image cache
|
||||
char cache_path_name[30 + 3] = {0};
|
||||
strcat(cache_path_name, "F:/");
|
||||
strcat(cache_path_name, (const char *)last_path_name);
|
||||
lv_img_cache_invalidate_src(cache_path_name);
|
||||
strcpy(last_path_name, path);
|
||||
}
|
||||
else {
|
||||
W25QXX.init(SPI_QUARTER_SPEED);
|
||||
currentFlashPage = 0;
|
||||
}
|
||||
pic_read_addr_offset = pic_read_base_addr;
|
||||
return LV_FS_RES_OK;
|
||||
}
|
||||
|
|
|
|||
|
|
@ -32,7 +32,7 @@
|
|||
|
||||
#include <lvgl.h>
|
||||
|
||||
extern uint8_t bmp_public_buf[14 * 1024];
|
||||
extern uint8_t bmp_public_buf[16 * 1024];
|
||||
extern uint8_t public_buf[513];
|
||||
|
||||
void tft_lvgl_init();
|
||||
|
|
|
|||
1137
Marlin/src/lcd/extui/mks_ui/uthash.h
Normal file
1137
Marlin/src/lcd/extui/mks_ui/uthash.h
Normal file
File diff suppressed because it is too large
Load diff
|
|
@ -45,13 +45,14 @@ namespace LanguageNarrow_cz {
|
|||
LSTR MSG_YES = _UxGT("ANO");
|
||||
LSTR MSG_NO = _UxGT("NE");
|
||||
LSTR MSG_BACK = _UxGT("Zpět");
|
||||
|
||||
LSTR MSG_MEDIA_ABORTING = _UxGT("Rušení...");
|
||||
LSTR MSG_MEDIA_INSERTED = _UxGT("Médium vloženo");
|
||||
LSTR MSG_MEDIA_REMOVED = _UxGT("Médium vyjmuto");
|
||||
LSTR MSG_MEDIA_WAITING = _UxGT("Čekání na médium");
|
||||
LSTR MSG_MEDIA_READ_ERROR = _UxGT("Chyba čtení média");
|
||||
LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB odstraněno");
|
||||
LSTR MSG_MEDIA_USB_FAILED = _UxGT("Chyba USB");
|
||||
LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("USB odstraněno");
|
||||
LSTR MSG_USB_FD_USB_FAILED = _UxGT("Chyba USB");
|
||||
|
||||
LSTR MSG_LCD_ENDSTOPS = _UxGT("Endstopy"); // max 8 znaku
|
||||
LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Soft Endstopy");
|
||||
LSTR MSG_MAIN_MENU = _UxGT("Hlavní nabídka");
|
||||
|
|
|
|||
|
|
@ -41,15 +41,16 @@ namespace LanguageNarrow_de {
|
|||
LSTR MSG_LOW = _UxGT("RUNTER");
|
||||
LSTR MSG_BACK = _UxGT("Zurück");
|
||||
LSTR MSG_ERROR = _UxGT("Fehler");
|
||||
|
||||
LSTR MSG_MEDIA_ABORTING = _UxGT("Abbruch...");
|
||||
LSTR MSG_MEDIA_INSERTED = _UxGT("Medium erkannt");
|
||||
LSTR MSG_MEDIA_REMOVED = _UxGT("Medium entfernt");
|
||||
LSTR MSG_MEDIA_WAITING = _UxGT("Warten auf Medium");
|
||||
LSTR MSG_MEDIA_INIT_FAIL = _UxGT("Medium Init fehlgesch.");
|
||||
LSTR MSG_MEDIA_READ_ERROR = _UxGT("Medium Lesefehler");
|
||||
LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB Gerät entfernt");
|
||||
LSTR MSG_MEDIA_USB_FAILED = _UxGT("USB Start fehlge.");
|
||||
LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("USB Gerät entfernt");
|
||||
LSTR MSG_USB_FD_USB_FAILED = _UxGT("USB Start fehlge.");
|
||||
LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Subcall überschritten");
|
||||
|
||||
LSTR MSG_LCD_ENDSTOPS = _UxGT("Endstopp"); // Max length 8 characters
|
||||
LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Software-Endstopp");
|
||||
LSTR MSG_MAIN_MENU = _UxGT("Hauptmenü");
|
||||
|
|
|
|||
|
|
@ -45,12 +45,12 @@ namespace LanguageNarrow_el {
|
|||
|
||||
LSTR MSG_MEDIA_INSERTED = _UxGT("Κάρτα εισήχθη");
|
||||
LSTR MSG_MEDIA_REMOVED = _UxGT("Κάρτα αφαιρέθη");
|
||||
LSTR MSG_MEDIA_WAITING = _UxGT("Αναμονή για κάρτα");
|
||||
LSTR MSG_MEDIA_ABORTING = _UxGT("Ματαίωση...");
|
||||
LSTR MSG_MEDIA_READ_ERROR = MEDIA_TYPE_EN _UxGT(" σφάλμα ανάγνωσης");
|
||||
LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB αφαιρέθη");
|
||||
LSTR MSG_MEDIA_USB_FAILED = _UxGT("Αποτυχία εκκίνησης USB");
|
||||
LSTR MSG_MEDIA_INIT_FAIL = _UxGT("Αποτυχία αρχικοποίησης SD");
|
||||
LSTR MSG_MEDIA_READ_ERROR = MEDIA_TYPE_EN _UxGT(" σφάλμα ανάγνωσης");
|
||||
LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("USB αφαιρέθη");
|
||||
LSTR MSG_USB_FD_USB_FAILED = _UxGT("Αποτυχία εκκίνησης USB");
|
||||
|
||||
LSTR MSG_MAIN_MENU = _UxGT("Αρχική Οθόνη");
|
||||
LSTR MSG_DISABLE_STEPPERS = _UxGT("Απενεργοποίηση μοτέρ");
|
||||
LSTR MSG_AUTO_HOME = _UxGT("Αυτόμ. επαναφορά XYZ");
|
||||
|
|
|
|||
|
|
@ -90,17 +90,16 @@ namespace LanguageNarrow_en {
|
|||
LSTR MSG_MEDIA_REMOVED = MEDIA_TYPE_EN _UxGT(" Removed");
|
||||
LSTR MSG_MEDIA_REMOVED_SD = _UxGT("SD Card Removed");
|
||||
LSTR MSG_MEDIA_REMOVED_USB = _UxGT("USB Drive Removed");
|
||||
LSTR MSG_MEDIA_WAITING = _UxGT("Waiting for ") MEDIA_TYPE_EN;
|
||||
LSTR MSG_MEDIA_WAITING_SD = _UxGT("Waiting for SD Card");
|
||||
LSTR MSG_MEDIA_WAITING_USB = _UxGT("Waiting for USB Drive");
|
||||
LSTR MSG_MEDIA_INIT_FAIL = MEDIA_TYPE_EN _UxGT(" Init Fail");
|
||||
LSTR MSG_MEDIA_INIT_FAIL_SD = _UxGT("SD Card Init Fail");
|
||||
LSTR MSG_MEDIA_INIT_FAIL_USB = _UxGT("USB Drive Init Fail");
|
||||
LSTR MSG_MEDIA_READ_ERROR = MEDIA_TYPE_EN _UxGT(" read error");
|
||||
LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB device removed");
|
||||
LSTR MSG_MEDIA_USB_FAILED = _UxGT("USB start failed");
|
||||
LSTR MSG_MEDIA_SORT = _UxGT("Sort ") MEDIA_TYPE_EN;
|
||||
LSTR MSG_MEDIA_UPDATE = MEDIA_TYPE_EN _UxGT(" Update");
|
||||
LSTR MSG_USB_FD_WAITING_FOR_MEDIA = _UxGT("Wait for USB Drive");
|
||||
LSTR MSG_USB_FD_MEDIA_REMOVED = _UxGT("USB Drive Removed");
|
||||
LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("USB device removed");
|
||||
LSTR MSG_USB_FD_USB_FAILED = _UxGT("USB start failed");
|
||||
|
||||
LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Subcall Overflow");
|
||||
LSTR MSG_LCD_ENDSTOPS = _UxGT("Endstops"); // Max length 8 characters
|
||||
|
|
@ -364,7 +363,7 @@ namespace LanguageNarrow_en {
|
|||
LSTR MSG_MOVE_N_MM = _UxGT("Move $mm");
|
||||
LSTR MSG_MOVE_N_IN = _UxGT("Move $in");
|
||||
LSTR MSG_MOVE_N_DEG = _UxGT("Move $") LCD_STR_DEGREE;
|
||||
LSTR MSG_LIVE_MOVE = _UxGT("Live Move");
|
||||
LSTR MSG_LIVE_MOVE = _UxGT("Live Movement");
|
||||
LSTR MSG_SPEED = _UxGT("Speed");
|
||||
LSTR MSG_MESH_Z_OFFSET = _UxGT("Bed Z");
|
||||
LSTR MSG_NOZZLE = _UxGT("Nozzle");
|
||||
|
|
|
|||
|
|
@ -46,15 +46,16 @@ namespace LanguageNarrow_es {
|
|||
LSTR MSG_YES = _UxGT("SI");
|
||||
LSTR MSG_NO = _UxGT("NO");
|
||||
LSTR MSG_BACK = _UxGT("Atrás");
|
||||
|
||||
LSTR MSG_MEDIA_ABORTING = _UxGT("Cancelando...");
|
||||
LSTR MSG_MEDIA_INSERTED = MEDIA_TYPE_ES _UxGT(" insertado");
|
||||
LSTR MSG_MEDIA_REMOVED = MEDIA_TYPE_ES _UxGT(" retirado");
|
||||
LSTR MSG_MEDIA_WAITING = _UxGT("Esperando al ") MEDIA_TYPE_ES;
|
||||
LSTR MSG_MEDIA_INIT_FAIL = _UxGT("Fallo al iniciar ") MEDIA_TYPE_ES;
|
||||
LSTR MSG_MEDIA_READ_ERROR = _UxGT("Error lectura ") MEDIA_TYPE_ES;
|
||||
LSTR MSG_MEDIA_USB_REMOVED = _UxGT("Disp. USB retirado");
|
||||
LSTR MSG_MEDIA_USB_FAILED = _UxGT("Inicio USB fallido");
|
||||
LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("Disp. USB retirado");
|
||||
LSTR MSG_USB_FD_USB_FAILED = _UxGT("Inicio USB fallido");
|
||||
LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Desbordamiento de subllamada");
|
||||
|
||||
LSTR MSG_LCD_ENDSTOPS = _UxGT("Endstops"); // Max length 8 characters
|
||||
LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Soft Endstops");
|
||||
LSTR MSG_MAIN_MENU = _UxGT("Menú principal");
|
||||
|
|
|
|||
|
|
@ -40,13 +40,14 @@ namespace LanguageNarrow_fr {
|
|||
LSTR MSG_YES = _UxGT("Oui");
|
||||
LSTR MSG_NO = _UxGT("Non");
|
||||
LSTR MSG_BACK = _UxGT("Retour");
|
||||
|
||||
LSTR MSG_MEDIA_ABORTING = _UxGT("Annulation...");
|
||||
LSTR MSG_MEDIA_INSERTED = _UxGT("Média inséré");
|
||||
LSTR MSG_MEDIA_REMOVED = _UxGT("Média retiré");
|
||||
LSTR MSG_MEDIA_WAITING = _UxGT("Attente média");
|
||||
LSTR MSG_MEDIA_READ_ERROR = _UxGT("Err lecture média");
|
||||
LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB débranché");
|
||||
LSTR MSG_MEDIA_USB_FAILED = _UxGT("Erreur média USB");
|
||||
LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("USB débranché");
|
||||
LSTR MSG_USB_FD_USB_FAILED = _UxGT("Erreur média USB");
|
||||
|
||||
LSTR MSG_LCD_ENDSTOPS = _UxGT("Butées");
|
||||
LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Butées SW");
|
||||
LSTR MSG_MAIN_MENU = _UxGT("Menu principal");
|
||||
|
|
|
|||
|
|
@ -40,13 +40,14 @@ namespace LanguageNarrow_fr_na {
|
|||
LSTR MSG_YES = _UxGT("Oui");
|
||||
LSTR MSG_NO = _UxGT("Non");
|
||||
LSTR MSG_BACK = _UxGT("Retour");
|
||||
|
||||
LSTR MSG_MEDIA_ABORTING = _UxGT("Annulation...");
|
||||
LSTR MSG_MEDIA_INSERTED = _UxGT("Media insere");
|
||||
LSTR MSG_MEDIA_REMOVED = _UxGT("Media retire");
|
||||
LSTR MSG_MEDIA_WAITING = _UxGT("Attente media");
|
||||
LSTR MSG_MEDIA_READ_ERROR = _UxGT("Err lecture media");
|
||||
LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB debranche");
|
||||
LSTR MSG_MEDIA_USB_FAILED = _UxGT("Erreur media USB");
|
||||
LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("USB debranche");
|
||||
LSTR MSG_USB_FD_USB_FAILED = _UxGT("Erreur media USB");
|
||||
|
||||
LSTR MSG_LCD_ENDSTOPS = _UxGT("Butees");
|
||||
LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Butees SW");
|
||||
LSTR MSG_MAIN_MENU = _UxGT("Menu principal");
|
||||
|
|
|
|||
|
|
@ -48,14 +48,15 @@ namespace LanguageNarrow_gl {
|
|||
LSTR MSG_YES = _UxGT("SI");
|
||||
LSTR MSG_NO = _UxGT("NON");
|
||||
LSTR MSG_BACK = _UxGT("Atrás");
|
||||
|
||||
LSTR MSG_MEDIA_ABORTING = _UxGT("Cancelando...");
|
||||
LSTR MSG_MEDIA_INSERTED = _UxGT("Tarxeta inserida");
|
||||
LSTR MSG_MEDIA_REMOVED = _UxGT("Tarxeta retirada");
|
||||
LSTR MSG_MEDIA_WAITING = _UxGT("Agardando ao ") MEDIA_TYPE_GL;
|
||||
LSTR MSG_MEDIA_READ_ERROR = _UxGT("Erro lectura ") MEDIA_TYPE_GL;
|
||||
LSTR MSG_MEDIA_USB_REMOVED = _UxGT("Disp. USB retirado");
|
||||
LSTR MSG_MEDIA_USB_FAILED = _UxGT("Inicio USB fallido");
|
||||
LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("Disp. USB retirado");
|
||||
LSTR MSG_USB_FD_USB_FAILED = _UxGT("Inicio USB fallido");
|
||||
LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Desbord. Subch.");
|
||||
|
||||
LSTR MSG_LCD_ENDSTOPS = _UxGT("FinCarro");
|
||||
LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("FinCarro SW");
|
||||
LSTR MSG_MAIN_MENU = _UxGT("Menú principal");
|
||||
|
|
|
|||
|
|
@ -43,15 +43,16 @@ namespace LanguageNarrow_hu {
|
|||
LSTR MSG_YES = _UxGT("IGEN");
|
||||
LSTR MSG_NO = _UxGT("NEM");
|
||||
LSTR MSG_BACK = _UxGT("Vissza");
|
||||
|
||||
LSTR MSG_MEDIA_ABORTING = _UxGT("Megszakítás...");
|
||||
LSTR MSG_MEDIA_INSERTED = _UxGT("Tároló behelyezve");
|
||||
LSTR MSG_MEDIA_REMOVED = _UxGT("Tároló eltávolítva");
|
||||
LSTR MSG_MEDIA_WAITING = _UxGT("Várakozás a tárolóra");
|
||||
LSTR MSG_MEDIA_INIT_FAIL = _UxGT("Tároló-kártya hiba");
|
||||
LSTR MSG_MEDIA_READ_ERROR = _UxGT("Tároló olvasási hiba");
|
||||
LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB eltávolítva");
|
||||
LSTR MSG_MEDIA_USB_FAILED = _UxGT("USB eszköz hiba");
|
||||
LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("USB eltávolítva");
|
||||
LSTR MSG_USB_FD_USB_FAILED = _UxGT("USB eszköz hiba");
|
||||
LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Túlfolyás");
|
||||
|
||||
LSTR MSG_LCD_ENDSTOPS = _UxGT("Végállás"); // Maximum 8 karakter
|
||||
LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Szoft. végállás");
|
||||
LSTR MSG_MAIN_MENU = _UxGT("<Fömenü>");
|
||||
|
|
|
|||
|
|
@ -59,16 +59,25 @@ namespace LanguageNarrow_it {
|
|||
LSTR MSG_LOW = _UxGT("BASSO");
|
||||
LSTR MSG_BACK = _UxGT("Indietro");
|
||||
LSTR MSG_ERROR = _UxGT("Errore");
|
||||
|
||||
LSTR MSG_MEDIA_ABORTING = _UxGT("Annullando...");
|
||||
LSTR MSG_MEDIA_INSERTED = MEDIA_TYPE_IT _UxGT(" inserito");
|
||||
LSTR MSG_MEDIA_REMOVED = MEDIA_TYPE_IT _UxGT(" rimosso");
|
||||
LSTR MSG_MEDIA_WAITING = _UxGT("Aspettando ") MEDIA_TYPE_IT;
|
||||
LSTR MSG_MEDIA_INSERTED = MEDIA_TYPE_IT _UxGT(" inserita");
|
||||
LSTR MSG_MEDIA_INSERTED_SD = _UxGT("Scheda SD inserita");
|
||||
LSTR MSG_MEDIA_INSERTED_USB = _UxGT("Unità USB inserita");
|
||||
LSTR MSG_MEDIA_REMOVED = MEDIA_TYPE_IT _UxGT(" rimossa");
|
||||
LSTR MSG_MEDIA_REMOVED_SD = _UxGT("Scheda SD rimossa");
|
||||
LSTR MSG_MEDIA_REMOVED_USB = _UxGT("Unità USB rimossa");
|
||||
LSTR MSG_MEDIA_INIT_FAIL = _UxGT("Iniz.") MEDIA_TYPE_IT _UxGT(" fallita");
|
||||
LSTR MSG_MEDIA_INIT_FAIL_SD = _UxGT("Iniz. SD fallita");
|
||||
LSTR MSG_MEDIA_INIT_FAIL_USB = _UxGT("Iniz. USB fallita");
|
||||
LSTR MSG_MEDIA_READ_ERROR = _UxGT("Err.leggendo ") MEDIA_TYPE_IT;
|
||||
LSTR MSG_MEDIA_USB_REMOVED = _UxGT("Dispos.USB rimosso");
|
||||
LSTR MSG_MEDIA_USB_FAILED = _UxGT("Avvio USB fallito");
|
||||
LSTR MSG_MEDIA_SORT = _UxGT("Ordina ") MEDIA_TYPE_IT;
|
||||
LSTR MSG_MEDIA_UPDATE = _UxGT("Aggiorna ") MEDIA_TYPE_IT;
|
||||
LSTR MSG_USB_FD_WAITING_FOR_MEDIA = _UxGT("In attesa unità USB");
|
||||
LSTR MSG_USB_FD_MEDIA_REMOVED = _UxGT("Unità USB rimossa");
|
||||
LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("Unità USB rimossa");
|
||||
LSTR MSG_USB_FD_USB_FAILED = _UxGT("Iniz. USB fallita");
|
||||
|
||||
LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Overflow sottochiamate");
|
||||
LSTR MSG_LCD_ENDSTOPS = _UxGT("Finecor."); // Max 8 characters
|
||||
LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Finecorsa soft");
|
||||
|
|
@ -133,11 +142,12 @@ namespace LanguageNarrow_it {
|
|||
|
||||
LSTR MSG_PREHEAT_M = _UxGT("Preriscalda $");
|
||||
LSTR MSG_PREHEAT_M_H = _UxGT("Preriscalda $ ~");
|
||||
LSTR MSG_PREHEAT_M_END = _UxGT("Preris.$ ugello");
|
||||
LSTR MSG_PREHEAT_M_END_E = _UxGT("Preris.$ ugello ~");
|
||||
LSTR MSG_PREHEAT_M_ALL = _UxGT("Preris.$ tutto");
|
||||
LSTR MSG_PREHEAT_M_BEDONLY = _UxGT("Preris.$ piatto");
|
||||
LSTR MSG_PREHEAT_M_SETTINGS = _UxGT("Preris.$ conf");
|
||||
LSTR MSG_PREHEAT_M_END = _UxGT("Preris.ugello $");
|
||||
LSTR MSG_PREHEAT_M_END_E = _UxGT("Preris.ugello ~ $");
|
||||
LSTR MSG_PREHEAT_M_ALL = _UxGT("Preris.tutto $");
|
||||
LSTR MSG_PREHEAT_M_BEDONLY = _UxGT("Preris.piatto $");
|
||||
LSTR MSG_PREHEAT_M_CHAMBER = _UxGT("Preris.camera $");
|
||||
LSTR MSG_PREHEAT_M_SETTINGS = _UxGT("Preris.conf $");
|
||||
|
||||
LSTR MSG_PREHEAT_HOTEND = _UxGT("Prerisc.ugello");
|
||||
LSTR MSG_PREHEAT_CUSTOM = _UxGT("Prerisc.personal.");
|
||||
|
|
@ -161,6 +171,7 @@ namespace LanguageNarrow_it {
|
|||
LSTR MSG_SPINDLE_REVERSE = _UxGT("Inverti mandrino");
|
||||
LSTR MSG_SWITCH_PS_ON = _UxGT("Accendi aliment.");
|
||||
LSTR MSG_SWITCH_PS_OFF = _UxGT("Spegni aliment.");
|
||||
LSTR MSG_POWER_EDM_FAULT = _UxGT("Anomalia alim.EDM");
|
||||
LSTR MSG_EXTRUDE = _UxGT("Estrudi");
|
||||
LSTR MSG_RETRACT = _UxGT("Ritrai");
|
||||
LSTR MSG_MOVE_AXIS = _UxGT("Muovi asse");
|
||||
|
|
@ -178,6 +189,7 @@ namespace LanguageNarrow_it {
|
|||
LSTR MSG_MESH_VIEWER = _UxGT("Visualiz. mesh");
|
||||
LSTR MSG_EDIT_MESH = _UxGT("Modifica mesh");
|
||||
LSTR MSG_MESH_VIEW = _UxGT("Visualizza mesh");
|
||||
LSTR MSG_MESH_VIEW_GRID = _UxGT("Vis.mesh (griglia)");
|
||||
LSTR MSG_EDITING_STOPPED = _UxGT("Modif. mesh fermata");
|
||||
LSTR MSG_NO_VALID_MESH = _UxGT("Mesh non valida");
|
||||
LSTR MSG_ACTIVATE_MESH = _UxGT("Attiva livellamento");
|
||||
|
|
@ -201,7 +213,9 @@ namespace LanguageNarrow_it {
|
|||
LSTR MSG_M48_TEST = _UxGT("Test sonda M48");
|
||||
LSTR MSG_M48_POINT = _UxGT("Punto M48");
|
||||
LSTR MSG_M48_OUT_OF_BOUNDS = _UxGT("Sonda oltre i limiti");
|
||||
LSTR MSG_M48_DEV = _UxGT("Dev");
|
||||
LSTR MSG_M48_DEVIATION = _UxGT("Deviazione");
|
||||
LSTR MSG_M48_MAX_DELTA = _UxGT("Delta max");
|
||||
LSTR MSG_IDEX_MENU = _UxGT("Modo IDEX");
|
||||
LSTR MSG_OFFSETS_MENU = _UxGT("Strumenti offsets");
|
||||
LSTR MSG_IDEX_MODE_AUTOPARK = _UxGT("Auto-Park");
|
||||
|
|
@ -327,7 +341,7 @@ namespace LanguageNarrow_it {
|
|||
LSTR MSG_MOVE_N_MM = _UxGT("Muovi di $mm");
|
||||
LSTR MSG_MOVE_N_IN = _UxGT("Muovi di $in");
|
||||
LSTR MSG_MOVE_N_DEG = _UxGT("Muovi di $") LCD_STR_DEGREE;
|
||||
LSTR MSG_LIVE_MOVE = _UxGT("Modalità live");
|
||||
LSTR MSG_LIVE_MOVE = _UxGT("Movimento live");
|
||||
LSTR MSG_SPEED = _UxGT("Velocità");
|
||||
LSTR MSG_MESH_Z_OFFSET = _UxGT("Piatto Z");
|
||||
LSTR MSG_NOZZLE = _UxGT("Ugello");
|
||||
|
|
@ -428,6 +442,7 @@ namespace LanguageNarrow_it {
|
|||
LSTR MSG_AMAX_EN = _UxGT("Acc.massima *");
|
||||
LSTR MSG_A_RETRACT = _UxGT("A-Ritrazione");
|
||||
LSTR MSG_A_TRAVEL = _UxGT("A-Spostamento");
|
||||
LSTR MSG_A_SPINDLE = _UxGT("Acc.mandrino");
|
||||
LSTR MSG_INPUT_SHAPING = _UxGT("Input shaping");
|
||||
LSTR MSG_SHAPING_ENABLE_N = _UxGT("Abilita shaping @");
|
||||
LSTR MSG_SHAPING_DISABLE_N = _UxGT("Disabil. shaping @");
|
||||
|
|
@ -466,8 +481,10 @@ namespace LanguageNarrow_it {
|
|||
LSTR MSG_DRAW_MAX_Y = _UxGT("Max Y area disegno");
|
||||
LSTR MSG_MAX_BELT_LEN = _UxGT("Lungh.max cinghia");
|
||||
LSTR MSG_LINEAR_ADVANCE = _UxGT("Avanzam.lineare");
|
||||
LSTR MSG_ADVANCE_K = _UxGT("K Avanzamento");
|
||||
LSTR MSG_ADVANCE_K_E = _UxGT("K Avanzamento *");
|
||||
LSTR MSG_ADVANCE_K = _UxGT("K advance");
|
||||
LSTR MSG_ADVANCE_TAU = _UxGT("Tau advance");
|
||||
LSTR MSG_ADVANCE_K_E = _UxGT("K advance *");
|
||||
LSTR MSG_ADVANCE_TAU_E = _UxGT("Tau advance *");
|
||||
LSTR MSG_CONTRAST = _UxGT("Contrasto LCD");
|
||||
LSTR MSG_BRIGHTNESS = _UxGT("Luminosità LCD");
|
||||
LSTR MSG_SCREEN_TIMEOUT = _UxGT("Timeout LCD (m)");
|
||||
|
|
@ -533,10 +550,8 @@ namespace LanguageNarrow_it {
|
|||
LSTR MSG_CANCEL_OBJECT = _UxGT("Cancella oggetto");
|
||||
LSTR MSG_CANCEL_OBJECT_N = _UxGT("Canc. oggetto {");
|
||||
LSTR MSG_CONTINUE_PRINT_JOB = _UxGT("Cont.proc.stampa");
|
||||
LSTR MSG_MEDIA_MENU = _UxGT("Stampa da ") MEDIA_TYPE_IT;
|
||||
LSTR MSG_TURN_OFF = _UxGT("Spegni stampante");
|
||||
LSTR MSG_END_LOOPS = _UxGT("Fine cicli di rip.");
|
||||
LSTR MSG_NO_MEDIA = MEDIA_TYPE_IT _UxGT(" non presente");
|
||||
LSTR MSG_DWELL = _UxGT("Sospensione...");
|
||||
LSTR MSG_USERWAIT = _UxGT("Premi tasto..");
|
||||
LSTR MSG_PRINT_PAUSED = _UxGT("Stampa sospesa");
|
||||
|
|
@ -590,10 +605,20 @@ namespace LanguageNarrow_it {
|
|||
|
||||
LSTR MSG_ATTACH_MEDIA = _UxGT("Collega ") MEDIA_TYPE_IT;
|
||||
LSTR MSG_ATTACH_SD = _UxGT("Collega scheda SD");
|
||||
LSTR MSG_ATTACH_USB = _UxGT("Collega penna USB");
|
||||
LSTR MSG_CHANGE_MEDIA = _UxGT("Cambia ") MEDIA_TYPE_IT;
|
||||
LSTR MSG_ATTACH_USB = _UxGT("Collega unità USB");
|
||||
LSTR MSG_RELEASE_MEDIA = _UxGT("Rilascia ") MEDIA_TYPE_IT;
|
||||
LSTR MSG_RUN_AUTOFILES = _UxGT("Esegui files auto");
|
||||
LSTR MSG_RELEASE_SD = _UxGT("Rilascia scheda SD");
|
||||
LSTR MSG_RELEASE_USB = _UxGT("Rilascia unità USB");
|
||||
LSTR MSG_CHANGE_MEDIA = _UxGT("Selez.") MEDIA_TYPE_IT;
|
||||
LSTR MSG_CHANGE_SD = _UxGT("Selez. scheda SD");
|
||||
LSTR MSG_CHANGE_USB = _UxGT("Selez. unità USB");
|
||||
LSTR MSG_RUN_AUTOFILES = _UxGT("Esegui Autofiles");
|
||||
LSTR MSG_RUN_AUTOFILES_SD = _UxGT("Esegui Autofiles SD");
|
||||
LSTR MSG_RUN_AUTOFILES_USB = _UxGT("Esegui Autofiles USB");
|
||||
LSTR MSG_MEDIA_MENU = _UxGT("Stampa da ") MEDIA_TYPE_IT;
|
||||
LSTR MSG_MEDIA_MENU_SD = _UxGT("Selez. da SD");
|
||||
LSTR MSG_MEDIA_MENU_USB = _UxGT("Selez. da USB");
|
||||
LSTR MSG_NO_MEDIA = MEDIA_TYPE_IT _UxGT(" non rilevato");
|
||||
|
||||
LSTR MSG_ZPROBE_OUT = _UxGT("Z probe fuori piatto");
|
||||
LSTR MSG_SKEW_FACTOR = _UxGT("Fattore distorsione");
|
||||
|
|
@ -849,6 +874,7 @@ namespace LanguageNarrow_it {
|
|||
LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("Spurgo filamento"));
|
||||
LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Premi x terminare"));
|
||||
LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Ripresa..."));
|
||||
|
||||
LSTR MSG_TMC_DRIVERS = _UxGT("Driver TMC");
|
||||
LSTR MSG_TMC_CURRENT = _UxGT("Corrente driver");
|
||||
LSTR MSG_TMC_ACURRENT = _UxGT("Corrente driver ") STR_A;
|
||||
|
|
@ -859,6 +885,7 @@ namespace LanguageNarrow_it {
|
|||
LSTR MSG_TMC_HOMING_THRS = _UxGT("Sensorless homing");
|
||||
LSTR MSG_TMC_STEPPING_MODE = _UxGT("Modo Stepping");
|
||||
LSTR MSG_TMC_STEALTHCHOP = _UxGT("StealthChop");
|
||||
LSTR MSG_TMC_HOMING_CURRENT = _UxGT("Corrente homing");
|
||||
|
||||
LSTR MSG_SERVICE_RESET = _UxGT("Resetta");
|
||||
LSTR MSG_SERVICE_IN = _UxGT(" tra:");
|
||||
|
|
@ -898,6 +925,7 @@ namespace LanguageNarrow_it {
|
|||
LSTR MSG_BOTTOM_LEFT = _UxGT("Basso sinistra");
|
||||
LSTR MSG_TOP_RIGHT = _UxGT("Alto destra");
|
||||
LSTR MSG_BOTTOM_RIGHT = _UxGT("Basso destra");
|
||||
LSTR MSG_TOUCH_CALIBRATION = _UxGT("Calibrazione touch");
|
||||
LSTR MSG_CALIBRATION_COMPLETED = _UxGT("Calibrazione completata");
|
||||
LSTR MSG_CALIBRATION_FAILED = _UxGT("Calibrazione fallita");
|
||||
|
||||
|
|
@ -908,7 +936,7 @@ namespace LanguageNarrow_it {
|
|||
|
||||
LSTR MSG_HOST_SHUTDOWN = _UxGT("Arresta host");
|
||||
|
||||
// DGUS-Specific message strings, not used elsewhere
|
||||
// DGUS-Specific message strings, not used elsewhere
|
||||
LSTR DGUS_MSG_NOT_WHILE_PRINTING = _UxGT("Non ammesso durante la stampa");
|
||||
LSTR DGUS_MSG_NOT_WHILE_IDLE = _UxGT("Non ammesso mentre è in riposo");
|
||||
LSTR DGUS_MSG_NO_FILE_SELECTED = _UxGT("Nessun file selezionato");
|
||||
|
|
@ -940,6 +968,41 @@ namespace LanguageNarrow_it {
|
|||
LSTR MSG_BTN_STOP = _UxGT("Stop");
|
||||
LSTR MSG_BTN_DISABLE_MMU = _UxGT("Disabilita");
|
||||
LSTR MSG_BTN_MORE = _UxGT("Più info");
|
||||
|
||||
// Prusa MMU
|
||||
LSTR MSG_DONE = _UxGT("Eseguito");
|
||||
LSTR MSG_FINISHING_MOVEMENTS = _UxGT("Termina movimenti");
|
||||
LSTR MSG_LOADING_FILAMENT = _UxGT("Carica. filamento");
|
||||
LSTR MSG_UNLOADING_FILAMENT = _UxGT("Scarico filamento");
|
||||
LSTR MSG_TESTING_FILAMENT = _UxGT("Testando filamento");
|
||||
LSTR MSG_EJECT_FROM_MMU = _UxGT("Espelli da MMU");
|
||||
LSTR MSG_CUT_FILAMENT = _UxGT("Taglia filamento");
|
||||
LSTR MSG_OFF = _UxGT("Off");
|
||||
LSTR MSG_ON = _UxGT("On");
|
||||
LSTR MSG_PROGRESS_OK = _UxGT("OK");
|
||||
LSTR MSG_PROGRESS_ENGAGE_IDLER = _UxGT("Innesto idler");
|
||||
LSTR MSG_PROGRESS_DISENGAGE_IDLER = _UxGT("Disinnesto idler");
|
||||
LSTR MSG_PROGRESS_UNLOAD_FINDA = _UxGT("Scarico a FINDA");
|
||||
LSTR MSG_PROGRESS_UNLOAD_PULLEY = _UxGT("Scarico a puleggia");
|
||||
LSTR MSG_PROGRESS_FEED_FINDA = _UxGT("Alim. a FINDA");
|
||||
LSTR MSG_PROGRESS_FEED_EXTRUDER = _UxGT("Alim. all'estrusore");
|
||||
LSTR MSG_PROGRESS_FEED_NOZZLE = _UxGT("Alim. all'ugello");
|
||||
LSTR MSG_PROGRESS_AVOID_GRIND = _UxGT("Evita grind");
|
||||
LSTR MSG_PROGRESS_WAIT_USER = _UxGT("ERR attesa utente");
|
||||
LSTR MSG_PROGRESS_ERR_INTERNAL = _UxGT("ERR interno");
|
||||
LSTR MSG_PROGRESS_ERR_HELP_FIL = _UxGT("ERR aiuto filamento");
|
||||
LSTR MSG_PROGRESS_ERR_TMC = _UxGT("ERR anomalia TMC");
|
||||
LSTR MSG_PROGRESS_SELECT_SLOT = _UxGT("Selez.slot filam.");
|
||||
LSTR MSG_PROGRESS_PREPARE_BLADE = _UxGT("Preparaz.lama");
|
||||
LSTR MSG_PROGRESS_PUSH_FILAMENT = _UxGT("Spinta fialmento");
|
||||
LSTR MSG_PROGRESS_PERFORM_CUT = _UxGT("Esecuzione taglio");
|
||||
LSTR MSG_PROGRESSPSTRETURN_SELECTOR = _UxGT("Ritorno selettore");
|
||||
LSTR MSG_PROGRESS_PARK_SELECTOR = _UxGT("Parcheggio selettore");
|
||||
LSTR MSG_PROGRESS_EJECT_FILAMENT = _UxGT("Esplusione filamento");
|
||||
LSTR MSG_PROGRESSPSTRETRACT_FINDA = _UxGT("Ritrai a FINDA");
|
||||
LSTR MSG_PROGRESS_HOMING = _UxGT("Homing");
|
||||
LSTR MSG_PROGRESS_MOVING_SELECTOR = _UxGT("Movim. selettore");
|
||||
LSTR MSG_PROGRESS_FEED_FSENSOR = _UxGT("Alim. a FSensor");
|
||||
}
|
||||
|
||||
namespace LanguageWide_it {
|
||||
|
|
@ -950,7 +1013,10 @@ namespace LanguageWide_it {
|
|||
LSTR MSG_CANCEL_OBJECT = _UxGT("Cancella oggetto");
|
||||
LSTR MSG_CANCEL_OBJECT_N = _UxGT("Cancella oggetto {");
|
||||
LSTR MSG_CONTINUE_PRINT_JOB = _UxGT("Continua il job di stampa");
|
||||
LSTR MSG_MEDIA_MENU = _UxGT("Selez.da supporto");
|
||||
LSTR MSG_MEDIA_MENU = _UxGT("Seleziona da ") MEDIA_TYPE_IT;
|
||||
LSTR MSG_MEDIA_MENU_SD = _UxGT("Seleziona da scheda SD");
|
||||
LSTR MSG_MEDIA_MENU_USB = _UxGT("Seleziona da unità USB");
|
||||
LSTR MSG_NO_MEDIA = MEDIA_TYPE_EN _UxGT(" non trovato");
|
||||
LSTR MSG_TURN_OFF = _UxGT("Spegni la stampante");
|
||||
LSTR MSG_END_LOOPS = _UxGT("Termina i cicli di ripetizione");
|
||||
LSTR MSG_MEDIA_NOT_INSERTED = _UxGT("Nessun supporto inserito."); // ProUI
|
||||
|
|
@ -960,7 +1026,13 @@ namespace LanguageWide_it {
|
|||
LSTR MSG_INFO_PRINT_TIME = _UxGT("Tempo totale");
|
||||
LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Lavoro più lungo");
|
||||
LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Totale estruso");
|
||||
LSTR MSG_TEMP_TOO_LOW = _UxGT("Temperatura troppo bassa");
|
||||
LSTR MSG_HOMING_FEEDRATE_N = _UxGT("Velocità @ di homing");
|
||||
LSTR MSG_HOMING_FEEDRATE_X = _UxGT("Velocità X di homing");
|
||||
LSTR MSG_HOMING_FEEDRATE_Y = _UxGT("Velocità Y di homing");
|
||||
LSTR MSG_HOMING_FEEDRATE_Z = _UxGT("Velocità Z di homing");
|
||||
LSTR MSG_EEPROM_INITIALIZED = _UxGT("Ripristinate impostazioni predefinite");
|
||||
LSTR MSG_PREHEAT_M_CHAMBER = _UxGT("Preriscalda camera per $");
|
||||
LSTR MSG_PREHEAT_M_SETTINGS = _UxGT("Configurazioni preriscaldo $");
|
||||
#endif
|
||||
}
|
||||
|
||||
|
|
|
|||
|
|
@ -48,14 +48,15 @@ namespace LanguageNarrow_pl {
|
|||
LSTR MSG_YES = _UxGT("TAK");
|
||||
LSTR MSG_NO = _UxGT("NIE");
|
||||
LSTR MSG_BACK = _UxGT("Wstecz");
|
||||
|
||||
LSTR MSG_MEDIA_ABORTING = _UxGT("Przerywanie...");
|
||||
LSTR MSG_MEDIA_INSERTED = _UxGT("Karta włożona");
|
||||
LSTR MSG_MEDIA_REMOVED = _UxGT("Karta usunięta");
|
||||
LSTR MSG_MEDIA_WAITING = _UxGT("Oczekiwanie na kartę");
|
||||
LSTR MSG_MEDIA_INIT_FAIL = _UxGT("Błąd inicializacji karty");
|
||||
LSTR MSG_MEDIA_READ_ERROR = _UxGT("Bład odczytu karty");
|
||||
LSTR MSG_MEDIA_USB_REMOVED = _UxGT("Urządzenie USB usunięte");
|
||||
LSTR MSG_MEDIA_USB_FAILED = _UxGT("Błąd uruchomienia USB");
|
||||
LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("Urządzenie USB usunięte");
|
||||
LSTR MSG_USB_FD_USB_FAILED = _UxGT("Błąd uruchomienia USB");
|
||||
|
||||
LSTR MSG_LCD_ENDSTOPS = _UxGT("Krańców."); // Max length 8 characters
|
||||
LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Progr. Krańcówki");
|
||||
LSTR MSG_MAIN_MENU = _UxGT("Menu główne");
|
||||
|
|
|
|||
|
|
@ -38,13 +38,14 @@ namespace LanguageNarrow_pt_br {
|
|||
LSTR MSG_YES = _UxGT("SIM");
|
||||
LSTR MSG_NO = _UxGT("NÃO");
|
||||
LSTR MSG_BACK = _UxGT("Voltar");
|
||||
|
||||
LSTR MSG_MEDIA_ABORTING = _UxGT("Abortando...");
|
||||
LSTR MSG_MEDIA_INSERTED = _UxGT("Cartão inserido");
|
||||
LSTR MSG_MEDIA_REMOVED = _UxGT("Cartão removido");
|
||||
LSTR MSG_MEDIA_WAITING = _UxGT("Aguardando cartão");
|
||||
LSTR MSG_MEDIA_READ_ERROR = _UxGT("Erro de leitura");
|
||||
LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB removido");
|
||||
LSTR MSG_MEDIA_USB_FAILED = _UxGT("USB falhou");
|
||||
LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("USB removido");
|
||||
LSTR MSG_USB_FD_USB_FAILED = _UxGT("USB falhou");
|
||||
|
||||
LSTR MSG_LCD_ENDSTOPS = _UxGT("Fins de curso");
|
||||
LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Soft Fins curso");
|
||||
LSTR MSG_MAIN_MENU = _UxGT("Menu principal");
|
||||
|
|
|
|||
|
|
@ -39,14 +39,15 @@ namespace LanguageNarrow_ro {
|
|||
LSTR MSG_YES = _UxGT("DA");
|
||||
LSTR MSG_NO = _UxGT("NU");
|
||||
LSTR MSG_BACK = _UxGT("Inapoi");
|
||||
|
||||
LSTR MSG_MEDIA_ABORTING = _UxGT("Abandon...");
|
||||
LSTR MSG_MEDIA_INSERTED = _UxGT("Media Introdus");
|
||||
LSTR MSG_MEDIA_REMOVED = _UxGT("Media Inlaturat");
|
||||
LSTR MSG_MEDIA_WAITING = _UxGT("Astept Media");
|
||||
LSTR MSG_MEDIA_READ_ERROR = _UxGT("Eroare Citire Media");
|
||||
LSTR MSG_MEDIA_USB_REMOVED = _UxGT("Dispozitiv USB Inlaturat");
|
||||
LSTR MSG_MEDIA_USB_FAILED = _UxGT("Pornire USB Esuata");
|
||||
LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("Dispozitiv USB Inlaturat");
|
||||
LSTR MSG_USB_FD_USB_FAILED = _UxGT("Pornire USB Esuata");
|
||||
LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Eroare:Subcall Overflow");
|
||||
|
||||
LSTR MSG_LCD_ENDSTOPS = _UxGT("Endstops"); // Max length 8 characters
|
||||
LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Soft Endstops");
|
||||
LSTR MSG_MAIN_MENU = _UxGT("Principal");
|
||||
|
|
|
|||
|
|
@ -39,16 +39,17 @@ namespace LanguageNarrow_ru {
|
|||
LSTR MSG_YES = _UxGT("Да");
|
||||
LSTR MSG_NO = _UxGT("Нет");
|
||||
LSTR MSG_BACK = _UxGT("Назад");
|
||||
|
||||
LSTR MSG_MEDIA_ABORTING = _UxGT("Прерывание...");
|
||||
LSTR MSG_MEDIA_INSERTED = _UxGT("SD карта вставлена");
|
||||
LSTR MSG_MEDIA_REMOVED = _UxGT("SD карта извлечена");
|
||||
LSTR MSG_MEDIA_WAITING = _UxGT("Вставьте SD карту");
|
||||
LSTR MSG_MEDIA_INIT_FAIL = _UxGT("Сбой инициализ. SD");
|
||||
LSTR MSG_ADVANCED_SETTINGS = _UxGT("Расшир. настройки");
|
||||
LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Переполн. вызова");
|
||||
LSTR MSG_MEDIA_READ_ERROR = _UxGT("Ошибка чтения");
|
||||
LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB диск удалён");
|
||||
LSTR MSG_MEDIA_USB_FAILED = _UxGT("Ошибка USB диска");
|
||||
LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("USB диск удалён");
|
||||
LSTR MSG_USB_FD_USB_FAILED = _UxGT("Ошибка USB диска");
|
||||
|
||||
LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Прогр. концевики");
|
||||
LSTR MSG_LCD_ENDSTOPS = _UxGT("Концевик"); // Max length 8 characters
|
||||
LSTR MSG_MAIN_MENU = _UxGT("Главное меню");
|
||||
|
|
|
|||
|
|
@ -54,14 +54,15 @@ namespace LanguageNarrow_sk {
|
|||
LSTR MSG_LOW = _UxGT("NÍZKA");
|
||||
LSTR MSG_BACK = _UxGT("Naspäť");
|
||||
LSTR MSG_ERROR = _UxGT("Chyba");
|
||||
|
||||
LSTR MSG_MEDIA_ABORTING = _UxGT("Ruším...");
|
||||
LSTR MSG_MEDIA_INSERTED = _UxGT("Karta vložená");
|
||||
LSTR MSG_MEDIA_REMOVED = _UxGT("Karta vybraná");
|
||||
LSTR MSG_MEDIA_WAITING = _UxGT("Čakám na kartu");
|
||||
LSTR MSG_MEDIA_INIT_FAIL = _UxGT("Inicial.karty zlyhala");
|
||||
LSTR MSG_MEDIA_READ_ERROR = _UxGT("Chyba čítania karty");
|
||||
LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB zaria. odstrán.");
|
||||
LSTR MSG_MEDIA_USB_FAILED = _UxGT("Chyba spúšťania USB");
|
||||
LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("USB zaria. odstrán.");
|
||||
LSTR MSG_USB_FD_USB_FAILED = _UxGT("Chyba spúšťania USB");
|
||||
|
||||
LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Preteč. podprogramu");
|
||||
LSTR MSG_LCD_ENDSTOPS = _UxGT("Endstopy"); // max 8 znakov
|
||||
LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Soft. endstopy");
|
||||
|
|
|
|||
|
|
@ -40,15 +40,16 @@ namespace LanguageNarrow_sv {
|
|||
LSTR MSG_YES = _UxGT("JA");
|
||||
LSTR MSG_NO = _UxGT("NEJ");
|
||||
LSTR MSG_BACK = _UxGT("Bakåt");
|
||||
|
||||
LSTR MSG_MEDIA_ABORTING = _UxGT("Avbryter...");
|
||||
LSTR MSG_MEDIA_INSERTED = _UxGT("Media Instatt");
|
||||
LSTR MSG_MEDIA_REMOVED = _UxGT("Media Borttaget");
|
||||
LSTR MSG_MEDIA_WAITING = _UxGT("Väntar på media");
|
||||
LSTR MSG_MEDIA_INIT_FAIL = _UxGT("Media init misslyckades");
|
||||
LSTR MSG_MEDIA_READ_ERROR = _UxGT("Media läsningsfel");
|
||||
LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB enhet borttagen");
|
||||
LSTR MSG_MEDIA_USB_FAILED = _UxGT("USB start misslyckad");
|
||||
LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("USB enhet borttagen");
|
||||
LSTR MSG_USB_FD_USB_FAILED = _UxGT("USB start misslyckad");
|
||||
LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Underanrop överskriden");
|
||||
|
||||
LSTR MSG_LCD_ENDSTOPS = _UxGT("Slutstop"); // Max length 8 characters
|
||||
LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Mjuk slutstopp");
|
||||
LSTR MSG_MAIN_MENU = _UxGT("Huvud");
|
||||
|
|
|
|||
|
|
@ -52,17 +52,18 @@ namespace LanguageNarrow_tr {
|
|||
LSTR MSG_LOW = _UxGT("DÜŞÜK");
|
||||
LSTR MSG_BACK = _UxGT("Geri");
|
||||
LSTR MSG_ERROR = _UxGT("Hata");
|
||||
|
||||
LSTR MSG_MEDIA_ABORTING = _UxGT("Durduruluyor...");
|
||||
LSTR MSG_MEDIA_INSERTED = _UxGT("SD K. Yerleştirildi.");
|
||||
LSTR MSG_MEDIA_REMOVED = _UxGT("SD Kart Çıkarıldı.");
|
||||
LSTR MSG_MEDIA_WAITING = _UxGT("SD Kart Bekleniyor");
|
||||
LSTR MSG_MEDIA_INIT_FAIL = _UxGT("SD K. Başlatma Hatası");
|
||||
LSTR MSG_MEDIA_READ_ERROR = _UxGT("Kart Okuma Hatası");
|
||||
LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB Çıkarıldı");
|
||||
LSTR MSG_MEDIA_USB_FAILED = _UxGT("USB Başlat. Hatası");
|
||||
LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("USB Çıkarıldı");
|
||||
LSTR MSG_USB_FD_USB_FAILED = _UxGT("USB Başlat. Hatası");
|
||||
LSTR MSG_MEDIA_SORT = _UxGT("Medyayı Sırala");
|
||||
LSTR MSG_MEDIA_UPDATE = _UxGT("Medyayı Güncelle");
|
||||
LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Subcall Overflow");
|
||||
|
||||
LSTR MSG_LCD_ENDSTOPS = _UxGT("Endstops"); // Max length 8 characters
|
||||
LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Soft Endstops");
|
||||
LSTR MSG_MAIN_MENU = _UxGT("Ana");
|
||||
|
|
@ -888,7 +889,6 @@ namespace LanguageNarrow_tr {
|
|||
namespace LanguageWide_tr {
|
||||
using namespace LanguageNarrow_tr;
|
||||
#if LCD_WIDTH >= 20 || HAS_DWIN_E3V2
|
||||
LSTR MSG_LIVE_MOVE = _UxGT("Canlı Hareket");
|
||||
LSTR MSG_HOST_START_PRINT = _UxGT("Host Baskıyı başlat");
|
||||
LSTR MSG_PRINTING_OBJECT = _UxGT("Yazdırma Nesnesi");
|
||||
LSTR MSG_CANCEL_OBJECT = _UxGT("Nesneyi İptal Et");
|
||||
|
|
|
|||
|
|
@ -40,15 +40,16 @@ namespace LanguageNarrow_uk {
|
|||
LSTR MSG_YES = _UxGT("ТАК");
|
||||
LSTR MSG_NO = _UxGT("НІ");
|
||||
LSTR MSG_BACK = _UxGT("Назад");
|
||||
|
||||
LSTR MSG_MEDIA_ABORTING = _UxGT("Переривання...");
|
||||
LSTR MSG_MEDIA_INSERTED = _UxGT("SD-картка вставлена");
|
||||
LSTR MSG_MEDIA_REMOVED = _UxGT("SD-картка видалена");
|
||||
LSTR MSG_MEDIA_WAITING = _UxGT("Вставте SD-картку");
|
||||
LSTR MSG_MEDIA_INIT_FAIL = _UxGT("Збій ініціаліз. SD");
|
||||
LSTR MSG_MEDIA_READ_ERROR = _UxGT("Помилка зчитування");
|
||||
LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB диск видалений");
|
||||
LSTR MSG_MEDIA_USB_FAILED = _UxGT("Помилка USB диску");
|
||||
LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("USB диск видалений");
|
||||
LSTR MSG_USB_FD_USB_FAILED = _UxGT("Помилка USB диску");
|
||||
LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Переповн. виклику");
|
||||
|
||||
LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Прогр.кінцевики");
|
||||
LSTR MSG_LCD_ENDSTOPS = _UxGT("Кінцевик"); // Max length 8 characters
|
||||
LSTR MSG_MAIN_MENU = _UxGT("Основне меню");
|
||||
|
|
|
|||
|
|
@ -35,13 +35,14 @@ namespace LanguageNarrow_vi {
|
|||
|
||||
LSTR WELCOME_MSG = MACHINE_NAME_SUBST _UxGT(" Sẵn sàng."); // Ready
|
||||
LSTR MSG_BACK = _UxGT("Trở lại"); // Back
|
||||
|
||||
LSTR MSG_MEDIA_ABORTING = _UxGT("Đang hủy bỏ...");
|
||||
LSTR MSG_MEDIA_INSERTED = _UxGT("Phương tiện được cắm vào"); // Media inserted
|
||||
LSTR MSG_MEDIA_REMOVED = _UxGT("Phương tiện được rút ra");
|
||||
LSTR MSG_MEDIA_WAITING = _UxGT("Chờ đợi phương tiện");
|
||||
LSTR MSG_MEDIA_READ_ERROR = _UxGT("Lỗi đọc phương tiện");
|
||||
LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB được rút ra");
|
||||
LSTR MSG_MEDIA_USB_FAILED = _UxGT("USB khởi thất bại");
|
||||
LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("USB được rút ra");
|
||||
LSTR MSG_USB_FD_USB_FAILED = _UxGT("USB khởi thất bại");
|
||||
|
||||
LSTR MSG_LCD_ENDSTOPS = _UxGT("Công tắc"); // Endstops - công tắc hành trình
|
||||
LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Công tắc mềm"); // Soft Endstops
|
||||
LSTR MSG_MAIN_MENU = _UxGT("Chính"); // Main
|
||||
|
|
|
|||
|
|
@ -41,14 +41,15 @@ namespace LanguageNarrow_zh_CN {
|
|||
LSTR MSG_LOW = _UxGT("低");
|
||||
LSTR MSG_BACK = _UxGT("返回"); // ”Back“
|
||||
LSTR MSG_ERROR = _UxGT("错误");
|
||||
|
||||
LSTR MSG_MEDIA_ABORTING = _UxGT("存储卡中止...");
|
||||
LSTR MSG_MEDIA_INSERTED = _UxGT("存储卡已插入"); // "Card inserted"
|
||||
LSTR MSG_MEDIA_REMOVED = _UxGT("存储卡被拔出"); // "Card removed"
|
||||
LSTR MSG_MEDIA_WAITING = _UxGT("等待存储器");
|
||||
LSTR MSG_MEDIA_READ_ERROR = _UxGT("卡读卡器错误");
|
||||
LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB设备已弹出");
|
||||
LSTR MSG_MEDIA_USB_FAILED = _UxGT("USB读取失败");
|
||||
LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("USB设备已弹出");
|
||||
LSTR MSG_USB_FD_USB_FAILED = _UxGT("USB读取失败");
|
||||
LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("子响应溢出");
|
||||
|
||||
LSTR MSG_LCD_ENDSTOPS = _UxGT("挡块"); // "Endstops" // Max length 8 characters
|
||||
LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("软挡块");
|
||||
LSTR MSG_MAIN_MENU = _UxGT("主菜单"); // "Main"
|
||||
|
|
|
|||
|
|
@ -37,13 +37,14 @@ namespace LanguageNarrow_zh_TW {
|
|||
LSTR MSG_YES = _UxGT("是"); // "YES"
|
||||
LSTR MSG_NO = _UxGT("否"); // "NO"
|
||||
LSTR MSG_BACK = _UxGT("返回"); // "Back"
|
||||
|
||||
LSTR MSG_MEDIA_ABORTING = _UxGT("正在中止..."); // "Aborting..."
|
||||
LSTR MSG_MEDIA_INSERTED = _UxGT("記憶卡已插入"); // "Card inserted"
|
||||
LSTR MSG_MEDIA_REMOVED = _UxGT("記憶卡被拔出"); // "Card removed"
|
||||
LSTR MSG_MEDIA_WAITING = _UxGT("等待記憶卡"); // "Waiting for media"
|
||||
LSTR MSG_MEDIA_READ_ERROR = _UxGT("記憶卡讀取錯誤"); //"Media read error"
|
||||
LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB裝置已移除"); // "USB device removed"
|
||||
LSTR MSG_MEDIA_USB_FAILED = _UxGT("USB啟動失敗"); // "USB start failed"
|
||||
LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("USB裝置已移除"); // "USB device removed"
|
||||
LSTR MSG_USB_FD_USB_FAILED = _UxGT("USB啟動失敗"); // "USB start failed"
|
||||
|
||||
LSTR MSG_LCD_ENDSTOPS = _UxGT("擋塊"); // "Endstops" // Max length 8 characters
|
||||
LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("軟體擋塊"); // "Soft Endstops"
|
||||
LSTR MSG_MAIN_MENU = _UxGT("主選單"); // "Main"
|
||||
|
|
|
|||
|
|
@ -1957,7 +1957,7 @@ uint8_t expand_u8str_P(char * const outstr, PGM_P const ptpl, const int8_t ind,
|
|||
if ((old_status ^ status) & INSERT_SD)
|
||||
LCD_MESSAGE(MSG_MEDIA_REMOVED_SD);
|
||||
else if ((old_status ^ status) & INSERT_USB)
|
||||
LCD_MESSAGE(MSG_MEDIA_REMOVED_USB);
|
||||
LCD_MESSAGE(MSG_USB_FD_MEDIA_REMOVED);
|
||||
else
|
||||
LCD_MESSAGE(MSG_MEDIA_REMOVED);
|
||||
|
||||
|
|
|
|||
|
|
@ -1505,10 +1505,12 @@ void Planner::check_axes_activity() {
|
|||
|
||||
#if HAS_LEVELING
|
||||
|
||||
constexpr xy_pos_t level_fulcrum = {
|
||||
TERN(Z_SAFE_HOMING, Z_SAFE_HOMING_X_POINT, X_HOME_POS),
|
||||
TERN(Z_SAFE_HOMING, Z_SAFE_HOMING_Y_POINT, Y_HOME_POS)
|
||||
};
|
||||
#if ABL_PLANAR
|
||||
constexpr xy_pos_t level_fulcrum = {
|
||||
TERN(Z_SAFE_HOMING, Z_SAFE_HOMING_X_POINT, X_HOME_POS),
|
||||
TERN(Z_SAFE_HOMING, Z_SAFE_HOMING_Y_POINT, Y_HOME_POS)
|
||||
};
|
||||
#endif
|
||||
|
||||
/**
|
||||
* rx, ry, rz - Cartesian positions in mm
|
||||
|
|
|
|||
|
|
@ -249,7 +249,7 @@ typedef struct PlannerBlock {
|
|||
uint32_t cruise_time; // Cruise time in STEP timer counts
|
||||
int32_t e_step_ratio_q30; // Ratio of e steps to block steps.
|
||||
#if ENABLED(INPUT_SHAPING_E_SYNC)
|
||||
uint32_t xy_length_inv_q30; // inverse of block->steps.x + block.steps.y
|
||||
uint32_t xy_length_inv_q30; // Inverse of block->steps.x + block.steps.y
|
||||
#endif
|
||||
#endif
|
||||
#if ANY(S_CURVE_ACCELERATION, SMOOTH_LIN_ADVANCE)
|
||||
|
|
@ -370,7 +370,6 @@ typedef struct PlannerSettings {
|
|||
};
|
||||
#undef _EASU
|
||||
#undef _DASU
|
||||
#undef _DLIM
|
||||
#endif
|
||||
|
||||
feedRate_t max_feedrate_mm_s[DISTINCT_AXES]; // (mm/s) M203 XYZE - Max speeds
|
||||
|
|
|
|||
|
|
@ -654,7 +654,7 @@ typedef struct SettingsDataStruct {
|
|||
// Fixed-Time Motion
|
||||
//
|
||||
#if ENABLED(FT_MOTION)
|
||||
ft_config_t ftMotion_cfg; // M493
|
||||
ft_config_t ftMotion_cfg; // M493
|
||||
#endif
|
||||
|
||||
//
|
||||
|
|
|
|||
|
|
@ -1541,7 +1541,7 @@ void Stepper::isr() {
|
|||
uint8_t max_loops = 10;
|
||||
|
||||
#if ENABLED(FT_MOTION)
|
||||
static uint32_t ftMotion_nextAuxISR = 0U; // Storage for the next ISR of the auxilliary tasks.
|
||||
static uint32_t ftMotion_nextAuxISR = 0U; // Storage for the next ISR of the auxiliary tasks.
|
||||
const bool using_ftMotion = ftMotion.cfg.active;
|
||||
#else
|
||||
constexpr bool using_ftMotion = false;
|
||||
|
|
@ -1556,21 +1556,18 @@ void Stepper::isr() {
|
|||
#if ENABLED(FT_MOTION)
|
||||
|
||||
if (using_ftMotion) {
|
||||
if (!nextMainISR) { // Main ISR is ready to fire during this iteration?
|
||||
nextMainISR = FTM_MIN_TICKS; // Set to minimum interval (a limit on the top speed)
|
||||
ftMotion_stepper(); // Run FTM Stepping
|
||||
// Define 2.5 msec task for auxilliary functions.
|
||||
if (!ftMotion_nextAuxISR) {
|
||||
TERN_(BABYSTEPPING, if (babystep.has_steps()) babystepping_isr());
|
||||
ftMotion_nextAuxISR = (STEPPER_TIMER_RATE) / 400;
|
||||
}
|
||||
ftMotion_stepper(); // Run FTM Stepping
|
||||
|
||||
// Define 2.5 msec task for auxiliary functions.
|
||||
if (!ftMotion_nextAuxISR) {
|
||||
TERN_(BABYSTEPPING, if (babystep.has_steps()) babystepping_isr());
|
||||
ftMotion_nextAuxISR = (STEPPER_TIMER_RATE) / 400;
|
||||
}
|
||||
|
||||
// Enable ISRs to reduce latency for higher priority ISRs, or all ISRs if no prioritization.
|
||||
// Enable ISRs to reduce latency for higher priority ISRs
|
||||
hal.isr_on();
|
||||
|
||||
interval = _MIN(nextMainISR, ftMotion_nextAuxISR);
|
||||
nextMainISR -= interval;
|
||||
interval = FTM_MIN_TICKS;
|
||||
ftMotion_nextAuxISR -= interval;
|
||||
}
|
||||
|
||||
|
|
@ -2924,8 +2921,13 @@ hal_timer_t Stepper::block_phase_isr() {
|
|||
if (++index == IS_COMPENSATION_BUFFER_SIZE) index = 0;
|
||||
}
|
||||
FORCE_INLINE xy_long_t past_item(const uint16_t n) {
|
||||
const int16_t i = int16_t(index) - n;
|
||||
return buffer[i >= 0 ? i : i + IS_COMPENSATION_BUFFER_SIZE];
|
||||
int16_t i = int16_t(index) - n;
|
||||
if (i < 0) i += IS_COMPENSATION_BUFFER_SIZE;
|
||||
// The following only happens when IS Freq is set below the minimum
|
||||
// configured at build time ...in which case IS will also misbehave!
|
||||
// Using setters whenever possible prevents values being set too low.
|
||||
if (TERN0(MARLIN_DEV_MODE, i < 0)) return {0, 0};
|
||||
return buffer[i];
|
||||
}
|
||||
} DelayBuffer;
|
||||
|
||||
|
|
@ -2998,44 +3000,38 @@ hal_timer_t Stepper::block_phase_isr() {
|
|||
? MULT_Q(30, curr_step_rate, current_block->e_step_ratio_q30)
|
||||
: 0;
|
||||
|
||||
int32_t total_step_rate = la_step_rate + planned_step_rate;
|
||||
|
||||
#if ENABLED(INPUT_SHAPING_E_SYNC)
|
||||
|
||||
xy_long_t pre_shaping_rate = xy_long_t({0, 0}),
|
||||
first_pulse_rate = xy_long_t({0, 0});
|
||||
int32_t unshaped_rate_e = total_step_rate;
|
||||
if (current_block) {
|
||||
if (current_block->xy_length_inv_q30 > 0) {
|
||||
unshaped_rate_e = 0;
|
||||
int32_t unshaped_rate_e = la_step_rate + planned_step_rate;
|
||||
|
||||
pre_shaping_rate = xy_long_t({
|
||||
TERN0(INPUT_SHAPING_X, MULT_Q(30, total_step_rate * current_block->steps.x, current_block->xy_length_inv_q30)),
|
||||
TERN0(INPUT_SHAPING_Y, MULT_Q(30, total_step_rate * current_block->steps.y, current_block->xy_length_inv_q30))
|
||||
});
|
||||
xy_long_t pre_shaping_rate{0}, first_pulse_rate{0};
|
||||
if (current_block && current_block->xy_length_inv_q30 > 0) {
|
||||
pre_shaping_rate = xy_long_t({
|
||||
MULT_Q(30, unshaped_rate_e * current_block->steps.x, current_block->xy_length_inv_q30),
|
||||
MULT_Q(30, unshaped_rate_e * current_block->steps.y, current_block->xy_length_inv_q30)
|
||||
});
|
||||
unshaped_rate_e = 0;
|
||||
|
||||
first_pulse_rate = xy_long_t({
|
||||
TERN0(INPUT_SHAPING_X, (pre_shaping_rate.x * Stepper::shaping_x.factor1) >> 7),
|
||||
TERN0(INPUT_SHAPING_Y, (pre_shaping_rate.y * Stepper::shaping_y.factor1) >> 7)
|
||||
});
|
||||
}
|
||||
first_pulse_rate = xy_long_t({
|
||||
TERN_(INPUT_SHAPING_X, shaping_x.enabled ? (pre_shaping_rate.x * shaping_x.factor1) >> 7 :) pre_shaping_rate.x,
|
||||
TERN_(INPUT_SHAPING_Y, shaping_y.enabled ? (pre_shaping_rate.y * shaping_y.factor1) >> 7 :) pre_shaping_rate.y
|
||||
});
|
||||
}
|
||||
|
||||
const xy_long_t second_pulse_rate = {
|
||||
TERN0(INPUT_SHAPING_X, (smooth_lin_adv_lookback(ShapingQueue::get_delay_x()).x * Stepper::shaping_x.factor2)) >> 7,
|
||||
TERN0(INPUT_SHAPING_Y, (smooth_lin_adv_lookback(ShapingQueue::get_delay_y()).y * Stepper::shaping_y.factor2)) >> 7
|
||||
};
|
||||
const xy_long_t second_pulse_rate = xy_long_t({
|
||||
TERN0(INPUT_SHAPING_X, shaping_x.enabled ? (smooth_lin_adv_lookback(ShapingQueue::get_delay_x()).x * shaping_x.factor2) >> 7 : 0),
|
||||
TERN0(INPUT_SHAPING_Y, shaping_y.enabled ? (smooth_lin_adv_lookback(ShapingQueue::get_delay_y()).y * shaping_y.factor2) >> 7 : 0)
|
||||
});
|
||||
|
||||
delayBuffer.add(pre_shaping_rate);
|
||||
|
||||
const int32_t x = TERN0(INPUT_SHAPING_X, first_pulse_rate.x + second_pulse_rate.x),
|
||||
y = TERN0(INPUT_SHAPING_Y, first_pulse_rate.y + second_pulse_rate.y);
|
||||
set_la_interval(unshaped_rate_e + first_pulse_rate.x + second_pulse_rate.x + first_pulse_rate.y + second_pulse_rate.y);
|
||||
|
||||
total_step_rate = unshaped_rate_e + x + y;
|
||||
#else // !INPUT_SHAPING_E_SYNC
|
||||
|
||||
#endif // INPUT_SHAPING_E_SYNC
|
||||
set_la_interval(la_step_rate + planned_step_rate);
|
||||
|
||||
set_la_interval(total_step_rate);
|
||||
#endif
|
||||
|
||||
curr_timer_tick += SMOOTH_LIN_ADV_INTERVAL;
|
||||
return SMOOTH_LIN_ADV_INTERVAL;
|
||||
|
|
|
|||
|
|
@ -1104,6 +1104,10 @@ void Temperature::factory_reset() {
|
|||
|
||||
do_z_clearance(MPC_TUNING_END_Z, false);
|
||||
|
||||
#ifdef EVENT_GCODE_AFTER_MPC_TUNE
|
||||
gcode.process_subcommands_now(F(EVENT_GCODE_AFTER_MPC_TUNE));
|
||||
#endif
|
||||
|
||||
TERN_(TEMP_TUNING_MAINTAIN_FAN, adaptive_fan_slowing = true);
|
||||
}
|
||||
|
||||
|
|
@ -2456,11 +2460,6 @@ void Temperature::task() {
|
|||
UNUSED(ms);
|
||||
}
|
||||
|
||||
// For a 5V input the AD595 returns a value scaled with 10mV per °C. (Minimum input voltage is 5V.)
|
||||
#define TEMP_AD595(RAW) ((RAW) * (ADC_VREF_MV / 10) / float(HAL_ADC_RANGE) / (OVERSAMPLENR) * (TEMP_SENSOR_AD595_GAIN) + TEMP_SENSOR_AD595_OFFSET)
|
||||
// For a 5V input the AD8495 returns a value scaled with 5mV per °C. (Minimum input voltage is 2.7V.)
|
||||
#define TEMP_AD8495(RAW) ((RAW) * (ADC_VREF_MV / 5) / float(HAL_ADC_RANGE) / (OVERSAMPLENR) * (TEMP_SENSOR_AD8495_GAIN) + TEMP_SENSOR_AD8495_OFFSET)
|
||||
|
||||
/**
|
||||
* Bisect search for the range of the 'raw' value, then interpolate
|
||||
* proportionally between the under and over values.
|
||||
|
|
@ -2600,6 +2599,22 @@ void Temperature::task() {
|
|||
}
|
||||
#endif
|
||||
|
||||
#if ANY_THERMISTOR_IS(-1)
|
||||
// For a 5V input the AD595 returns a value scaled with 10mV per °C. (Minimum input voltage is 5V.)
|
||||
static constexpr celsius_float_t temp_ad595(const raw_adc_t raw) {
|
||||
return raw * (float(ADC_VREF_MV) / 10.0f) / float(HAL_ADC_RANGE) / (OVERSAMPLENR)
|
||||
* (TEMP_SENSOR_AD595_GAIN) + (TEMP_SENSOR_AD595_OFFSET);
|
||||
}
|
||||
#endif
|
||||
|
||||
#if ANY_THERMISTOR_IS(-4)
|
||||
// For a 5V input the AD8495 returns a value scaled with 5mV per °C. (Minimum input voltage is 2.7V.)
|
||||
static constexpr celsius_float_t temp_ad8495(const raw_adc_t raw) {
|
||||
return raw * (float(ADC_VREF_MV) / 5.0f) / float(HAL_ADC_RANGE) / (OVERSAMPLENR)
|
||||
* (TEMP_SENSOR_AD8495_GAIN) + (TEMP_SENSOR_AD8495_OFFSET);
|
||||
}
|
||||
#endif
|
||||
|
||||
#if HAS_HOTEND
|
||||
// Derived from RepRap FiveD extruder::getTemperature()
|
||||
// For hot end temperature measurement.
|
||||
|
|
@ -2626,9 +2641,9 @@ void Temperature::task() {
|
|||
return (int16_t)raw * 0.25f;
|
||||
#endif
|
||||
#elif TEMP_SENSOR_0_IS_AD595
|
||||
return TEMP_AD595(raw);
|
||||
return temp_ad595(raw);
|
||||
#elif TEMP_SENSOR_0_IS_AD8495
|
||||
return TEMP_AD8495(raw);
|
||||
return temp_ad8495(raw);
|
||||
#else
|
||||
break;
|
||||
#endif
|
||||
|
|
@ -2645,9 +2660,9 @@ void Temperature::task() {
|
|||
return (int16_t)raw * 0.25f;
|
||||
#endif
|
||||
#elif TEMP_SENSOR_1_IS_AD595
|
||||
return TEMP_AD595(raw);
|
||||
return temp_ad595(raw);
|
||||
#elif TEMP_SENSOR_1_IS_AD8495
|
||||
return TEMP_AD8495(raw);
|
||||
return temp_ad8495(raw);
|
||||
#else
|
||||
break;
|
||||
#endif
|
||||
|
|
@ -2664,9 +2679,9 @@ void Temperature::task() {
|
|||
return (int16_t)raw * 0.25f;
|
||||
#endif
|
||||
#elif TEMP_SENSOR_2_IS_AD595
|
||||
return TEMP_AD595(raw);
|
||||
return temp_ad595(raw);
|
||||
#elif TEMP_SENSOR_2_IS_AD8495
|
||||
return TEMP_AD8495(raw);
|
||||
return temp_ad8495(raw);
|
||||
#else
|
||||
break;
|
||||
#endif
|
||||
|
|
@ -2674,9 +2689,9 @@ void Temperature::task() {
|
|||
#if TEMP_SENSOR_3_IS_CUSTOM
|
||||
return user_thermistor_to_deg_c(CTI_HOTEND_3, raw);
|
||||
#elif TEMP_SENSOR_3_IS_AD595
|
||||
return TEMP_AD595(raw);
|
||||
return temp_ad595(raw);
|
||||
#elif TEMP_SENSOR_3_IS_AD8495
|
||||
return TEMP_AD8495(raw);
|
||||
return temp_ad8495(raw);
|
||||
#else
|
||||
break;
|
||||
#endif
|
||||
|
|
@ -2684,9 +2699,9 @@ void Temperature::task() {
|
|||
#if TEMP_SENSOR_4_IS_CUSTOM
|
||||
return user_thermistor_to_deg_c(CTI_HOTEND_4, raw);
|
||||
#elif TEMP_SENSOR_4_IS_AD595
|
||||
return TEMP_AD595(raw);
|
||||
return temp_ad595(raw);
|
||||
#elif TEMP_SENSOR_4_IS_AD8495
|
||||
return TEMP_AD8495(raw);
|
||||
return temp_ad8495(raw);
|
||||
#else
|
||||
break;
|
||||
#endif
|
||||
|
|
@ -2694,9 +2709,9 @@ void Temperature::task() {
|
|||
#if TEMP_SENSOR_5_IS_CUSTOM
|
||||
return user_thermistor_to_deg_c(CTI_HOTEND_5, raw);
|
||||
#elif TEMP_SENSOR_5_IS_AD595
|
||||
return TEMP_AD595(raw);
|
||||
return temp_ad595(raw);
|
||||
#elif TEMP_SENSOR_5_IS_AD8495
|
||||
return TEMP_AD8495(raw);
|
||||
return temp_ad8495(raw);
|
||||
#else
|
||||
break;
|
||||
#endif
|
||||
|
|
@ -2704,9 +2719,9 @@ void Temperature::task() {
|
|||
#if TEMP_SENSOR_6_IS_CUSTOM
|
||||
return user_thermistor_to_deg_c(CTI_HOTEND_6, raw);
|
||||
#elif TEMP_SENSOR_6_IS_AD595
|
||||
return TEMP_AD595(raw);
|
||||
return temp_ad595(raw);
|
||||
#elif TEMP_SENSOR_6_IS_AD8495
|
||||
return TEMP_AD8495(raw);
|
||||
return temp_ad8495(raw);
|
||||
#else
|
||||
break;
|
||||
#endif
|
||||
|
|
@ -2714,9 +2729,9 @@ void Temperature::task() {
|
|||
#if TEMP_SENSOR_7_IS_CUSTOM
|
||||
return user_thermistor_to_deg_c(CTI_HOTEND_7, raw);
|
||||
#elif TEMP_SENSOR_7_IS_AD595
|
||||
return TEMP_AD595(raw);
|
||||
return temp_ad595(raw);
|
||||
#elif TEMP_SENSOR_7_IS_AD8495
|
||||
return TEMP_AD8495(raw);
|
||||
return temp_ad8495(raw);
|
||||
#else
|
||||
break;
|
||||
#endif
|
||||
|
|
@ -2750,9 +2765,9 @@ void Temperature::task() {
|
|||
#elif TEMP_SENSOR_BED_IS_THERMISTOR
|
||||
SCAN_THERMISTOR_TABLE(TEMPTABLE_BED, TEMPTABLE_BED_LEN);
|
||||
#elif TEMP_SENSOR_BED_IS_AD595
|
||||
return TEMP_AD595(raw);
|
||||
return temp_ad595(raw);
|
||||
#elif TEMP_SENSOR_BED_IS_AD8495
|
||||
return TEMP_AD8495(raw);
|
||||
return temp_ad8495(raw);
|
||||
#else
|
||||
UNUSED(raw);
|
||||
return 0;
|
||||
|
|
@ -2768,9 +2783,9 @@ void Temperature::task() {
|
|||
#elif TEMP_SENSOR_CHAMBER_IS_THERMISTOR
|
||||
SCAN_THERMISTOR_TABLE(TEMPTABLE_CHAMBER, TEMPTABLE_CHAMBER_LEN);
|
||||
#elif TEMP_SENSOR_CHAMBER_IS_AD595
|
||||
return TEMP_AD595(raw);
|
||||
return temp_ad595(raw);
|
||||
#elif TEMP_SENSOR_CHAMBER_IS_AD8495
|
||||
return TEMP_AD8495(raw);
|
||||
return temp_ad8495(raw);
|
||||
#else
|
||||
UNUSED(raw);
|
||||
return 0;
|
||||
|
|
@ -2786,9 +2801,9 @@ void Temperature::task() {
|
|||
#elif TEMP_SENSOR_COOLER_IS_THERMISTOR
|
||||
SCAN_THERMISTOR_TABLE(TEMPTABLE_COOLER, TEMPTABLE_COOLER_LEN);
|
||||
#elif TEMP_SENSOR_COOLER_IS_AD595
|
||||
return TEMP_AD595(raw);
|
||||
return temp_ad595(raw);
|
||||
#elif TEMP_SENSOR_COOLER_IS_AD8495
|
||||
return TEMP_AD8495(raw);
|
||||
return temp_ad8495(raw);
|
||||
#else
|
||||
UNUSED(raw);
|
||||
return 0;
|
||||
|
|
@ -2804,9 +2819,9 @@ void Temperature::task() {
|
|||
#elif TEMP_SENSOR_PROBE_IS_THERMISTOR
|
||||
SCAN_THERMISTOR_TABLE(TEMPTABLE_PROBE, TEMPTABLE_PROBE_LEN);
|
||||
#elif TEMP_SENSOR_PROBE_IS_AD595
|
||||
return TEMP_AD595(raw);
|
||||
return temp_ad595(raw);
|
||||
#elif TEMP_SENSOR_PROBE_IS_AD8495
|
||||
return TEMP_AD8495(raw);
|
||||
return temp_ad8495(raw);
|
||||
#else
|
||||
UNUSED(raw);
|
||||
return 0;
|
||||
|
|
@ -2822,9 +2837,9 @@ void Temperature::task() {
|
|||
#elif TEMP_SENSOR_BOARD_IS_THERMISTOR
|
||||
SCAN_THERMISTOR_TABLE(TEMPTABLE_BOARD, TEMPTABLE_BOARD_LEN);
|
||||
#elif TEMP_SENSOR_BOARD_IS_AD595
|
||||
return TEMP_AD595(raw);
|
||||
return temp_ad595(raw);
|
||||
#elif TEMP_SENSOR_BOARD_IS_AD8495
|
||||
return TEMP_AD8495(raw);
|
||||
return temp_ad8495(raw);
|
||||
#else
|
||||
UNUSED(raw);
|
||||
return 0;
|
||||
|
|
@ -2835,14 +2850,11 @@ void Temperature::task() {
|
|||
#if HAS_TEMP_SOC
|
||||
// For SoC temperature measurement.
|
||||
celsius_float_t Temperature::analog_to_celsius_soc(const raw_adc_t raw) {
|
||||
return (
|
||||
#ifdef TEMP_SOC_SENSOR
|
||||
TEMP_SOC_SENSOR(raw)
|
||||
#else
|
||||
0
|
||||
#error "TEMP_SENSOR_SOC requires the TEMP_SOC_SENSOR(RAW) macro to be defined for your board."
|
||||
#endif
|
||||
);
|
||||
#ifndef TEMP_SOC_SENSOR
|
||||
#error "TEMP_SENSOR_SOC requires the TEMP_SOC_SENSOR(RAW) macro to be defined for your board."
|
||||
#define TEMP_SOC_SENSOR(...) 0
|
||||
#endif
|
||||
return TEMP_SOC_SENSOR(raw);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
|
@ -2860,9 +2872,9 @@ void Temperature::task() {
|
|||
#elif TEMP_SENSOR_REDUNDANT_IS_THERMISTOR
|
||||
SCAN_THERMISTOR_TABLE(TEMPTABLE_REDUNDANT, TEMPTABLE_REDUNDANT_LEN);
|
||||
#elif TEMP_SENSOR_REDUNDANT_IS_AD595
|
||||
return TEMP_AD595(raw);
|
||||
return temp_ad595(raw);
|
||||
#elif TEMP_SENSOR_REDUNDANT_IS_AD8495
|
||||
return TEMP_AD8495(raw);
|
||||
return temp_ad8495(raw);
|
||||
#else
|
||||
UNUSED(raw);
|
||||
return 0;
|
||||
|
|
|
|||
|
|
@ -108,16 +108,19 @@
|
|||
#endif
|
||||
|
||||
//
|
||||
// SPI pins for TMC2130 stepper drivers
|
||||
// SPI pins for TMC2130, TMC2160, TMC2240, TMC2660, TMC5130, or TMC5160 stepper drivers
|
||||
//
|
||||
#ifndef TMC_SPI_MOSI
|
||||
#define TMC_SPI_MOSI PB15
|
||||
#endif
|
||||
#ifndef TMC_SPI_MISO
|
||||
#define TMC_SPI_MISO PB14
|
||||
#endif
|
||||
#ifndef TMC_SPI_SCK
|
||||
#define TMC_SPI_SCK PB13
|
||||
#if HAS_TMC_SPI
|
||||
#define TMC_USE_SW_SPI
|
||||
#ifndef TMC_SPI_MOSI
|
||||
#define TMC_SPI_MOSI PB15
|
||||
#endif
|
||||
#ifndef TMC_SPI_MISO
|
||||
#define TMC_SPI_MISO PB14
|
||||
#endif
|
||||
#ifndef TMC_SPI_SCK
|
||||
#define TMC_SPI_SCK PB13
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if HAS_TMC_UART
|
||||
|
|
|
|||
|
|
@ -124,16 +124,19 @@
|
|||
#endif
|
||||
|
||||
//
|
||||
// SPI pins for TMC2130 stepper drivers
|
||||
// SPI pins for TMC2130, TMC2160, TMC2240, TMC2660, TMC5130, or TMC5160 stepper drivers
|
||||
//
|
||||
#ifndef TMC_SPI_MOSI
|
||||
#define TMC_SPI_MOSI PC6
|
||||
#endif
|
||||
#ifndef TMC_SPI_MISO
|
||||
#define TMC_SPI_MISO PG3
|
||||
#endif
|
||||
#ifndef TMC_SPI_SCK
|
||||
#define TMC_SPI_SCK PC7
|
||||
#if HAS_TMC_SPI
|
||||
#define TMC_USE_SW_SPI
|
||||
#ifndef TMC_SPI_MOSI
|
||||
#define TMC_SPI_MOSI PC6
|
||||
#endif
|
||||
#ifndef TMC_SPI_MISO
|
||||
#define TMC_SPI_MISO PG3
|
||||
#endif
|
||||
#ifndef TMC_SPI_SCK
|
||||
#define TMC_SPI_SCK PC7
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if HAS_TMC_UART
|
||||
|
|
|
|||
|
|
@ -128,7 +128,7 @@ bool DiskIODriver_USBFlash::usbStartup() {
|
|||
SERIAL_ECHOPGM("Starting USB host...");
|
||||
if (!UHS_START) {
|
||||
SERIAL_ECHOLNPGM(" failed.");
|
||||
LCD_MESSAGE(MSG_MEDIA_USB_FAILED);
|
||||
LCD_MESSAGE(MSG_USB_FD_USB_FAILED);
|
||||
return false;
|
||||
}
|
||||
|
||||
|
|
@ -223,8 +223,8 @@ void DiskIODriver_USBFlash::idle() {
|
|||
#endif
|
||||
#if USB_DEBUG >= 1
|
||||
SERIAL_ECHOLNPGM("Waiting for media");
|
||||
LCD_MESSAGE(MSG_USB_FD_WAITING_FOR_MEDIA);
|
||||
#endif
|
||||
LCD_MESSAGE(MSG_MEDIA_WAITING);
|
||||
GOTO_STATE_AFTER_DELAY(state, 2000);
|
||||
}
|
||||
break;
|
||||
|
|
@ -237,9 +237,9 @@ void DiskIODriver_USBFlash::idle() {
|
|||
// Handle device removal events
|
||||
#if USB_DEBUG >= 1
|
||||
SERIAL_ECHOLNPGM("USB device removed");
|
||||
if (state != MEDIA_READY)
|
||||
LCD_MESSAGE(MSG_USB_FD_DEVICE_REMOVED);
|
||||
#endif
|
||||
if (state != MEDIA_READY)
|
||||
LCD_MESSAGE(MSG_MEDIA_USB_REMOVED);
|
||||
GOTO_STATE_AFTER_DELAY(WAIT_FOR_DEVICE, 0);
|
||||
}
|
||||
|
||||
|
|
@ -247,8 +247,8 @@ void DiskIODriver_USBFlash::idle() {
|
|||
// Handle media removal events
|
||||
#if USB_DEBUG >= 1
|
||||
SERIAL_ECHOLNPGM("Media removed");
|
||||
LCD_MESSAGE(MSG_USB_FD_MEDIA_REMOVED);
|
||||
#endif
|
||||
LCD_MESSAGE(MSG_MEDIA_REMOVED);
|
||||
GOTO_STATE_AFTER_DELAY(WAIT_FOR_DEVICE, 0);
|
||||
}
|
||||
|
||||
|
|
|
|||
|
|
@ -20,7 +20,8 @@ exec_test $1 $2 "Ender-3 V2 - JyersUI (ABL Bilinear/Manual)" "$3"
|
|||
|
||||
use_example_configs "Creality/Ender-3 V2/CrealityV422/CrealityUI"
|
||||
opt_disable DWIN_CREALITY_LCD PIDTEMP
|
||||
opt_enable DWIN_MARLINUI_LANDSCAPE LCD_ENDSTOP_TEST AUTO_BED_LEVELING_UBL BLTOUCH Z_SAFE_HOMING MPCTEMP MPC_AUTOTUNE \
|
||||
opt_enable DWIN_MARLINUI_LANDSCAPE LCD_ENDSTOP_TEST AUTO_BED_LEVELING_UBL BLTOUCH Z_SAFE_HOMING \
|
||||
MPCTEMP MPC_AUTOTUNE EVENT_GCODE_AFTER_MPC_TUNE \
|
||||
MARLIN_BRICKOUT MARLIN_INVADERS MARLIN_SNAKE GAMES_EASTER_EGG
|
||||
exec_test $1 $2 "Ender-3 V2 - MarlinUI (Games, UBL+BLTOUCH, MPCTEMP, LCD_ENDSTOP_TEST)" "$3"
|
||||
|
||||
|
|
|
|||
|
|
@ -13,14 +13,14 @@
|
|||
|
||||
[features]
|
||||
YHCB2004 = LiquidCrystal_AIP31068=https://github.com/ellensp/LiquidCrystal_AIP31068/archive/3fc43b7.zip, red-scorp/SoftSPIB@^1.1.1
|
||||
HAS_TFT_LVGL_UI = lvgl=https://github.com/makerbase-mks/LVGL-6.1.1-MKS/archive/a3ebe98bc6.zip
|
||||
HAS_TFT_LVGL_UI = lvgl=https://github.com/staff1010/LVGL-6.1.1-MKS/archive/v6.1.2.zip
|
||||
build_src_filter=+<src/lcd/extui/mks_ui>
|
||||
extra_scripts=download_mks_assets.py
|
||||
MARLIN_TEST_BUILD = build_src_filter=+<src/tests>
|
||||
POSTMORTEM_DEBUGGING = build_src_filter=+<src/HAL/shared/cpu_exception> +<src/HAL/shared/backtrace>
|
||||
build_flags=-funwind-tables
|
||||
MKS_WIFI_MODULE = QRCode=https://github.com/makerbase-mks/QRCode/archive/261c5a696a.zip
|
||||
HAS_TRINAMIC_CONFIG = TMCStepper=https://github.com/MarlinFirmware/TMCStepper/archive/marlin-2.1.3.x.zip
|
||||
HAS_TRINAMIC_CONFIG = TMCStepper=https://github.com/MarlinFirmware/TMCStepper/archive/v0.8.3.zip
|
||||
build_src_filter=+<src/module/stepper/trinamic.cpp> +<src/gcode/feature/trinamic/M122.cpp> +<src/gcode/feature/trinamic/M906.cpp> +<src/gcode/feature/trinamic/M911-M914.cpp> +<src/gcode/feature/trinamic/M919.cpp>
|
||||
HAS_STEPPER_CONTROL = build_src_filter=+<src/module/stepper/control.cpp>
|
||||
HAS_T(RINAMIC_CONFIG|MC_SPI) = build_src_filter=+<src/feature/tmc_util.cpp>
|
||||
|
|
|
|||
|
|
@ -27,8 +27,8 @@
|
|||
# Base Environment for all HC32F460 variants
|
||||
#
|
||||
[HC32F460_base]
|
||||
platform = https://github.com/shadow578/platform-hc32f46x/archive/1.1.0.zip
|
||||
platform_packages = framework-hc32f46x-ddl@https://github.com/shadow578/framework-hc32f46x-ddl/archive/2.2.2.zip
|
||||
platform = https://github.com/shadow578/platform-hc32f46x/archive/1.1.1.zip
|
||||
platform_packages = framework-hc32f46x-ddl@https://github.com/shadow578/framework-hc32f46x-ddl/archive/2.2.3.zip
|
||||
framework-arduino-hc32f46x@https://github.com/shadow578/framework-arduino-hc32f46x/archive/1.2.0.zip
|
||||
board = generic_hc32f460
|
||||
build_src_filter = ${common.default_src_filter} +<src/HAL/HC32> +<src/HAL/shared/backtrace>
|
||||
|
|
|
|||
Loading…
Add table
Add a link
Reference in a new issue