Browse Source

🎨 Misc cleanup and fixes

vanilla_fb_2.0.x
Scott Lahteine 4 years ago
committed by Scott Lahteine
parent
commit
f7d28ce1d6
  1. 2
      Marlin/src/core/debug_section.h
  2. 16
      Marlin/src/core/language.h
  3. 2
      Marlin/src/core/serial.cpp
  4. 10
      Marlin/src/core/serial.h
  5. 20
      Marlin/src/core/types.h
  6. 36
      Marlin/src/gcode/calibrate/G425.cpp
  7. 32
      Marlin/src/gcode/config/M200-M205.cpp
  8. 9
      Marlin/src/gcode/config/M92.cpp
  9. 16
      Marlin/src/gcode/control/M17_M18_M84.cpp
  10. 4
      Marlin/src/gcode/control/M211.cpp
  11. 46
      Marlin/src/gcode/feature/trinamic/M911-M914.cpp
  12. 2
      Marlin/src/gcode/gcode.cpp
  13. 22
      Marlin/src/gcode/host/M114.cpp
  14. 2
      Marlin/src/gcode/motion/G0_G1.cpp
  15. 8
      Marlin/src/gcode/motion/G2_G3.cpp
  16. 2
      Marlin/src/gcode/parser.cpp
  17. 2
      Marlin/src/gcode/parser.h
  18. 2
      Marlin/src/inc/Conditionals_post.h
  19. 2
      Marlin/src/inc/SanityCheck.h
  20. 1
      Marlin/src/lcd/extui/dgus/dgus_extui.cpp
  21. 12
      Marlin/src/lcd/extui/ui_api.cpp
  22. 3
      Marlin/src/lcd/menu/menu_mmu2.cpp
  23. 4
      Marlin/src/module/endstops.cpp
  24. 20
      Marlin/src/module/motion.cpp
  25. 4
      Marlin/src/module/settings.cpp
  26. 2
      Marlin/src/module/stepper/trinamic.cpp

2
Marlin/src/core/debug_section.h

@ -44,6 +44,6 @@ private:
SERIAL_ECHOPGM_P(the_msg);
}
SERIAL_CHAR(' ');
print_xyz(current_position);
print_pos(current_position);
}
};

16
Marlin/src/core/language.h

@ -277,14 +277,6 @@
#define STR_REMINDER_SAVE_SETTINGS "Remember to save!"
#define STR_PASSWORD_SET "Password is "
// LCD Menu Messages
#define LANGUAGE_DATA_INCL_(M) STRINGIFY_(fontdata/langdata_##M.h)
#define LANGUAGE_DATA_INCL(M) LANGUAGE_DATA_INCL_(M)
#define LANGUAGE_INCL_(M) STRINGIFY_(../lcd/language/language_##M.h)
#define LANGUAGE_INCL(M) LANGUAGE_INCL_(M)
#define STR_X "X"
#define STR_Y "Y"
#define STR_Z "Z"
@ -386,6 +378,14 @@
#define LCD_STR_E6 "E" LCD_STR_N6
#define LCD_STR_E7 "E" LCD_STR_N7
// Include localized LCD Menu Messages
#define LANGUAGE_DATA_INCL_(M) STRINGIFY_(fontdata/langdata_##M.h)
#define LANGUAGE_DATA_INCL(M) LANGUAGE_DATA_INCL_(M)
#define LANGUAGE_INCL_(M) STRINGIFY_(../lcd/language/language_##M.h)
#define LANGUAGE_INCL(M) LANGUAGE_INCL_(M)
// Use superscripts, if possible. Evaluated at point of use.
#define SUPERSCRIPT_TWO TERN(NOT_EXTENDED_ISO10646_1_5X7, "^2", "²")
#define SUPERSCRIPT_THREE TERN(NOT_EXTENDED_ISO10646_1_5X7, "^3", "³")

2
Marlin/src/core/serial.cpp

