Skip to content
Open
Show file tree
Hide file tree
Changes from 5 commits
Commits
Show all changes
39 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
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
5 changes: 5 additions & 0 deletions Marlin/Configuration_adv.h
Original file line number Diff line number Diff line change
Expand Up @@ -2592,6 +2592,11 @@
*/
//#define DIRECT_STEPPING

/**
* Rotate Workspace
*/
//#define ROTATE_WORKSPACE

/**
* G38 Probe Target
*
Expand Down
4 changes: 4 additions & 0 deletions Marlin/src/gcode/gcode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -450,6 +450,10 @@ 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
#endif

#if ALL(PTC_PROBE, PTC_BED)
case 76: G76(); break; // G76: Calibrate first layer compensation values
#endif
Expand Down
5 changes: 5 additions & 0 deletions Marlin/src/gcode/gcode.h
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,7 @@
* G42 - Coordinated move to a mesh point (Requires MESH_BED_LEVELING, AUTO_BED_LEVELING_BLINEAR, or AUTO_BED_LEVELING_UBL)
* G60 - Save current position. (Requires SAVED_POSITIONS)
* G61 - Apply/Restore saved coordinates. (Requires SAVED_POSITIONS)
* G68 - Set Workspace Rotation
* 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 @@ -628,6 +629,10 @@ class GcodeSuite {
static void G61(int8_t slot=-1);
#endif

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

#if ENABLED(GCODE_MOTION_MODES)
static void G80();
#endif
Expand Down
86 changes: 86 additions & 0 deletions Marlin/src/gcode/motion/G68.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(ROTATE_WORKSPACE)

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

/**
* G68: Set Workspace Rotation
*
* Set the rotation (about Z axis) for the current workspace (begins at 0).
*
* Parameters:
* P<index> Workspace index (Optional, default: current)
* R<deg> Rotation angle in degrees (Required)
*
* Example:
* G68 R45 ; Rotate current workspace by 45°
* G68 R-30 ; Rotate current workspace by -30°
* G68 P2 R90 ; Rotate workspace 2 by 90° around
* G68 P1 ; Set active workspace to 1 (no rotation change)
*
* NOTES:
* - Only rotation is set. No translation/offset is changed.
* - All subsequent moves are rotated by the specified angle.
*/
void GcodeSuite::G68() {
const int P = parser.seenval('P') ? parser.value_int() : active_workspace;
float rotation_angle[MAX_COORDINATE_SYSTEMS] = { 0 };
float r_angle = rotation_angle[active_workspace];

if (parser.seenval('P')) {
if (P < 0 || P >= MAX_COORDINATE_SYSTEMS) {
SERIAL_ECHOLNPGM("Invalid workspace index.");
return;
}
active_workspace = P;
SERIAL_ECHOLN("Active workspace set to ", P, ".");
}

if (parser.seenval('P') && !parser.seenval('R')) {
return;
}

if (parser.seenval('R')) {
// Parse R parameter (rotation angle)
r_angle = parser.value_float();
rotation_angle[active_workspace] = r_angle;

float center_x = rotation_center_x;
center_x = (X_MIN_POS + X_MAX_POS) * 0.5f;
rotation_center_x = center_x;

float center_y = rotation_center_y;
center_y = (Y_MIN_POS + Y_MAX_POS) * 0.5f;
rotation_center_y = center_y;
SERIAL_ECHOLN("Workspace ", P, " rotation set to: ", r_angle, " deg.");
}
else {
SERIAL_ECHOLNPGM("Missing R parameter (rotation angle).");
}
}

#endif // ROTATE_WORKSPACE
34 changes: 34 additions & 0 deletions Marlin/src/module/motion.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -137,6 +137,30 @@ xyze_pos_t destination; // {0}
}
#endif

#if ENABLED(ROTATE_WORKSPACE)
uint8_t active_workspace = 0;
float rotation_center_x = 0.0;
float rotation_center_y = 0.0;

void apply_workspace_rotation() {
// Apply translation to origin
float temp_x = destination[X_AXIS] - rotation_center_x;
float temp_y = destination[Y_AXIS] - rotation_center_y;

const float angle_rad = RADIANS(rotation_angle[active_workspace]);
const float cos_angle = cos(angle_rad);
const float sin_angle = sin(angle_rad);

// Apply rotation
float rotated_x = temp_x * cos_angle - temp_y * sin_angle;
float rotated_y = temp_x * sin_angle + temp_y * cos_angle;

// Apply translation back
destination[X_AXIS] = rotated_x + rotation_center_x;
destination[Y_AXIS] = rotated_y + rotation_center_y;
}
#endif

// The feedrate for the current move, often used as the default if
// no other feedrate is specified. Overridden for special moves.
// Set by the last G0 through G5 command's "F" parameter.
Expand Down Expand Up @@ -1897,6 +1921,10 @@ float get_move_distance(const xyze_pos_t &diff OPTARG(HAS_ROTATIONAL_AXES, bool
void prepare_line_to_destination() {
apply_motion_limits(destination);

#if ENABLED(ROTATE_WORKSPACE)
apply_workspace_rotation();
#endif

#if ANY(PREVENT_COLD_EXTRUSION, PREVENT_LENGTHY_EXTRUDE)

if (!DEBUGGING(DRYRUN) && destination.e != current_position.e) {
Expand Down Expand Up @@ -1947,6 +1975,12 @@ void prepare_line_to_destination() {
#endif
) return;

if (DEBUGGING(LEVELING)) DEBUG_POS("prepare_line_to_destination", destination);

TERN_(HAS_POSITION_MODIFIERS, planner.apply_modifiers(destination));

planner.buffer_line(destination, MMS_SCALED(feedrate_mm_s));

current_position = destination;
}

Expand Down
11 changes: 11 additions & 0 deletions Marlin/src/module/motion.h
Original file line number Diff line number Diff line change
Expand Up @@ -62,6 +62,17 @@ extern xyz_pos_t cartes;
extern abce_pos_t delta;
#endif

#if ENABLED(ROTATE_WORKSPACE)
#include "../gcode/gcode.h"

extern uint8_t active_workspace;
extern float rotation_angle[MAX_COORDINATE_SYSTEMS]; // Store rotation for each workspace
extern float rotation_center_x;
extern float rotation_center_y;

void apply_workspace_rotation();
#endif

#if HAS_ABL_NOT_UBL
extern feedRate_t xy_probe_feedrate_mm_s;
#define XY_PROBE_FEEDRATE_MM_S xy_probe_feedrate_mm_s
Expand Down
1 change: 1 addition & 0 deletions ini/features.ini
Original file line number Diff line number Diff line change
Expand Up @@ -231,6 +231,7 @@ USE_CONTROLLER_FAN = build_src_filter=+<src/feature/controll
HAS_COOLER|LASER_COOLANT_FLOW_METER = build_src_filter=+<src/feature/cooler.cpp>
HAS_MOTOR_CURRENT_DAC = build_src_filter=+<src/feature/dac>
DIRECT_STEPPING = build_src_filter=+<src/feature/direct_stepping.cpp> +<src/gcode/motion/G6.cpp>
ROTATE_WORKSPACE = build_src_filter=+<src/gcode/motion/G68.cpp>
EMERGENCY_PARSER = build_src_filter=+<src/feature/e_parser.cpp> -<src/gcode/control/M108_*.cpp>
EASYTHREED_UI = build_src_filter=+<src/feature/easythreed_ui.cpp>
I2C_POSITION_ENCODERS = build_src_filter=+<src/feature/encoder_i2c.cpp>
Expand Down