From a68aa255bc077074ec7b871548cccc7afb1fee9f Mon Sep 17 00:00:00 2001
From: Scott Lahteine <thinkyhead@users.noreply.github.com>
Date: Sun, 26 Jun 2022 22:24:59 -0500
Subject: [PATCH] =?UTF-8?q?=E2=99=BB=EF=B8=8F=20Planner=20flags=20refactor?=
MIME-Version: 1.0
Content-Type: text/plain; charset=UTF-8
Content-Transfer-Encoding: 8bit

---
 Marlin/src/gcode/motion/G2_G3.cpp   |   2 +-
 Marlin/src/gcode/motion/G6.cpp      |   2 +-
 Marlin/src/gcode/temp/M106_M107.cpp |   4 +-
 Marlin/src/module/planner.cpp       | 143 ++++++++++++++--------------
 Marlin/src/module/planner.h         | 122 ++++++++++++++----------
 Marlin/src/module/stepper.cpp       |  21 ++--
 Marlin/src/module/stepper.h         |   3 +-
 7 files changed, 160 insertions(+), 137 deletions(-)

diff --git a/Marlin/src/gcode/motion/G2_G3.cpp b/Marlin/src/gcode/motion/G2_G3.cpp
index 238ad8cf470..f2f4d54320d 100644
--- a/Marlin/src/gcode/motion/G2_G3.cpp
+++ b/Marlin/src/gcode/motion/G2_G3.cpp
@@ -286,7 +286,7 @@ void plan_arc(
         // Compute exact location by applying transformation matrix from initial radius vector(=-offset).
         // To reduce stuttering, the sin and cos could be computed at different times.
         // For now, compute both at the same time.
-        const float cos_Ti = cos(i * theta_per_segment), sin_Ti = sin(i * theta_per_segment);
+        const float Ti = i * theta_per_segment, cos_Ti = cos(Ti), sin_Ti = sin(Ti);
         rvec.a = -offset[0] * cos_Ti + offset[1] * sin_Ti;
         rvec.b = -offset[0] * sin_Ti - offset[1] * cos_Ti;
       }