@ -101,7 +101,7 @@ void print_bin(uint16_t val) {
}
}
void print_xyz(const_float_t x, const_float_t y, const_float_t z, PGM_P const prefix/*=nullptr*/, PGM_P const suffix/*=nullptr*/) {
void print_pos(const_float_t x, const_float_t y, const_float_t z, PGM_P const prefix/*=nullptr*/, PGM_P const suffix/*=nullptr*/) {
if (prefix) serialprintPGM(prefix);
SERIAL_ECHOPAIR_P(SP_X_STR, x, SP_Y_STR, y, SP_Z_STR, z);
if (suffix) serialprintPGM(suffix); else SERIAL_EOL();

10
Marlin/src/core/serial.h

@ -310,11 +310,11 @@ void serialprint_truefalse(const bool tf);
void serial_spaces(uint8_t count);
void print_bin(const uint16_t val);
void print_xyz(const_float_t x, const_float_t y, const_float_t z, PGM_P const prefix=nullptr, PGM_P const suffix=nullptr);
void print_pos(const_float_t x, const_float_t y, const_float_t z, PGM_P const prefix=nullptr, PGM_P const suffix=nullptr);
inline void print_xyz(const xyz_pos_t &xyz, PGM_P const prefix=nullptr, PGM_P const suffix=nullptr) {
print_xyz(xyz.x, xyz.y, xyz.z, prefix, suffix);
inline void print_pos(const xyz_pos_t &xyz, PGM_P const prefix=nullptr, PGM_P const suffix=nullptr) {
print_pos(xyz.x, xyz.y, xyz.z, prefix, suffix);
}
#define SERIAL_POS(SUFFIX,VAR) do { print_xyz(VAR, PSTR(" " STRINGIFY(VAR) "="), PSTR(" : " SUFFIX "\n")); }while(0)
#define SERIAL_XYZ(PREFIX,V...) do { print_xyz(V, PSTR(PREFIX), nullptr); }while(0)
#define SERIAL_POS(SUFFIX,VAR) do { print_pos(VAR, PSTR(" " STRINGIFY(VAR) "="), PSTR(" : " SUFFIX "\n")); }while(0)
#define SERIAL_XYZ(PREFIX,V...) do { print_pos(V, PSTR(PREFIX), nullptr); }while(0)

20
Marlin/src/core/types.h

@ -29,6 +29,16 @@
class __FlashStringHelper;
typedef const __FlashStringHelper *progmem_str;
//
// Conditional type assignment magic. For example...
//
// typename IF<(MYOPT==12), int, float>::type myvar;
//
template <bool, class L, class R>
struct IF { typedef R type; };
template <class L, class R>
struct IF<true, L, R> { typedef L type; };
//
// Enumerated axis indices
//
@ -57,16 +67,6 @@ enum AxisEnum : uint8_t {
#define LOOP_ABCE(VAR) LOOP_S_LE_N(VAR, A_AXIS, E_AXIS)
#define LOOP_ABCE_N(VAR) LOOP_S_L_N(VAR, A_AXIS, XYZE_N)
//
// Conditional type assignment magic. For example...
//
// typename IF<(MYOPT==12), int, float>::type myvar;
//
template <bool, class L, class R>
struct IF { typedef R type; };
template <class L, class R>
struct IF<true, L, R> { typedef L type; };
//
// feedRate_t is just a humble float
//

36
Marlin/src/gcode/calibrate/G425.cpp

@ -194,16 +194,20 @@ float measuring_movement(const AxisEnum axis, const int dir, const bool stop_sta
inline float measure(const AxisEnum axis, const int dir, const bool stop_state, float * const backlash_ptr, const float uncertainty) {
const bool fast = uncertainty == CALIBRATION_MEASUREMENT_UNKNOWN;
// Save position
destination = current_position;
const float start_pos = destination[axis];
// Save the current position of the specified axis
const float start_pos = current_position[axis];
// Take a measurement. Only the specified axis will be affected.
const float measured_pos = measuring_movement(axis, dir, stop_state, fast);
// Measure backlash
if (backlash_ptr && !fast) {
const float release_pos = measuring_movement(axis, -dir, !stop_state, fast);
*backlash_ptr = ABS(release_pos - measured_pos);
}
// Return to starting position
// Move back to the starting position
destination = current_position;
destination[axis] = start_pos;
do_blocking_move_to(destination, MMM_TO_MMS(CALIBRATION_FEEDRATE_TRAVEL));
return measured_pos;
@ -235,12 +239,12 @@ inline void probe_side(measurements_t &m, const float uncertainty, const side_t
}
#endif
#if AXIS_CAN_CALIBRATE(X)
case RIGHT: dir = -1;
case LEFT: axis = X_AXIS; break;
case RIGHT: axis = X_AXIS; dir = -1; break;
#endif
#if AXIS_CAN_CALIBRATE(Y)
case BACK: dir = -1;
case FRONT: axis = Y_AXIS; break;
case BACK: axis = Y_AXIS; dir = -1; break;
#endif
default: return;
}
@ -303,16 +307,8 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
// The difference between the known and the measured location
// of the calibration object is the positional error
m.pos_error.x = (0
#if HAS_X_CENTER
+ true_center.x - m.obj_center.x
#endif
);
m.pos_error.y = (0
#if HAS_Y_CENTER
+ true_center.y - m.obj_center.y
#endif
);
m.pos_error.x = TERN0(HAS_X_CENTER, true_center.x - m.obj_center.x);
m.pos_error.y = TERN0(HAS_Y_CENTER, true_center.y - m.obj_center.y);
m.pos_error.z = true_center.z - m.obj_center.z;
}
@ -589,12 +585,12 @@ void GcodeSuite::G425() {
SET_SOFT_ENDSTOP_LOOSE(true);
measurements_t m;
float uncertainty = parser.seenval('U') ? parser.value_float() : CALIBRATION_MEASUREMENT_UNCERTAIN;
const float uncertainty = parser.floatval('U', CALIBRATION_MEASUREMENT_UNCERTAIN);
if (parser.seen('B'))
if (parser.seen_test('B'))
calibrate_backlash(m, uncertainty);
else if (parser.seen('T'))
calibrate_toolhead(m, uncertainty, parser.has_value() ? parser.value_int() : active_extruder);
else if (parser.seen_test('T'))
calibrate_toolhead(m, uncertainty, parser.intval('T', active_extruder));
#if ENABLED(CALIBRATION_REPORTING)
else if (parser.seen('V')) {
probe_sides(m, uncertainty);

32
Marlin/src/gcode/config/M200-M205.cpp

@ -87,7 +87,7 @@ void GcodeSuite::M201() {
#endif
LOOP_XYZE(i) {
if (parser.seen(axis_codes[i])) {
if (parser.seenval(axis_codes[i])) {
const uint8_t a = (i == E_AXIS ? uint8_t(E_AXIS_N(target_extruder)) : i);
planner.set_max_acceleration(a, parser.value_axis_units((AxisEnum)a));
}
@ -105,7 +105,7 @@ void GcodeSuite::M203() {
if (target_extruder < 0) return;
LOOP_XYZE(i)
if (parser.seen(axis_codes[i])) {
if (parser.seenval(axis_codes[i])) {
const uint8_t a = (i == E_AXIS ? uint8_t(E_AXIS_N(target_extruder)) : i);
planner.set_max_feedrate(a, parser.value_axis_units((AxisEnum)a));
}
@ -147,24 +147,14 @@ void GcodeSuite::M204() {
* J = Junction Deviation (mm) (If not using CLASSIC_JERK)
*/
void GcodeSuite::M205() {
#if HAS_JUNCTION_DEVIATION
#define J_PARAM "J"
#else
#define J_PARAM
#endif
#if HAS_CLASSIC_JERK
#define XYZE_PARAM "XYZE"
#else
#define XYZE_PARAM
#endif
if (!parser.seen("BST" J_PARAM XYZE_PARAM)) return;
if (!parser.seen("BST" TERN_(HAS_JUNCTION_DEVIATION, "J") TERN_(HAS_CLASSIC_JERK, "XYZE"))) return;
//planner.synchronize();
if (parser.seen('B')) planner.settings.min_segment_time_us = parser.value_ulong();
if (parser.seen('S')) planner.settings.min_feedrate_mm_s = parser.value_linear_units();
if (parser.seen('T')) planner.settings.min_travel_feedrate_mm_s = parser.value_linear_units();
if (parser.seenval('B')) planner.settings.min_segment_time_us = parser.value_ulong();
if (parser.seenval('S')) planner.settings.min_feedrate_mm_s = parser.value_linear_units();
if (parser.seenval('T')) planner.settings.min_travel_feedrate_mm_s = parser.value_linear_units();
#if HAS_JUNCTION_DEVIATION
if (parser.seen('J')) {
if (parser.seenval('J')) {
const float junc_dev = parser.value_linear_units();
if (WITHIN(junc_dev, 0.01f, 0.3f)) {
planner.junction_deviation_mm = junc_dev;
@ -175,9 +165,9 @@ void GcodeSuite::M205() {
}
#endif
#if HAS_CLASSIC_JERK
if (parser.seen('X')) planner.set_max_jerk(X_AXIS, parser.value_linear_units());
if (parser.seen('Y')) planner.set_max_jerk(Y_AXIS, parser.value_linear_units());
if (parser.seen('Z')) {
if (parser.seenval('X')) planner.set_max_jerk(X_AXIS, parser.value_linear_units());
if (parser.seenval('Y')) planner.set_max_jerk(Y_AXIS, parser.value_linear_units());
if (parser.seenval('Z')) {
planner.set_max_jerk(Z_AXIS, parser.value_linear_units());
#if HAS_MESH && DISABLED(LIMITED_JERK_EDITING)
if (planner.max_jerk.z <= 0.1f)
@ -185,7 +175,7 @@ void GcodeSuite::M205() {
#endif
}
#if HAS_CLASSIC_E_JERK
if (parser.seen('E')) planner.set_max_jerk(E_AXIS, parser.value_linear_units());
if (parser.seenval('E')) planner.set_max_jerk(E_AXIS, parser.value_linear_units());
#endif
#endif
}

9
Marlin/src/gcode/config/M92.cpp

@ -42,7 +42,7 @@ void report_M92(const bool echo=true, const int8_t e=-1) {
}
#endif
UNUSED_E(e);
UNUSED(e);
}
/**
@ -64,11 +64,8 @@ void GcodeSuite::M92() {
if (target_extruder < 0) return;
// No arguments? Show M92 report.
if (!parser.seen("XYZE"
#if ENABLED(MAGIC_NUMBERS_GCODE)
"HL"
#endif
)) return report_M92(true, target_extruder);
if (!parser.seen("XYZE" TERN_(MAGIC_NUMBERS_GCODE, "HL")))
return report_M92(true, target_extruder);
LOOP_XYZE(i) {
if (parser.seenval(axis_codes[i])) {

16
Marlin/src/gcode/control/M17_M18_M84.cpp

@ -34,10 +34,10 @@
*/
void GcodeSuite::M17() {
if (parser.seen("XYZE")) {
if (parser.seen('X')) ENABLE_AXIS_X();
if (parser.seen('Y')) ENABLE_AXIS_Y();
if (parser.seen('Z')) ENABLE_AXIS_Z();
if (TERN0(HAS_E_STEPPER_ENABLE, parser.seen('E'))) enable_e_steppers();
if (parser.seen_test('X')) ENABLE_AXIS_X();
if (parser.seen_test('Y')) ENABLE_AXIS_Y();
if (parser.seen_test('Z')) ENABLE_AXIS_Z();
if (TERN0(HAS_E_STEPPER_ENABLE, parser.seen_test('E'))) enable_e_steppers();
}
else {
LCD_MESSAGEPGM(MSG_NO_MOVE);
@ -56,10 +56,10 @@ void GcodeSuite::M18_M84() {
else {
if (parser.seen("XYZE")) {
planner.synchronize();
if (parser.seen('X')) DISABLE_AXIS_X();
if (parser.seen('Y')) DISABLE_AXIS_Y();
if (parser.seen('Z')) DISABLE_AXIS_Z();
if (TERN0(HAS_E_STEPPER_ENABLE, parser.seen('E'))) disable_e_steppers();
if (parser.seen_test('X')) DISABLE_AXIS_X();
if (parser.seen_test('Y')) DISABLE_AXIS_Y();
if (parser.seen_test('Z')) DISABLE_AXIS_Z();
if (TERN0(HAS_E_STEPPER_ENABLE, parser.seen_test('E'))) disable_e_steppers();
}
else
planner.finish_and_disable();

4
Marlin/src/gcode/control/M211.cpp

@ -39,8 +39,8 @@ void GcodeSuite::M211() {
SERIAL_ECHOPGM(STR_SOFT_ENDSTOPS);
if (parser.seen('S')) soft_endstop._enabled = parser.value_bool();
serialprint_onoff(soft_endstop._enabled);
print_xyz(l_soft_min, PSTR(STR_SOFT_MIN), PSTR(" "));
print_xyz(l_soft_max, PSTR(STR_SOFT_MAX));
print_pos(l_soft_min, PSTR(STR_SOFT_MIN), PSTR(" "));
print_pos(l_soft_max, PSTR(STR_SOFT_MAX));
}
#endif

46
Marlin/src/gcode/feature/trinamic/M911-M914.cpp

@ -35,10 +35,19 @@
#define M91x_USE(ST) (AXIS_DRIVER_TYPE(ST, TMC2130) || AXIS_DRIVER_TYPE(ST, TMC2160) || AXIS_DRIVER_TYPE(ST, TMC2208) || AXIS_DRIVER_TYPE(ST, TMC2209) || AXIS_DRIVER_TYPE(ST, TMC2660) || AXIS_DRIVER_TYPE(ST, TMC5130) || AXIS_DRIVER_TYPE(ST, TMC5160))
#define M91x_USE_E(N) (E_STEPPERS > N && M91x_USE(E##N))
#define M91x_SOME_X (M91x_USE(X) || M91x_USE(X2))
#define M91x_SOME_Y (M91x_USE(Y) || M91x_USE(Y2))
#define M91x_SOME_Z (M91x_USE(Z) || M91x_USE(Z2) || M91x_USE(Z3) || M91x_USE(Z4))
#define M91x_SOME_E (M91x_USE_E(0) || M91x_USE_E(1) || M91x_USE_E(2) || M91x_USE_E(3) || M91x_USE_E(4) || M91x_USE_E(5) || M91x_USE_E(6) || M91x_USE_E(7))
#if M91x_USE(X) || M91x_USE(X2)
#define M91x_SOME_X 1
#endif
#if M91x_USE(Y) || M91x_USE(Y2)
#define M91x_SOME_Y 1
#endif
#if M91x_USE(Z) || M91x_USE(Z2) || M91x_USE(Z3) || M91x_USE(Z4)
#define M91x_SOME_Z 1
#endif
#if M91x_USE_E(0) || M91x_USE_E(1) || M91x_USE_E(2) || M91x_USE_E(3) || M91x_USE_E(4) || M91x_USE_E(5) || M91x_USE_E(6) || M91x_USE_E(7)
#define M91x_SOME_E 1
#endif
#if !M91x_SOME_X && !M91x_SOME_Y && !M91x_SOME_Z && !M91x_SOME_E
#error "MONITOR_DRIVER_STATUS requires at least one TMC2130, 2160, 2208, 2209, 2660, 5130, or 5160."
@ -112,31 +121,12 @@
* M912 E1 ; clear E1 only
*/
void GcodeSuite::M912() {
#if M91x_SOME_X
const bool hasX = parser.seen(axis_codes.x);
#else
constexpr bool hasX = false;
#endif
#if M91x_SOME_Y
const bool hasY = parser.seen(axis_codes.y);
#else
constexpr bool hasY = false;
#endif
#if M91x_SOME_Z
const bool hasZ = parser.seen(axis_codes.z);
#else
constexpr bool hasZ = false;
#endif
#if M91x_SOME_E
const bool hasE = parser.seen(axis_codes.e);
#else
constexpr bool hasE = false;
#endif
const bool hasX = TERN0(M91x_SOME_X, parser.seen(axis_codes.x)),
hasY = TERN0(M91x_SOME_Y, parser.seen(axis_codes.y)),
hasZ = TERN0(M91x_SOME_Z, parser.seen(axis_codes.z)),
hasE = TERN0(M91x_SOME_E, parser.seen(axis_codes.e));
const bool hasNone = !hasX && !hasY && !hasZ && !hasE;
const bool hasNone = !hasE && !hasX && !hasY && !hasZ;
#if M91x_SOME_X
const int8_t xval = int8_t(parser.byteval(axis_codes.x, 0xFF));

2
Marlin/src/gcode/gcode.cpp

@ -140,7 +140,7 @@ int8_t GcodeSuite::get_target_e_stepper_from_command() {
* - Set the feedrate, if included
*/
void GcodeSuite::get_destination_from_command() {
xyze_bool_t seen = { false, false, false, false };
xyze_bool_t seen{false};
#if ENABLED(CANCEL_OBJECTS)
const bool &skip_move = cancelable.skipping;

22
Marlin/src/gcode/host/M114.cpp

@ -34,7 +34,7 @@
#include "../../core/debug_out.h"
#endif
void report_xyze(const xyze_pos_t &pos, const uint8_t n=XYZE, const uint8_t precision=3) {
void report_all_axis_pos(const xyze_pos_t &pos, const uint8_t n=XYZE, const uint8_t precision=3) {
char str[12];
LOOP_L_N(a, n) {
SERIAL_CHAR(' ', axis_codes[a], ':');
@ -43,9 +43,9 @@
}
SERIAL_EOL();
}
inline void report_xyz(const xyze_pos_t &pos) { report_xyze(pos, XYZ); }
inline void report_linear_axis_pos(const xyze_pos_t &pos) { report_all_axis_pos(pos, XYZ); }
void report_xyz(const xyz_pos_t &pos, const uint8_t precision=3) {
void report_linear_axis_pos(const xyz_pos_t &pos, const uint8_t precision=3) {
char str[12];
LOOP_XYZ(a) {
SERIAL_CHAR(' ', XYZ_CHAR(a), ':');
@ -57,11 +57,11 @@
void report_current_position_detail() {
// Position as sent by G-code
SERIAL_ECHOPGM("\nLogical:");
report_xyz(current_position.asLogical());
report_linear_axis_pos(current_position.asLogical());
// Cartesian position in native machine space
SERIAL_ECHOPGM("Raw: ");
report_xyz(current_position);
report_linear_axis_pos(current_position);
xyze_pos_t leveled = current_position;
@ -69,20 +69,20 @@
// Current position with leveling applied
SERIAL_ECHOPGM("Leveled:");
planner.apply_leveling(leveled);
report_xyz(leveled);
report_linear_axis_pos(leveled);
// Test planner un-leveling. This should match the Raw result.
SERIAL_ECHOPGM("UnLevel:");
xyze_pos_t unleveled = leveled;
planner.unapply_leveling(unleveled);
report_xyz(unleveled);
report_linear_axis_pos(unleveled);
#endif
#if IS_KINEMATIC
// Kinematics applied to the leveled position
SERIAL_ECHOPGM(TERN(IS_SCARA, "ScaraK: ", "DeltaK: "));
inverse_kinematics(leveled); // writes delta[]
report_xyz(delta);
report_linear_axis_pos(delta);
#endif
planner.synchronize();
@ -165,17 +165,17 @@
planner.get_axis_position_degrees(B_AXIS)
};
SERIAL_ECHOPGM("Degrees:");
report_xyze(deg, 2);
report_all_axis_pos(deg, 2);
#endif
SERIAL_ECHOPGM("FromStp:");
get_cartesian_from_steppers(); // writes 'cartes' (with forward kinematics)
xyze_pos_t from_steppers = { cartes.x, cartes.y, cartes.z, planner.get_axis_position_mm(E_AXIS) };
report_xyze(from_steppers);
report_all_axis_pos(from_steppers);
const xyze_float_t diff = from_steppers - leveled;
SERIAL_ECHOPGM("Diff: ");
report_xyze(diff);
report_all_axis_pos(diff);
TERN_(FULL_REPORT_TO_HOST_FEATURE, report_current_grblstate_moving());
}

2
Marlin/src/gcode/motion/G0_G1.cpp

@ -83,7 +83,7 @@ void GcodeSuite::G0_G1(TERN_(HAS_FAST_MOVES, const bool fast_move/*=false*/)) {
if (MIN_AUTORETRACT <= MAX_AUTORETRACT) {
// When M209 Autoretract is enabled, convert E-only moves to firmware retract/recover moves
if (fwretract.autoretract_enabled && parser.seen('E') && !(parser.seen('X') || parser.seen('Y') || parser.seen('Z'))) {
if (fwretract.autoretract_enabled && parser.seen('E') && !parser.seen("XYZ")) {
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)) {

8
Marlin/src/gcode/motion/G2_G3.cpp

@ -291,12 +291,12 @@ void plan_arc(
* Mixing IJ/JK/KI with R will throw an error.
*
* - R specifies the radius. X or Y (Y or Z / Z or X) is required.
* Omitting both XY/YZ/ZX will throw an error.
* XY/YZ/ZX must differ from the current XY/YZ/ZX.
* Mixing R with IJ/JK/KI will throw an error.
* Omitting both XY/YZ/ZX will throw an error.
* XY/YZ/ZX must differ from the current XY/YZ/ZX.
* Mixing R with IJ/JK/KI will throw an error.
*
* - P specifies the number of full circles to do
* before the specified arc move.
* before the specified arc move.
*
* Examples:
*

2
Marlin/src/gcode/parser.cpp

@ -222,7 +222,7 @@ void GCodeParser::parse(char *p) {
#if ENABLED(GCODE_MOTION_MODES)
if (letter == 'G'
&& (codenum <= TERN(ARC_SUPPORT, 3, 1) || codenum == 5 || TERN0(G38_PROBE_TARGET, codenum == 38))
&& (codenum <= TERN(ARC_SUPPORT, 3, 1) || TERN0(BEZIER_CURVE_SUPPORT, codenum == 5) || TERN0(G38_PROBE_TARGET, codenum == 38))
) {
motion_mode_codenum = codenum;
TERN_(USE_GCODE_SUBCODES, motion_mode_subcode = subcode);

2
Marlin/src/gcode/parser.h

@ -226,7 +226,7 @@ public:
// Seen any axis parameter
static inline bool seen_axis() {
return seen_test('X') || seen_test('Y') || seen_test('Z') || seen_test('E');
return seen("XYZE");
}
#if ENABLED(GCODE_QUOTED_STRINGS)

2
Marlin/src/inc/Conditionals_post.h

@ -125,7 +125,7 @@
#if EITHER(IS_CORE, MARKFORGED_XY)
#define CAN_CALIBRATE(A,B) (_AXIS(A) == B)
#else
#define CAN_CALIBRATE(A,B) 1
#define CAN_CALIBRATE(A,B) true
#endif
#endif
#define AXIS_CAN_CALIBRATE(A) CAN_CALIBRATE(A,NORMAL_AXIS)

2
Marlin/src/inc/SanityCheck.h

@ -3247,7 +3247,7 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2)
/**
* Sanity check for MIXING_EXTRUDER & DISTINCT_E_FACTORS these are not compatible
*/
#if ENABLED(MIXING_EXTRUDER) && ENABLED(DISTINCT_E_FACTORS)
#if BOTH(MIXING_EXTRUDER, DISTINCT_E_FACTORS)
#error "MIXING_EXTRUDER can't be used with DISTINCT_E_FACTORS. But you may use SINGLENOZZLE with DISTINCT_E_FACTORS."
#endif

1
Marlin/src/lcd/extui/dgus/dgus_extui.cpp

@ -147,6 +147,7 @@ namespace ExtUI {
case PID_DONE:
ScreenHandler.setstatusmessagePGM(GET_TEXT(MSG_PID_AUTOTUNE_DONE));
break;
case PID_STARTED: break;
}
ScreenHandler.GotoScreen(DGUSLCD_SCREEN_MAIN);
}

12
Marlin/src/lcd/extui/ui_api.cpp

@ -569,7 +569,7 @@ namespace ExtUI {
}
float getAxisSteps_per_mm(const extruder_t extruder) {
UNUSED_E(extruder);
UNUSED(extruder);
return planner.settings.axis_steps_per_mm[E_AXIS_N(extruder - E0)];
}
@ -579,7 +579,7 @@ namespace ExtUI {
}
void setAxisSteps_per_mm(const_float_t value, const extruder_t extruder) {
UNUSED_E(extruder);
UNUSED(extruder);
planner.settings.axis_steps_per_mm[E_AXIS_N(extruder - E0)] = value;
planner.refresh_positioning();
}
@ -589,7 +589,7 @@ namespace ExtUI {
}
feedRate_t getAxisMaxFeedrate_mm_s(const extruder_t extruder) {
UNUSED_E(extruder);
UNUSED(extruder);
return planner.settings.max_feedrate_mm_s[E_AXIS_N(extruder - E0)];
}
@ -598,7 +598,7 @@ namespace ExtUI {
}
void setAxisMaxFeedrate_mm_s(const feedRate_t value, const extruder_t extruder) {
UNUSED_E(extruder);
UNUSED(extruder);
planner.set_max_feedrate(E_AXIS_N(extruder - E0), value);
}
@ -607,7 +607,7 @@ namespace ExtUI {
}
float getAxisMaxAcceleration_mm_s2(const extruder_t extruder) {
UNUSED_E(extruder);
UNUSED(extruder);
return planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(extruder - E0)];
}
@ -616,7 +616,7 @@ namespace ExtUI {
}
void setAxisMaxAcceleration_mm_s2(const_float_t value, const extruder_t extruder) {
UNUSED_E(extruder);
UNUSED(extruder);
planner.set_max_acceleration(E_AXIS_N(extruder - E0), value);
}

3
Marlin/src/lcd/menu/menu_mmu2.cpp

@ -37,8 +37,7 @@ inline void action_mmu2_load_filament_to_nozzle(const uint8_t tool) {
ui.reset_status();
ui.return_to_status();
ui.status_printf_P(0, GET_TEXT(MSG_MMU2_LOADING_FILAMENT), int(tool + 1));
if (mmu2.load_filament_to_nozzle(tool))
ui.reset_status();
if (mmu2.load_filament_to_nozzle(tool)) ui.reset_status();
ui.return_to_status();
}

4
Marlin/src/module/endstops.cpp

@ -508,7 +508,7 @@ void Endstops::update() {
#define UPDATE_ENDSTOP_BIT(AXIS, MINMAX) SET_BIT_TO(live_state, _ENDSTOP(AXIS, MINMAX), (READ(_ENDSTOP_PIN(AXIS, MINMAX)) != _ENDSTOP_INVERTING(AXIS, MINMAX)))
#define COPY_LIVE_STATE(SRC_BIT, DST_BIT) SET_BIT_TO(live_state, DST_BIT, TEST(live_state, SRC_BIT))
#if ENABLED(G38_PROBE_TARGET) && PIN_EXISTS(Z_MIN_PROBE) && NONE(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY)
#if BOTH(G38_PROBE_TARGET, HAS_Z_MIN_PROBE_PIN) && NONE(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY)
// If G38 command is active check Z_MIN_PROBE for ALL movement
if (G38_move) UPDATE_ENDSTOP_BIT(Z, MIN_PROBE);
#endif
@ -747,7 +747,7 @@ void Endstops::update() {
#define PROCESS_ENDSTOP_Z(MINMAX) PROCESS_DUAL_ENDSTOP(Z, MINMAX)
#endif
#if ENABLED(G38_PROBE_TARGET) && PIN_EXISTS(Z_MIN_PROBE) && NONE(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY)
#if BOTH(G38_PROBE_TARGET, HAS_Z_MIN_PROBE_PIN) && NONE(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY)
#if ENABLED(G38_PROBE_AWAY)
#define _G38_OPEN_STATE (G38_move >= 4)
#else

20
Marlin/src/module/motion.cpp

@ -83,13 +83,13 @@ bool relative_mode; // = false;
* Used by 'line_to_current_position' to do a move after changing it.
* Used by 'sync_plan_position' to update 'planner.position'.
*/
xyze_pos_t current_position = { X_HOME_POS, Y_HOME_POS,
#ifdef Z_IDLE_HEIGHT
Z_IDLE_HEIGHT
#else
Z_HOME_POS
#endif
};
#ifdef Z_IDLE_HEIGHT
#define Z_INIT_POS Z_IDLE_HEIGHT
#else
#define Z_INIT_POS Z_HOME_POS
#endif
xyze_pos_t current_position = { X_HOME_POS, Y_HOME_POS, Z_INIT_POS };
/**
* Cartesian Destination
@ -204,11 +204,7 @@ void report_real_position() {
get_cartesian_from_steppers();
xyze_pos_t npos = cartes;
npos.e = planner.get_axis_position_mm(E_AXIS);
#if HAS_POSITION_MODIFIERS
planner.unapply_modifiers(npos, true);
#endif
TERN_(HAS_POSITION_MODIFIERS, planner.unapply_modifiers(npos, true));
report_logical_position(npos);
report_more_positions();
}

4
Marlin/src/module/settings.cpp

@ -2584,8 +2584,8 @@ void MarlinSettings::postprocess() {
void MarlinSettings::reset() {
LOOP_XYZE_N(i) {
planner.settings.max_acceleration_mm_per_s2[i] = pgm_read_dword(&_DMA[ALIM(i, _DMA)]);
planner.settings.axis_steps_per_mm[i] = pgm_read_float(&_DASU[ALIM(i, _DASU)]);
planner.settings.max_feedrate_mm_s[i] = pgm_read_float(&_DMF[ALIM(i, _DMF)]);
planner.settings.axis_steps_per_mm[i] = pgm_read_float(&_DASU[ALIM(i, _DASU)]);
planner.settings.max_feedrate_mm_s[i] = pgm_read_float(&_DMF[ALIM(i, _DMF)]);
}
planner.settings.min_segment_time_us = DEFAULT_MINSEGMENTTIME;

2
Marlin/src/module/stepper/trinamic.cpp

@ -62,7 +62,7 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E };
#define _TMC_UART_DEFINE(SWHW, IC, ST, AI) TMC_UART_##SWHW##_DEFINE(IC, ST, TMC_##ST##_LABEL, AI)
#define TMC_UART_DEFINE(SWHW, ST, AI) _TMC_UART_DEFINE(SWHW, ST##_DRIVER_TYPE, ST, AI##_AXIS)
#if DISTINCT_E > 1
#if ENABLED(DISTINCT_E_FACTORS)
#define TMC_SPI_DEFINE_E(AI) TMC_SPI_DEFINE(E##AI, E##AI)
#define TMC_UART_DEFINE_E(SWHW, AI) TMC_UART_DEFINE(SWHW, E##AI, E##AI)
#else

Loading…
Cancel
Save