Skip to content
Open
Show file tree
Hide file tree
Changes from 15 commits
Commits
Show all changes
43 commits
Select commit Hold shift + click to select a range
0cd2d5d
add G7 rotate workspace
classicrocker883 Jun 27, 2025
a7dab7c
Merge branch 'bugfix-2.1.x' into bugfix-2.1.x-June3
classicrocker883 Jul 1, 2025
491620a
rename G68
classicrocker883 Jul 1, 2025
09c6a73
update G68
classicrocker883 Jul 1, 2025
0e74e67
working G68
classicrocker883 Jul 12, 2025
b8a6033
relocate rotation_angle
classicrocker883 Jul 12, 2025
10126fc
relocate G68 stuff, remove from motion
classicrocker883 Jul 13, 2025
558a4b5
remove not necessary
classicrocker883 Jul 13, 2025
c6536e4
fix TERN
classicrocker883 Jul 13, 2025
74c788d
add way for DELTA or square bed
classicrocker883 Jul 13, 2025
003b136
relocate section CNC and safety
classicrocker883 Jul 13, 2025
f10483e
fix G68, G69, add G50, G51 (#3)
DerAndere1 Jul 22, 2025
e64387e
fix some issues, update G68, switch G50/51
classicrocker883 Jul 22, 2025
aa5f0c8
update features.ini
classicrocker883 Jul 22, 2025
4fff50a
add TERN0
classicrocker883 Jul 22, 2025
5f2aebc
revert G50/G51 naming, update Config_adv, add option to limit angle (…
classicrocker883 Jul 23, 2025
4f677de
add options for G51
classicrocker883 Jul 24, 2025
fdd899c
Make adjustments, add test
thinkyhead Aug 2, 2025
a378a20
float trig functions
thinkyhead Aug 2, 2025
f155c69
Merge branch 'bugfix-2.1.x' into pr/27945
thinkyhead Aug 2, 2025
166c167
more refinements
thinkyhead Aug 2, 2025
2deec18
cleanup
thinkyhead Aug 2, 2025
b5c4dec
more refinement
thinkyhead Aug 2, 2025
f99408f
fixes from comments, add flags
classicrocker883 Aug 4, 2025
13dc9d2
adjust gcode, add flag
classicrocker883 Aug 4, 2025
e6f42ec
use TERN0
classicrocker883 Aug 4, 2025
a222334
update get_destination_from_command function to make single move work
classicrocker883 Aug 5, 2025
2549b85
add in gcode.h
classicrocker883 Aug 5, 2025
51b7e56
cache cos() sin(), revert gcode.h private
classicrocker883 Aug 5, 2025
2e34887
update get_destination_from_command logic
classicrocker883 Aug 5, 2025
539c808
add sanitycheck, move struct
classicrocker883 Aug 5, 2025
0be7a6b
optimize invariant Z0
thinkyhead Aug 5, 2025
fa4ffd7
found it
thinkyhead Aug 5, 2025
b73504c
fix missing } and typo
classicrocker883 Aug 6, 2025
70558fd
update comments
classicrocker883 Aug 6, 2025
0cb6c91
Merge branch 'bugfix-2.1.x' into bugfix-2.1.x-June3
classicrocker883 Aug 21, 2025
91637f9
Merge branch 'bugfix-2.1.x' into bugfix-2.1.x-June3
classicrocker883 Sep 10, 2025
deb5694
Merge branch 'MarlinFirmware:bugfix-2.1.x' into bugfix-2.1.x-June3
classicrocker883 Sep 17, 2025
0d0ee8b
Merge branch 'bugfix-2.1.x' into bugfix-2.1.x-June3
classicrocker883 Oct 29, 2025
e4e0101
Merge branch 'bugfix-2.1.x' of https://github.com/MarlinFirmware/Marl…
classicrocker883 Dec 14, 2025
6b5415c
Fix missing #endif
classicrocker883 Dec 14, 2025
1b094d0
Merge branch 'bugfix-2.1.x' of https://github.com/MarlinFirmware/Marl…
classicrocker883 Dec 16, 2025
ef8753a
Merge branch 'bugfix-2.1.x' into bugfix-2.1.x-June3
classicrocker883 Dec 29, 2025
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
55 changes: 29 additions & 26 deletions Marlin/Configuration_adv.h
Original file line number Diff line number Diff line change
Expand Up @@ -2289,22 +2289,6 @@

//#define FAST_BUTTON_POLLING // Poll buttons at ~1kHz on 8-bit AVR. Set to 'false' for slow polling on 32-bit.

// @section safety

/**
* The watchdog hardware timer will do a reset and disable all outputs
* if the firmware gets too overloaded to read the temperature sensors.
*
* If you find that watchdog reboot causes your AVR board to hang forever,
* enable WATCHDOG_RESET_MANUAL to use a custom timer instead of WDTO.
* NOTE: This method is less reliable as it can only catch hangups while
* interrupts are enabled.
*/
#define USE_WATCHDOG
#if ENABLED(USE_WATCHDOG)
//#define WATCHDOG_RESET_MANUAL
#endif

// @section lcd

/**
Expand Down Expand Up @@ -3644,6 +3628,21 @@

// @section cnc

/**
* CNC Coordinate Systems
*
* Enables G53 and G54-G59.3 commands to select coordinate systems
* and G92.1 to reset the workspace to native machine space.
*/
//#define CNC_COORDINATE_SYSTEMS

/**
* Rotate Workspace
*
* Enables G68 command to rotate the workspace.
*/
//#define ROTATE_WORKSPACE

/**
* Spindle & Laser control
*
Expand Down Expand Up @@ -3911,6 +3910,20 @@

// @section safety

/**
* The watchdog hardware timer will do a reset and disable all outputs
* if the firmware gets too overloaded to read the temperature sensors.
*
* If you find that watchdog reboot causes your AVR board to hang forever,
* enable WATCHDOG_RESET_MANUAL to use a custom timer instead of WDTO.
* NOTE: This method is less reliable as it can only catch hangups while
* interrupts are enabled.
*/
#define USE_WATCHDOG
#if ENABLED(USE_WATCHDOG)
//#define WATCHDOG_RESET_MANUAL
#endif

/**
* Stepper Driver Anti-SNAFU Protection
*
Expand All @@ -3920,16 +3933,6 @@
*/
//#define DISABLE_DRIVER_SAFE_POWER_PROTECT

// @section cnc

/**
* CNC Coordinate Systems
*
* Enables G53 and G54-G59.3 commands to select coordinate systems
* and G92.1 to reset the workspace to native machine space.
*/
//#define CNC_COORDINATE_SYSTEMS

// @section security

/**
Expand Down
74 changes: 69 additions & 5 deletions Marlin/src/gcode/gcode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -100,6 +100,21 @@ relative_t GcodeSuite::axis_relative; // Init in constructor
xyz_pos_t GcodeSuite::coordinate_system[MAX_COORDINATE_SYSTEMS];
#endif

#if ENABLED(SCALE_WORKSPACE)
float GcodeSuite::scaling_center_x = 0.0f;
float GcodeSuite::scaling_center_y = 0.0f;
float GcodeSuite::scaling_center_z = 0.0f;
float GcodeSuite::scaling_factor_x = 1.0f;
float GcodeSuite::scaling_factor_y = 1.0f;
float GcodeSuite::scaling_factor_z = 1.0f;
#endif

#if ENABLED(ROTATE_WORKSPACE)
float GcodeSuite::rotation_center_x = 0.0f;
float GcodeSuite::rotation_center_y = 0.0f;
float GcodeSuite::rotation_angle = 0.0f;
#endif

void GcodeSuite::report_echo_start(const bool forReplay) { if (!forReplay) SERIAL_ECHO_START(); }
void GcodeSuite::report_heading(const bool forReplay, FSTR_P const fstr, const bool eol/*=true*/) {
if (forReplay) return;
Expand Down Expand Up @@ -175,15 +190,54 @@ void GcodeSuite::get_destination_from_command() {
LOOP_NUM_AXES(i) {
if ( (seen[i] = parser.seenval(AXIS_CHAR(i))) ) {
const float v = parser.value_axis_units((AxisEnum)i);
if (skip_move)
if (skip_move) {
#if ANY(SCALE_WORKSPACE, ROTATE_WORKSPACE)
raw_destination[i] = current_position[i];
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It looks to me like …

The current_position will contain a position that was already scaled and rotated. You must unrotate and unscale the current_position or set some flag that indicates that the raw_destination[i] coordinate is already rotated and scaled, and then don't rotate or scale that axis below.

Copy link
Contributor Author

@classicrocker883 classicrocker883 Aug 4, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I made flags that is set when there is rotation/scaling, not sure if thats the right approach but its there for now.

main concern is getting move commands to take a single one like G1 X100, using X+Y works fine, not sure what logic needs changing.

#else
destination[i] = current_position[i];
#endif
}
else {
#if ANY(SCALE_WORKSPACE, ROTATE_WORKSPACE)
raw_destination[i] = axis_is_relative(AxisEnum(i)) ? raw_destination[i] + v : LOGICAL_TO_NATIVE(v, i);
#else
destination[i] = axis_is_relative(AxisEnum(i)) ? current_position[i] + v : LOGICAL_TO_NATIVE(v, i);
#endif
}
}
else {
#if NONE(SCALE_WORKSPACE, ROTATE_WORKSPACE)
destination[i] = current_position[i];
else
destination[i] = axis_is_relative(AxisEnum(i)) ? current_position[i] + v : LOGICAL_TO_NATIVE(v, i);
#endif
}
else
destination[i] = current_position[i];
}

#if ANY(SCALE_WORKSPACE, ROTATE_WORKSPACE)
destination = raw_destination;
#endif

#if ENABLED(SCALE_WORKSPACE)
if (!(NEAR(scaling_factor_x, 1.0f) || NEAR(scaling_factor_y, 1.0f) || NEAR(scaling_factor_z, 1.0f))) {
destination.x = (raw_destination.x - scaling_center_x) * scaling_factor_x + scaling_center_x;
TERN_(HAS_Y_AXIS, destination.y = (raw_destination.y - scaling_center_y) * scaling_factor_y + scaling_center_y);
TERN_(HAS_Z_AXIS, destination.z = (raw_destination.z - scaling_center_z) * scaling_factor_z + scaling_center_z);
}
#endif

#if ENABLED(ROTATE_WORKSPACE)
if (!NEAR_ZERO(rotation_angle)) {
const float angle_rad = RADIANS(rotation_angle);
const float cos_angle = cos(angle_rad);
const float sin_angle = sin(angle_rad);

// Apply rotation
const float temp_x = destination.x - rotation_center_x;
const float temp_y = destination.y - rotation_center_y;
destination.x = temp_x * cos_angle - temp_y * sin_angle + rotation_center_x;
destination.y = temp_x * sin_angle + temp_y * cos_angle + rotation_center_y;
}
#endif

#if HAS_EXTRUDERS
// Get new E position, whether absolute or relative
if ( (seen.e = parser.seenval('E')) ) {
Expand Down Expand Up @@ -435,6 +489,11 @@ void GcodeSuite::process_parsed_command(bool no_ok/*=false*/) {
case 42: G42(); break; // G42: Coordinated move to a mesh point
#endif

#if ENABLED(SCALE_WORKSPACE)
case 50: G50(); break; // G50: Cancel Workspace Scaling
case 51: G51(); break; // G51: Set Workspace Scaling
#endif

#if ENABLED(CNC_COORDINATE_SYSTEMS)
case 53: G53(); break; // G53: (prefix) Apply native workspace
case 54: G54(); break; // G54: Switch to Workspace 1
Expand All @@ -450,6 +509,11 @@ void GcodeSuite::process_parsed_command(bool no_ok/*=false*/) {
case 61: G61(); break; // G61: Apply/restore saved coordinates.
#endif

#if ENABLED(ROTATE_WORKSPACE)
case 68: G68(); break; // G68: Set Workspace Rotation
case 69: G69(); break; // G69: Cancel Workspace Rotation
#endif

#if ALL(PTC_PROBE, PTC_BED)
case 76: G76(); break; // G76: Calibrate first layer compensation values
#endif
Expand Down
29 changes: 29 additions & 0 deletions Marlin/src/gcode/gcode.h
Original file line number Diff line number Diff line change
Expand Up @@ -64,8 +64,12 @@
* G35 - Read bed corners to help adjust bed screws: T<screw_thread> (Requires ASSISTED_TRAMMING)
* G38 - Probe in any direction using the Z_MIN_PROBE (Requires G38_PROBE_TARGET)
* G42 - Coordinated move to a mesh point (Requires MESH_BED_LEVELING, AUTO_BED_LEVELING_BLINEAR, or AUTO_BED_LEVELING_UBL)
* G50 - Set Workspace Scaling (Requires SCALE_WORKSPACE)
* G51 - Cancel Workspace Scaling (Requires SCALE_WORKSPACE)
* G60 - Save current position. (Requires SAVED_POSITIONS)
* G61 - Apply/Restore saved coordinates. (Requires SAVED_POSITIONS)
* G68 - Set Workspace Rotation (Requires ROTATE_WORKSPACE)
* G69 - Cancel Workspace Rotation (Requires ROTATE_WORKSPACE)
* G76 - Calibrate first layer temperature offsets. (Requires PTC_PROBE and PTC_BED)
* G80 - Cancel current motion mode (Requires GCODE_MOTION_MODES)
* G90 - Use Absolute Coordinates
Expand Down Expand Up @@ -431,6 +435,21 @@ class GcodeSuite {
static bool select_coordinate_system(const int8_t _new);
#endif

#if ENABLED(SCALE_WORKSPACE)
static float scaling_center_x;
static float scaling_center_y;
static float scaling_center_z;
static float scaling_factor_x;
static float scaling_factor_y;
static float scaling_factor_z;
#endif

#if ENABLED(ROTATE_WORKSPACE)
static float rotation_angle;
static float rotation_center_x;
static float rotation_center_y;
#endif

static millis_t previous_move_ms, max_inactive_time;
FORCE_INLINE static bool stepper_max_timed_out(const millis_t ms=millis()) {
return max_inactive_time && ELAPSED(ms, previous_move_ms, max_inactive_time);
Expand Down Expand Up @@ -609,6 +628,11 @@ class GcodeSuite {
static void G42();
#endif

#if ENABLED(SCALE_WORKSPACE)
static void G50();
static void G51();
#endif

#if ENABLED(CNC_COORDINATE_SYSTEMS)
static void G53();
static void G54();
Expand All @@ -628,6 +652,11 @@ class GcodeSuite {
static void G61(int8_t slot=-1);
#endif

#if ENABLED(ROTATE_WORKSPACE)
static void G68();
static void G69();
#endif

#if ENABLED(GCODE_MOTION_MODES)
static void G80();
#endif
Expand Down
9 changes: 7 additions & 2 deletions Marlin/src/gcode/geometry/G17-G19.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,8 +37,13 @@ inline void report_workspace_plane() {
}

inline void set_workspace_plane(const GcodeSuite::WorkspacePlane plane) {
gcode.workspace_plane = plane;
if (DEBUGGING(INFO)) report_workspace_plane();
if (TERN0(ROTATE_WORKSPACE, !NEAR_ZERO(gcode.rotation_angle))) {
SERIAL_ECHOLNPGM("Error: Workspace plane cannnot change while using workspace rotation.");
}
else {
gcode.workspace_plane = plane;
if (DEBUGGING(INFO)) report_workspace_plane();
}
}

/**
Expand Down
86 changes: 86 additions & 0 deletions Marlin/src/gcode/geometry/G50_G51.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,86 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/

#include "../../inc/MarlinConfigPre.h"

#if ENABLED(SCALE_WORKSPACE)

#include "../gcode.h"
#include "../../module/motion.h"

/**
* G50: Set Workspace Scaling
*
* Scale the current workspace coordinate system.
*
* Parameters:
* X<linear> X coordinate of the scaling center
* Y<linear> Y coordinate of the scaling center
* Z<linear> Z coordinate of the scaling center
* I<float> scaling factor for X axis
* J<float> scaling factor for Y axis
* K<float> scaling factor for Z axis
* P<float> scaling factor
*/
void GcodeSuite::G50() {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

oh i see. well I figure since G68 enables and G69 cancels, logically G50 would enable G51 cancel. but I suppose since this copies actual cnc stuff then i can revert

if (parser.seenval('P')) {
const float scaling_factor = parser.value_float();
scaling_factor_x = scaling_factor;
TERN_(HAS_Y_AXIS, scaling_factor_y = scaling_factor);
TERN_(HAS_Z_AXIS, scaling_factor_z = scaling_factor);
}
else {
if (parser.seenval('I'))
scaling_factor_x = parser.value_float();
#if HAS_Y_AXIS
if (parser.seenval('J'))
scaling_factor_y = parser.value_float();
#endif
#if HAS_Z_AXIS
if (parser.seenval('K'))
scaling_factor_z = parser.value_float();
#endif
}

scaling_center_x = parser.seenval('X') ? LOGICAL_TO_NATIVE(parser.value_axis_units(X_AXIS), X_AXIS) : current_position.x;
TERN_(HAS_Y_AXIS, scaling_center_y = parser.seenval('Y') ? LOGICAL_TO_NATIVE(parser.value_axis_units(Y_AXIS), Y_AXIS) : current_position.y);
TERN_(HAS_Z_AXIS, scaling_center_z = parser.seenval('Z') ? LOGICAL_TO_NATIVE(parser.value_axis_units(Z_AXIS), Z_AXIS) : current_position.z);

SERIAL_ECHOLNPGM("Workspace scaling set");
}

/**
* G51: Cancel Workspace Scaling
*/
void GcodeSuite::G51() {
scaling_factor_x = 1.0f;
scaling_center_x = 0.0f;
scaling_factor_y = 1.0f;
scaling_center_y = 0.0f;
#if HAS_Z_AXIS
scaling_factor_z = 1.0f;
scaling_center_z = 0.0f;
#endif
SERIAL_ECHOLNPGM("Workspace scaling canceled");
}

#endif // SCALE_WORKSPACE
4 changes: 4 additions & 0 deletions Marlin/src/gcode/geometry/G53-G59.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,10 @@
*/
bool GcodeSuite::select_coordinate_system(const int8_t _new) {
if (active_coordinate_system == _new) return false;
if (TERN0(ROTATE_WORKSPACE, !NEAR_ZERO(gcode.rotation_angle))) {
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It is very unlikely that the rotation_angle will be anything other than 0.0 when set explicitly to 0.0 so this can safely be !gcode.rotation_angle.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

surely you mean if there is rotation_angle?
if != 0 means there is rotation.

SERIAL_ECHOLNPGM("Cannot change workspace while workspace rotation is active");
return false;
}
active_coordinate_system = _new;
xyz_float_t new_offset{0};
if (WITHIN(_new, 0, MAX_COORDINATE_SYSTEMS - 1))
Expand Down
Loading