diff --git a/Marlin/src/gcode/motion/G6.cpp b/Marlin/src/gcode/motion/G6.cpp
index a57a293e06f..fb6281707b4 100644
--- a/Marlin/src/gcode/motion/G6.cpp
+++ b/Marlin/src/gcode/motion/G6.cpp
@@ -50,7 +50,7 @@ void GcodeSuite::G6() {
   // No speed is set, can't schedule the move
   if (!planner.last_page_step_rate) return;
 
-  const page_idx_t page_idx = (page_idx_t) parser.value_ulong();
+  const page_idx_t page_idx = (page_idx_t)parser.value_ulong();
 
   uint16_t num_steps = DirectStepping::Config::TOTAL_STEPS;
   if (parser.seen('S')) num_steps = parser.value_ushort();
diff --git a/Marlin/src/gcode/temp/M106_M107.cpp b/Marlin/src/gcode/temp/M106_M107.cpp
index 98e87c415de..ae517c977b2 100644
--- a/Marlin/src/gcode/temp/M106_M107.cpp
+++ b/Marlin/src/gcode/temp/M106_M107.cpp
@@ -90,7 +90,7 @@ void GcodeSuite::M106() {
   // Set speed, with constraint
   thermalManager.set_fan_speed(pfan, speed);
 
-  TERN_(LASER_SYNCHRONOUS_M106_M107, planner.buffer_sync_block(BLOCK_FLAG_SYNC_FANS));
+  TERN_(LASER_SYNCHRONOUS_M106_M107, planner.buffer_sync_block(BLOCK_BIT_SYNC_FANS));
 
   if (TERN0(DUAL_X_CARRIAGE, idex_is_duplicating()))  // pfan == 0 when duplicating
     thermalManager.set_fan_speed(1 - pfan, speed);
@@ -111,7 +111,7 @@ void GcodeSuite::M107() {
   if (TERN0(DUAL_X_CARRIAGE, idex_is_duplicating()))  // pfan == 0 when duplicating
     thermalManager.set_fan_speed(1 - pfan, 0);
 
-  TERN_(LASER_SYNCHRONOUS_M106_M107, planner.buffer_sync_block(BLOCK_FLAG_SYNC_FANS));
+  TERN_(LASER_SYNCHRONOUS_M106_M107, planner.buffer_sync_block(BLOCK_BIT_SYNC_FANS));
 }
 
 #endif // HAS_FAN
diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp
index 9e773f0c8cb..2d0a7664399 100644
--- a/Marlin/src/module/planner.cpp
+++ b/Marlin/src/module/planner.cpp
@@ -739,7 +739,7 @@ block_t* Planner::get_current_block() {
     block_t * const block = &block_buffer[block_buffer_tail];
 
     // No trapezoid calculated? Don't execute yet.
-    if (TEST(block->flag, BLOCK_BIT_RECALCULATE)) return nullptr;
+    if (block->flag.recalculate) return nullptr;
 
     // We can't be sure how long an active block will take, so don't count it.
     TERN_(HAS_WIRED_LCD, block_buffer_runtime_us -= block->segment_time_us);
@@ -948,7 +948,7 @@ void Planner::reverse_pass_kernel(block_t * const current, const block_t * const
 
     // Compute maximum entry speed decelerating over the current block from its exit speed.
     // If not at the maximum entry speed, or the previous block entry speed changed
-    if (current->entry_speed_sqr != max_entry_speed_sqr || (next && TEST(next->flag, BLOCK_BIT_RECALCULATE))) {
+    if (current->entry_speed_sqr != max_entry_speed_sqr || (next && next->flag.recalculate)) {
 
       // If nominal length true, max junction speed is guaranteed to be reached.
       // If a block can de/ac-celerate from nominal speed to zero within the length of the block, then
@@ -958,14 +958,14 @@ void Planner::reverse_pass_kernel(block_t * const current, const block_t * const
       // the reverse and forward planners, the corresponding block junction speed will always be at the
       // the maximum junction speed and may always be ignored for any speed reduction checks.
 
-      const float new_entry_speed_sqr = TEST(current->flag, BLOCK_BIT_NOMINAL_LENGTH)
+      const float new_entry_speed_sqr = current->flag.nominal_length
         ? max_entry_speed_sqr
         : _MIN(max_entry_speed_sqr, max_allowable_speed_sqr(-current->acceleration, next ? next->entry_speed_sqr : sq(float(MINIMUM_PLANNER_SPEED)), current->millimeters));
       if (current->entry_speed_sqr != new_entry_speed_sqr) {
 
         // Need to recalculate the block speed - Mark it now, so the stepper
         // ISR does not consume the block before being recalculated
-        SBI(current->flag, BLOCK_BIT_RECALCULATE);
+        current->flag.recalculate = true;
 
         // But there is an inherent race condition here, as the block may have
         // become BUSY just before being marked RECALCULATE, so check for that!
@@ -973,7 +973,7 @@ void Planner::reverse_pass_kernel(block_t * const current, const block_t * const
           // Block became busy. Clear the RECALCULATE flag (no point in
           // recalculating BUSY blocks). And don't set its speed, as it can't
           // be updated at this time.
-          CBI(current->flag, BLOCK_BIT_RECALCULATE);
+          current->flag.recalculate = false;
         }
         else {
           // Block is not BUSY so this is ahead of the Stepper ISR:
@@ -1011,8 +1011,8 @@ void Planner::reverse_pass() {
     // Perform the reverse pass
     block_t *current = &block_buffer[block_index];
 
-    // Only consider non sync-and-page blocks
-    if (!(current->flag & BLOCK_MASK_SYNC) && !IS_PAGE(current)) {
+    // Only process movement blocks
+    if (current->is_move()) {
       reverse_pass_kernel(current, next);
       next = current;
     }
@@ -1041,8 +1041,7 @@ void Planner::forward_pass_kernel(const block_t * const previous, block_t * cons
     // change, adjust the entry speed accordingly. Entry speeds have already been reset,
     // maximized, and reverse-planned. If nominal length is set, max junction speed is
     // guaranteed to be reached. No need to recheck.
-    if (!TEST(previous->flag, BLOCK_BIT_NOMINAL_LENGTH) &&
-      previous->entry_speed_sqr < current->entry_speed_sqr) {
+    if (!previous->flag.nominal_length && previous->entry_speed_sqr < current->entry_speed_sqr) {
 
       // Compute the maximum allowable speed
       const float new_entry_speed_sqr = max_allowable_speed_sqr(-previous->acceleration, previous->entry_speed_sqr, previous->millimeters);
@@ -1052,7 +1051,7 @@ void Planner::forward_pass_kernel(const block_t * const previous, block_t * cons
 
         // Mark we need to recompute the trapezoidal shape, and do it now,
         // so the stepper ISR does not consume the block before being recalculated
-        SBI(current->flag, BLOCK_BIT_RECALCULATE);
+        current->flag.recalculate = true;
 
         // But there is an inherent race condition here, as the block maybe
         // became BUSY, just before it was marked as RECALCULATE, so check
@@ -1061,7 +1060,7 @@ void Planner::forward_pass_kernel(const block_t * const previous, block_t * cons
           // Block became busy. Clear the RECALCULATE flag (no point in
           //  recalculating BUSY blocks and don't set its speed, as it can't
           //  be updated at this time.
-          CBI(current->flag, BLOCK_BIT_RECALCULATE);
+          current->flag.recalculate = false;
         }
         else {
           // Block is not BUSY, we won the race against the Stepper ISR:
@@ -1106,8 +1105,8 @@ void Planner::forward_pass() {
     // Perform the forward pass
     block = &block_buffer[block_index];
 
-    // Skip SYNC and page blocks
-    if (!(block->flag & BLOCK_MASK_SYNC) && !IS_PAGE(block)) {
+    // Only process movement blocks
+    if (block->is_move()) {
       // If there's no previous block or the previous block is not
       // BUSY (thus, modifiable) run the forward_pass_kernel. Otherwise,
       // the previous block became BUSY, so assume the current block's
@@ -1131,9 +1130,10 @@ void Planner::recalculate_trapezoids() {
   // The tail may be changed by the ISR so get a local copy.
   uint8_t block_index = block_buffer_tail,
           head_block_index = block_buffer_head;
-  // Since there could be a sync block in the head of the queue, and the
+
+  // Since there could be non-move blocks in the head of the queue, and the
   // next loop must not recalculate the head block (as it needs to be
-  // specially handled), scan backwards to the first non-SYNC block.
+  // specially handled), scan backwards to the first move block.
   while (head_block_index != block_index) {
 
     // Go back (head always point to the first free block)
@@ -1142,8 +1142,8 @@ void Planner::recalculate_trapezoids() {
     // Get the pointer to the block
     block_t *prev = &block_buffer[prev_index];
 
-    // If not dealing with a sync block, we are done. The last block is not a SYNC block
-    if (!(prev->flag & BLOCK_MASK_SYNC)) break;
+    // It the block is a move, we're done with this loop
+    if (prev->is_move()) break;
 
     // Examine the previous block. This and all following are SYNC blocks
     head_block_index = prev_index;
@@ -1156,18 +1156,17 @@ void Planner::recalculate_trapezoids() {
 
     next = &block_buffer[block_index];
 
-    // Skip sync and page blocks
-    if (!(next->flag & BLOCK_MASK_SYNC) && !IS_PAGE(next)) {
+    // Only process movement blocks
+    if (next->is_move()) {
       next_entry_speed = SQRT(next->entry_speed_sqr);
 
       if (block) {
-        // Recalculate if current block entry or exit junction speed has changed.
-        if (TEST(block->flag, BLOCK_BIT_RECALCULATE) || TEST(next->flag, BLOCK_BIT_RECALCULATE)) {
 
-          // Mark the current block as RECALCULATE, to protect it from the Stepper ISR running it.
-          // Note that due to the above condition, there's a chance the current block isn't marked as
-          // RECALCULATE yet, but the next one is. That's the reason for the following line.
-          SBI(block->flag, BLOCK_BIT_RECALCULATE);
+        // If the next block is marked to RECALCULATE, also mark the previously-fetched one
+        if (next->flag.recalculate) block->flag.recalculate = true;
+
+        // Recalculate if current block entry or exit junction speed has changed.
+        if (block->flag.recalculate) {
 
           // But there is an inherent race condition here, as the block maybe
           // became BUSY, just before it was marked as RECALCULATE, so check
@@ -1190,7 +1189,7 @@ void Planner::recalculate_trapezoids() {
 
           // Reset current only to ensure next trapezoid is computed - The
           // stepper is free to use the block from now on.
-          CBI(block->flag, BLOCK_BIT_RECALCULATE);
+          block->flag.recalculate = false;
         }
       }
 
@@ -1204,10 +1203,10 @@ void Planner::recalculate_trapezoids() {
   // Last/newest block in buffer. Exit speed is set with MINIMUM_PLANNER_SPEED. Always recalculated.
   if (next) {
 
-    // Mark the next(last) block as RECALCULATE, to prevent the Stepper ISR running it.
+    // Mark the last block as RECALCULATE, to prevent the Stepper ISR running it.
     // As the last block is always recalculated here, there is a chance the block isn't
     // marked as RECALCULATE yet. That's the reason for the following line.
-    SBI(next->flag, BLOCK_BIT_RECALCULATE);
+    block->flag.recalculate = true;
 
     // But there is an inherent race condition here, as the block maybe
     // became BUSY, just before it was marked as RECALCULATE, so check
@@ -1229,7 +1228,7 @@ void Planner::recalculate_trapezoids() {
 
     // Reset next only to ensure its trapezoid is computed - The stepper is free to use
     // the block from now on.
-    CBI(next->flag, BLOCK_BIT_RECALCULATE);
+    next->flag.recalculate = false;
   }
 }
 
@@ -1454,7 +1453,7 @@ void Planner::check_axes_activity() {
     for (uint8_t b = block_buffer_tail; b != block_buffer_head; b = next_block_index(b)) {
       const block_t * const block = &block_buffer[b];
       if (LINEAR_AXIS_GANG(block->steps.x, || block->steps.y, || block->steps.z, || block->steps.i, || block->steps.j, || block->steps.k)) {
-        const float se = (float)block->steps.e / block->step_event_count * SQRT(block->nominal_speed_sqr); // mm/sec;
+        const float se = (float)block->steps.e / block->step_event_count * SQRT(block->nominal_speed_sqr); // mm/sec
         NOLESS(high, se);
       }
     }
@@ -1776,7 +1775,7 @@ void Planner::synchronize() { while (busy()) idle(); }
 bool Planner::_buffer_steps(const xyze_long_t &target
   OPTARG(HAS_POSITION_FLOAT, const xyze_pos_t &target_float)
   OPTARG(HAS_DIST_MM_ARG, const xyze_float_t &cart_dist_mm)
-  , feedRate_t fr_mm_s, const uint8_t extruder, const_float_t millimeters
+  , feedRate_t fr_mm_s, const uint8_t extruder, const_float_t millimeters/*=0.0*/
 ) {
 
   // Wait for the next available block
@@ -1790,10 +1789,11 @@ bool Planner::_buffer_steps(const xyze_long_t &target
 
   // Fill the block with the specified movement
   if (!_populate_block(block, false, target
-    OPTARG(HAS_POSITION_FLOAT, target_float)
-    OPTARG(HAS_DIST_MM_ARG, cart_dist_mm)
-    , fr_mm_s, extruder, millimeters
-  )) {
+        OPTARG(HAS_POSITION_FLOAT, target_float)
+        OPTARG(HAS_DIST_MM_ARG, cart_dist_mm)
+        , fr_mm_s, extruder, millimeters
+      )
+  ) {
     // Movement was not queued, probably because it was too short.
     //  Simply accept that as movement queued and done
     return true;
@@ -1847,24 +1847,8 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
   );
 
   /* <-- add a slash to enable
-    SERIAL_ECHOLNPGM(
-      "  _populate_block FR:", fr_mm_s,
-      " A:", target.a, " (", da, " steps)"
-      " B:", target.b, " (", db, " steps)"
-      " C:", target.c, " (", dc, " steps)"
-      #if HAS_I_AXIS
-        " " STR_I ":", target.i, " (", di, " steps)"
-      #endif
-      #if HAS_J_AXIS
-        " " STR_J ":", target.j, " (", dj, " steps)"
-      #endif
-      #if HAS_K_AXIS
-        " " STR_K ":", target.k, " (", dk, " steps)"
-      #endif
-      #if HAS_EXTRUDERS
-        " E:", target.e, " (", de, " steps)"
-      #endif
-    );
+    #define _ALINE(A) " " STR_##A  ":", target[_AXIS(A)], " (", int32_t(target[_AXIS(A)] - position[_AXIS(A)]), " steps)"
+    SERIAL_ECHOLNPGM("  _populate_block FR:", fr_mm_s, LOGICAL_AXIS_MAP(_ALINE));
   //*/
 
   #if EITHER(PREVENT_COLD_EXTRUSION, PREVENT_LENGTHY_EXTRUDE)
@@ -1954,7 +1938,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
   #endif
 
   // Clear all flags, including the "busy" bit
-  block->flag = 0x00;
+  block->flag.clear();
 
   // Set direction bits
   block->direction_bits = dm;
@@ -2358,7 +2342,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
   if (speed_factor < 1.0f) {
     current_speed *= speed_factor;
     block->nominal_rate *= speed_factor;
-    block->nominal_speed_sqr = block->nominal_speed_sqr * sq(speed_factor);
+    block->nominal_speed_sqr *= sq(speed_factor);
   }
 
   // Compute and limit the acceleration rate for the trapezoid generator.
@@ -2550,14 +2534,15 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
         vmax_junction_sqr = sq(float(MINIMUM_PLANNER_SPEED));
       }
       else {
-        NOLESS(junction_cos_theta, -0.999999f); // Check for numerical round-off to avoid divide by zero.
-
         // Convert delta vector to unit vector
         xyze_float_t junction_unit_vec = unit_vec - prev_unit_vec;
         normalize_junction_vector(junction_unit_vec);
 
-        const float junction_acceleration = limit_value_by_axis_maximum(block->acceleration, junction_unit_vec),
-                    sin_theta_d2 = SQRT(0.5f * (1.0f - junction_cos_theta)); // Trig half angle identity. Always positive.
+        const float junction_acceleration = limit_value_by_axis_maximum(block->acceleration, junction_unit_vec);
+
+        NOLESS(junction_cos_theta, -0.999999f); // Check for numerical round-off to avoid divide by zero.
+
+        const float sin_theta_d2 = SQRT(0.5f * (1.0f - junction_cos_theta)); // Trig half angle identity. Always positive.
 
         vmax_junction_sqr = junction_acceleration * junction_deviation_mm * sin_theta_d2 / (1.0f - sin_theta_d2);
 
@@ -2787,7 +2772,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
   // block nominal speed limits both the current and next maximum junction speeds. Hence, in both
   // the reverse and forward planners, the corresponding block junction speed will always be at the
   // the maximum junction speed and may always be ignored for any speed reduction checks.
-  block->flag |= block->nominal_speed_sqr <= v_allowable_sqr ? BLOCK_FLAG_RECALCULATE | BLOCK_FLAG_NOMINAL_LENGTH : BLOCK_FLAG_RECALCULATE;
+  block->flag.set_nominal(block->nominal_speed_sqr <= v_allowable_sqr);
 
   // Update previous path unit_vector and nominal speed
   previous_speed = current_speed;
@@ -2812,9 +2797,9 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
  * Add a block to the buffer that just updates the position,
  * or in case of LASER_SYNCHRONOUS_M106_M107 the fan PWM
  */
-void Planner::buffer_sync_block(TERN_(LASER_SYNCHRONOUS_M106_M107, uint8_t sync_flag)) {
+void Planner::buffer_sync_block(TERN_(LASER_SYNCHRONOUS_M106_M107, const BlockFlagBit sync_flag/*=BLOCK_BIT_SYNC_POSITION*/)) {
   #if DISABLED(LASER_SYNCHRONOUS_M106_M107)
-    constexpr uint8_t sync_flag = BLOCK_FLAG_SYNC_POSITION;
+    constexpr BlockFlagBit sync_flag = BLOCK_BIT_SYNC_POSITION;
   #endif
 
   // Wait for the next available block
@@ -2824,7 +2809,7 @@ void Planner::buffer_sync_block(TERN_(LASER_SYNCHRONOUS_M106_M107, uint8_t sync_
   // Clear block
   memset(block, 0, sizeof(block_t));
 
-  block->flag = sync_flag;
+  block->flag.apply(sync_flag);
 
   block->position = position;
   #if ENABLED(BACKLASH_COMPENSATION)
@@ -2954,8 +2939,8 @@ bool Planner::buffer_segment(const abce_pos_t &abce
   if (!_buffer_steps(target
       OPTARG(HAS_POSITION_FLOAT, target_float)
       OPTARG(HAS_DIST_MM_ARG, cart_dist_mm)
-      , fr_mm_s, extruder, millimeters)
-  ) return false;
+      , fr_mm_s, extruder, millimeters
+  )) return false;
 
   stepper.wake_up();
   return true;
@@ -3020,6 +3005,14 @@ bool Planner::buffer_line(const xyze_pos_t &cart, const_feedRate_t fr_mm_s, cons
 
 #if ENABLED(DIRECT_STEPPING)
 
+  /**
+   * @brief Add a direct stepping page block to the buffer
+   *        and wake up the Stepper ISR to process it.
+   *
+   * @param page_idx Page index provided by G6 I<index>
+   * @param extruder The extruder to use in the move
+   * @param num_steps Number of steps to process in the ISR
+   */
   void Planner::buffer_page(const page_idx_t page_idx, const uint8_t extruder, const uint16_t num_steps) {
     if (!last_page_step_rate) {
       kill(GET_TEXT_F(MSG_BAD_PAGE_SPEED));
@@ -3029,7 +3022,7 @@ bool Planner::buffer_line(const xyze_pos_t &cart, const_feedRate_t fr_mm_s, cons
     uint8_t next_buffer_head;
     block_t * const block = get_next_free_block(next_buffer_head);
 
-    block->flag = BLOCK_FLAG_IS_PAGE;
+    block->flag.reset(BLOCK_BIT_PAGE);
 
     #if HAS_FAN
       FANS_LOOP(i) block->fan_speed[i] = thermalManager.fan_speed[i];
@@ -3114,6 +3107,12 @@ void Planner::set_machine_position_mm(const abce_pos_t &abce) {
   }
 }
 
+/**
+ * @brief Set the Planner position in mm
+ * @details Set the Planner position from a native machine position in mm
+ *
+ * @param xyze A native (Cartesian) machine position
+ */
 void Planner::set_position_mm(const xyze_pos_t &xyze) {
   xyze_pos_t machine = xyze;
   TERN_(HAS_POSITION_MODIFIERS, apply_modifiers(machine, true));
@@ -3149,7 +3148,13 @@ void Planner::set_position_mm(const xyze_pos_t &xyze) {
 
 #endif
 
-// Recalculate the steps/s^2 acceleration rates, based on the mm/s^2
+/**
+ * @brief Recalculate the steps/s^2 acceleration rates, based on the mm/s^2
+ * @details Update planner movement factors after a change to certain settings:
+ *          - max_acceleration_steps_per_s2 from settings max_acceleration_mm_per_s2 * axis_steps_per_mm (M201, M92)
+ *          - acceleration_long_cutoff based on the largest max_acceleration_steps_per_s2 (M201)
+ *          - max_e_jerk for all extruders based on junction_deviation_mm (M205 J)
+ */
 void Planner::reset_acceleration_rates() {
   uint32_t highest_rate = 1;
   LOOP_DISTINCT_AXES(i) {
@@ -3162,8 +3167,8 @@ void Planner::reset_acceleration_rates() {
 }
 
 /**
- * Recalculate 'position' and 'mm_per_step'.
- * Must be called whenever settings.axis_steps_per_mm changes!
+ * @brief Recalculate 'position' and 'mm_per_step'.
+ * @details Required whenever settings.axis_steps_per_mm changes!
  */
 void Planner::refresh_positioning() {
   LOOP_DISTINCT_AXES(i) mm_per_step[i] = 1.0f / settings.axis_steps_per_mm[i];
diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h
index 7b8908a4dac..c600b9e50de 100644
--- a/Marlin/src/module/planner.h
+++ b/Marlin/src/module/planner.h
@@ -70,9 +70,6 @@
 
 #if ENABLED(DIRECT_STEPPING)
   #include "../feature/direct_stepping.h"
-  #define IS_PAGE(B) TEST(B->flag, BLOCK_BIT_IS_PAGE)
-#else
-  #define IS_PAGE(B) false
 #endif
 
 #if ENABLED(EXTERNAL_CLOSED_LOOP_CONTROLLER)
@@ -91,47 +88,6 @@
   #define HAS_DIST_MM_ARG 1
 #endif
 
-enum BlockFlagBit : char {
-  // Recalculate trapezoids on entry junction. For optimization.
-  BLOCK_BIT_RECALCULATE,
-
-  // Nominal speed always reached.
-  // i.e., The segment is long enough, so the nominal speed is reachable if accelerating
-  // from a safe speed (in consideration of jerking from zero speed).
-  BLOCK_BIT_NOMINAL_LENGTH,
-
-  // The block is segment 2+ of a longer move
-  BLOCK_BIT_CONTINUED,
-
-  // Sync the stepper counts from the block
-  BLOCK_BIT_SYNC_POSITION
-
-  // Direct stepping page
-  #if ENABLED(DIRECT_STEPPING)
-    , BLOCK_BIT_IS_PAGE
-  #endif
-
-  // Sync the fan speeds from the block
-  #if ENABLED(LASER_SYNCHRONOUS_M106_M107)
-    , BLOCK_BIT_SYNC_FANS
-  #endif
-};
-
-enum BlockFlag : char {
-    BLOCK_FLAG_RECALCULATE          = _BV(BLOCK_BIT_RECALCULATE)
-  , BLOCK_FLAG_NOMINAL_LENGTH       = _BV(BLOCK_BIT_NOMINAL_LENGTH)
-  , BLOCK_FLAG_CONTINUED            = _BV(BLOCK_BIT_CONTINUED)
-  , BLOCK_FLAG_SYNC_POSITION        = _BV(BLOCK_BIT_SYNC_POSITION)
-  #if ENABLED(DIRECT_STEPPING)
-    , BLOCK_FLAG_IS_PAGE            = _BV(BLOCK_BIT_IS_PAGE)
-  #endif
-  #if ENABLED(LASER_SYNCHRONOUS_M106_M107)
-    , BLOCK_FLAG_SYNC_FANS          = _BV(BLOCK_BIT_SYNC_FANS)
-  #endif
-};
-
-#define BLOCK_MASK_SYNC ( BLOCK_FLAG_SYNC_POSITION | TERN0(LASER_SYNCHRONOUS_M106_M107, BLOCK_FLAG_SYNC_FANS) )
-
 #if ENABLED(LASER_POWER_INLINE)
 
   typedef struct {
@@ -157,17 +113,83 @@ enum BlockFlag : char {
 #endif
 
 /**
- * struct block_t
- *
- * A single entry in the planner buffer.
- * Tracks linear movement over multiple axes.
+ * Planner block flags as boolean bit fields
+ */
+enum BlockFlagBit {
+  // Recalculate trapezoids on entry junction. For optimization.
+  BLOCK_BIT_RECALCULATE,
+
+  // Nominal speed always reached.
+  // i.e., The segment is long enough, so the nominal speed is reachable if accelerating
+  // from a safe speed (in consideration of jerking from zero speed).
+  BLOCK_BIT_NOMINAL_LENGTH,
+
+  // The block is segment 2+ of a longer move
+  BLOCK_BIT_CONTINUED,
+
+  // Sync the stepper counts from the block
+  BLOCK_BIT_SYNC_POSITION
+
+  // Direct stepping page
+  #if ENABLED(DIRECT_STEPPING)
+    , BLOCK_BIT_PAGE
+  #endif
+
+  // Sync the fan speeds from the block
+  #if ENABLED(LASER_SYNCHRONOUS_M106_M107)
+    , BLOCK_BIT_SYNC_FANS
+  #endif
+};
+
+/**
+ * Planner block flags as boolean bit fields
+ */
+typedef struct {
+  union {
+    uint8_t bits;
+
+    struct {
+      bool recalculate:1;
+
+      bool nominal_length:1;
+
+      bool continued:1;
+
+      bool sync_position:1;
+
+      #if ENABLED(DIRECT_STEPPING)
+        bool page:1;
+      #endif
+
+      #if ENABLED(LASER_SYNCHRONOUS_M106_M107)
+        bool sync_fans:1;
+      #endif
+    };
+  };
+
+  void clear() volatile { bits = 0; }
+  void apply(const uint8_t f) volatile { bits |= f; }
+  void apply(const BlockFlagBit b) volatile { SBI(bits, b); }
+  void reset(const BlockFlagBit b) volatile { bits = _BV(b); }
+  void set_nominal(const bool n) volatile { recalculate = true; if (n) nominal_length = true; }
+
+} block_flags_t;
+
+/**
+ * A single entry in the planner buffer, used to set up and
+ * track a coordinated linear motion for one or more axes.
  *
  * The "nominal" values are as-specified by G-code, and
  * may never actually be reached due to acceleration limits.
  */
 typedef struct block_t {
 
-  volatile uint8_t flag;                    // Block flags (See BlockFlag enum above) - Modified by ISR and main thread!
+  volatile block_flags_t flag;              // Block flags
+
+  volatile bool is_fan_sync() { return TERN0(LASER_SYNCHRONOUS_M106_M107, flag.sync_fans); }
+  volatile bool is_sync() { return flag.sync_position || is_fan_sync(); }
+  volatile bool is_page() { return TERN0(DIRECT_STEPPING, flag.page); }
+  volatile bool is_move() { return !(is_sync() || is_page()); }
 
   // Fields used by the motion planner to manage acceleration
   float nominal_speed_sqr,                  // The nominal speed for this block in (mm/sec)^2
@@ -758,7 +780,7 @@ class Planner {
      * case of LASER_SYNCHRONOUS_M106_M107 the fan pwm
      */
     static void buffer_sync_block(
-      TERN_(LASER_SYNCHRONOUS_M106_M107, uint8_t sync_flag=BLOCK_FLAG_SYNC_POSITION)
+      TERN_(LASER_SYNCHRONOUS_M106_M107, const BlockFlagBit flag=BLOCK_BIT_SYNC_POSITION)
     );
 
   #if IS_KINEMATIC
diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp
index 1e86040db63..7fd8f17fa42 100644
--- a/Marlin/src/module/stepper.cpp
+++ b/Marlin/src/module/stepper.cpp
@@ -1682,7 +1682,7 @@ void Stepper::pulse_phase_isr() {
     }while(0)
 
     // Direct Stepping page?
-    const bool is_page = IS_PAGE(current_block);
+    const bool is_page = current_block->is_page();
 
     #if ENABLED(DIRECT_STEPPING)
       // Direct stepping is currently not ready for HAS_I_AXIS
@@ -1933,7 +1933,7 @@ uint32_t Stepper::block_phase_isr() {
             count_position[_AXIS(AXIS)] += page_step_state.bd[_AXIS(AXIS)] * count_direction[_AXIS(AXIS)];
         #endif
 
-        if (IS_PAGE(current_block)) {
+        if (current_block->is_page()) {
           PAGE_SEGMENT_UPDATE_POS(X);
           PAGE_SEGMENT_UPDATE_POS(Y);
           PAGE_SEGMENT_UPDATE_POS(Z);
@@ -2123,16 +2123,13 @@ uint32_t Stepper::block_phase_isr() {
     if ((current_block = planner.get_current_block())) {
 
       // Sync block? Sync the stepper counts or fan speeds and return
-      while (current_block->flag & BLOCK_MASK_SYNC) {
+      while (current_block->is_sync()) {
 
-        #if ENABLED(LASER_SYNCHRONOUS_M106_M107)
-          const bool is_sync_fans = TEST(current_block->flag, BLOCK_BIT_SYNC_FANS);
-          if (is_sync_fans) planner.sync_fan_speeds(current_block->fan_speed);
-        #else
-          constexpr bool is_sync_fans = false;
-        #endif
-
-        if (!is_sync_fans) _set_position(current_block->position);
+        if (current_block->is_fan_sync()) {
+          TERN_(LASER_SYNCHRONOUS_M106_M107, planner.sync_fan_speeds(current_block->fan_speed));
+        }
+        else
+          _set_position(current_block->position);
 
         discard_current_block();
 
@@ -2152,7 +2149,7 @@ uint32_t Stepper::block_phase_isr() {
       #endif
 
       #if ENABLED(DIRECT_STEPPING)
-        if (IS_PAGE(current_block)) {
+        if (current_block->is_page()) {
           page_step_state.segment_steps = 0;
           page_step_state.segment_idx = 0;
           page_step_state.page = page_manager.get_page(current_block->page_idx);
diff --git a/Marlin/src/module/stepper.h b/Marlin/src/module/stepper.h
index dac04d69b5e..2267ae829d3 100644
--- a/Marlin/src/module/stepper.h
+++ b/Marlin/src/module/stepper.h
@@ -511,8 +511,7 @@ class Stepper {
     // Discard current block and free any resources
     FORCE_INLINE static void discard_current_block() {
       #if ENABLED(DIRECT_STEPPING)
-        if (IS_PAGE(current_block))
-          page_manager.free_page(current_block->page_idx);
+        if (current_block->is_page()) page_manager.free_page(current_block->page_idx);
       #endif
       current_block = nullptr;
       axis_did_move = 0;